This commit is contained in:
NeoZng 2023-06-27 22:28:48 +08:00
commit 2404edd4eb
49 changed files with 827 additions and 383 deletions

View File

@ -69,6 +69,7 @@
#define configUSE_16_BIT_TICKS 0 #define configUSE_16_BIT_TICKS 0
#define configUSE_MUTEXES 1 #define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8 #define configQUEUE_REGISTRY_SIZE 8
#define configUSE_COUNTING_SEMAPHORES 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1 #define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
/* USER CODE BEGIN MESSAGE_BUFFER_LENGTH_TYPE */ /* USER CODE BEGIN MESSAGE_BUFFER_LENGTH_TYPE */
/* Defaults to size_t for backward compatibility, but can be changed /* Defaults to size_t for backward compatibility, but can be changed

View File

@ -52,6 +52,7 @@ void MemManage_Handler(void);
void BusFault_Handler(void); void BusFault_Handler(void);
void UsageFault_Handler(void); void UsageFault_Handler(void);
void DebugMon_Handler(void); void DebugMon_Handler(void);
void FLASH_IRQHandler(void);
void EXTI3_IRQHandler(void); void EXTI3_IRQHandler(void);
void EXTI4_IRQHandler(void); void EXTI4_IRQHandler(void);
void DMA1_Stream1_IRQHandler(void); void DMA1_Stream1_IRQHandler(void);

View File

@ -119,6 +119,7 @@ bsp/can/bsp_can.c \
bsp/usart/bsp_usart.c \ bsp/usart/bsp_usart.c \
bsp/usb/bsp_usb.c \ bsp/usb/bsp_usb.c \
bsp/log/bsp_log.c \ bsp/log/bsp_log.c \
bsp/flash/bsp_flash.c \
bsp/bsp_init.c \ bsp/bsp_init.c \
modules/algorithm/controller.c \ modules/algorithm/controller.c \
modules/algorithm/kalman_filter.c \ modules/algorithm/kalman_filter.c \
@ -152,6 +153,7 @@ modules/can_comm/can_comm.c \
modules/message_center/message_center.c \ modules/message_center/message_center.c \
modules/daemon/daemon.c \ modules/daemon/daemon.c \
modules/vofa/vofa.c \ modules/vofa/vofa.c \
modules/alarm/buzzer.c \
application/gimbal/gimbal.c \ application/gimbal/gimbal.c \
application/chassis/chassis.c \ application/chassis/chassis.c \
application/shoot/shoot.c \ application/shoot/shoot.c \
@ -197,7 +199,7 @@ FPU = -mfpu=fpv4-sp-d16
FLOAT-ABI = -mfloat-abi=hard FLOAT-ABI = -mfloat-abi=hard
# mcu # mcu
MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI) MCU = $(CPU) -mthumb -mthumb-interwork $(FPU) $(FLOAT-ABI)
# macros for gcc # macros for gcc
# AS defines # AS defines
@ -209,7 +211,9 @@ C_DEFS = \
-DSTM32F407xx \ -DSTM32F407xx \
-DARM_MATH_CM4 \ -DARM_MATH_CM4 \
-DARM_MATH_MATRIX_CHECK \ -DARM_MATH_MATRIX_CHECK \
-DARM_MATH_ROUNDING -DARM_MATH_ROUNDING \
-DARM_MATH_LOOPUNROLL \
-DISABLEFLOAT16
# AS includes # AS includes
AS_INCLUDES = \ AS_INCLUDES = \
@ -244,6 +248,7 @@ C_INCLUDES = \
-Ibsp/spi \ -Ibsp/spi \
-Ibsp/iic \ -Ibsp/iic \
-Ibsp/log \ -Ibsp/log \
-Ibsp/flash \
-Ibsp/pwm \ -Ibsp/pwm \
-Ibsp/bsp_legacy_support \ -Ibsp/bsp_legacy_support \
-Ibsp \ -Ibsp \
@ -268,13 +273,14 @@ C_INCLUDES = \
-Imodules/message_center \ -Imodules/message_center \
-Imodules/daemon \ -Imodules/daemon \
-Imodules/vofa \ -Imodules/vofa \
-Imodules/alarm \
-Imodules -Imodules
# compile gcc flags # compile gcc flags
ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -fdata-sections -ffunction-sections ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -fdata-sections -ffunction-sections
CFLAGS += $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -fdata-sections -ffunction-sections CFLAGS += $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -fdata-sections -ffunction-sections -fmessage-length=0
ifeq ($(DEBUG), 1) ifeq ($(DEBUG), 1)
CFLAGS += -g -gdwarf-2 CFLAGS += -g -gdwarf-2
@ -296,7 +302,7 @@ LIBS = -lc -lm -lnosys \
-l:libCMSISDSP.a -l:libCMSISDSP.a
LIBDIR = \ LIBDIR = \
-LMiddlewares/ST/ARM/DSP/Lib -LMiddlewares/ST/ARM/DSP/Lib
LDFLAGS = $(MCU) -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections LDFLAGS = $(MCU) -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections -flto
# default action: build all # default action: build all
all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
@ -336,7 +342,7 @@ $(BUILD_DIR):
# clean up # clean up
####################################### #######################################
clean: clean:
rd /s/q $(BUILD_DIR) rd $(BUILD_DIR) /s/q
####################################### #######################################

View File

@ -123,9 +123,9 @@ void MX_FREERTOS_Init(void)
void StartDefaultTask(void const *argument) void StartDefaultTask(void const *argument)
{ {
/* init code for USB_DEVICE */ /* init code for USB_DEVICE */
MX_USB_DEVICE_Init(); // USB??? MX_USB_DEVICE_Init(); // 默认usb启动任务的位置
/* USER CODE BEGIN StartDefaultTask */ /* USER CODE BEGIN StartDefaultTask */
vTaskDelete(NULL); // ??????,????CPU vTaskDelete(NULL); // 避免空置和切换占用cpu
/* USER CODE END StartDefaultTask */ /* USER CODE END StartDefaultTask */
} }

View File

@ -36,6 +36,7 @@
/* Private includes ----------------------------------------------------------*/ /* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */ /* USER CODE BEGIN Includes */
#include "robot.h" #include "robot.h"
#include "bsp_log.h"
/* USER CODE END Includes */ /* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/ /* Private typedef -----------------------------------------------------------*/
@ -120,6 +121,7 @@ int main(void)
MX_DAC_Init(); MX_DAC_Init();
/* USER CODE BEGIN 2 */ /* USER CODE BEGIN 2 */
RobotInit(); // 唯一的初始化函数 RobotInit(); // 唯一的初始化函数
LOGINFO("[main] SystemInit() and RobotInit() done");
/* USER CODE END 2 */ /* USER CODE END 2 */
/* Call init function for freertos objects (in freertos.c) */ /* Call init function for freertos objects (in freertos.c) */

View File

@ -73,6 +73,11 @@ void HAL_MspInit(void)
/* PendSV_IRQn interrupt configuration */ /* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0);
/* Peripheral interrupt init */
/* FLASH_IRQn interrupt configuration */
HAL_NVIC_SetPriority(FLASH_IRQn, 6, 0);
HAL_NVIC_EnableIRQ(FLASH_IRQn);
/* USER CODE BEGIN MspInit 1 */ /* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */ /* USER CODE END MspInit 1 */

View File

@ -183,6 +183,20 @@ void DebugMon_Handler(void)
/* please refer to the startup file (startup_stm32f4xx.s). */ /* please refer to the startup file (startup_stm32f4xx.s). */
/******************************************************************************/ /******************************************************************************/
/**
* @brief This function handles Flash global interrupt.
*/
void FLASH_IRQHandler(void)
{
/* USER CODE BEGIN FLASH_IRQn 0 */
/* USER CODE END FLASH_IRQn 0 */
HAL_FLASH_IRQHandler();
/* USER CODE BEGIN FLASH_IRQn 1 */
/* USER CODE END FLASH_IRQn 1 */
}
/** /**
* @brief This function handles EXTI line3 interrupt. * @brief This function handles EXTI line3 interrupt.
*/ */

View File

@ -27,7 +27,7 @@
#include "usbd_cdc.h" #include "usbd_cdc.h"
/* USER CODE BEGIN Includes */ /* USER CODE BEGIN Includes */
#include "bsp_dwt.h"
/* USER CODE END Includes */ /* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/ /* Private typedef -----------------------------------------------------------*/
@ -95,7 +95,11 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef* pcdHandle)
HAL_NVIC_SetPriority(OTG_FS_IRQn, 5, 0); HAL_NVIC_SetPriority(OTG_FS_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(OTG_FS_IRQn); HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspInit 1 */ /* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
// 上电后重新枚举usb设备
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_12, GPIO_PIN_RESET);
DWT_Delay(100);
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_12, GPIO_PIN_RESET);
DWT_Delay(100);
/* USER CODE END USB_OTG_FS_MspInit 1 */ /* USER CODE END USB_OTG_FS_MspInit 1 */
} }
} }

View File

@ -8,6 +8,9 @@
#include "message_center.h" #include "message_center.h"
#include "general_def.h" #include "general_def.h"
#include "dji_motor.h" #include "dji_motor.h"
// bsp
#include "bsp_dwt.h"
#include "bsp_log.h"
// 私有宏,自动将编码器转换成角度值 // 私有宏,自动将编码器转换成角度值
#define YAW_ALIGN_ANGLE (YAW_CHASSIS_ALIGN_ECD * ECD_ANGLE_COEF_DJI) // 对齐时的角度,0-360 #define YAW_ALIGN_ANGLE (YAW_CHASSIS_ALIGN_ECD * ECD_ANGLE_COEF_DJI) // 对齐时的角度,0-360
@ -129,16 +132,8 @@ static void RemoteControlSet()
{ // 按照摇杆的输出大小进行角度增量,增益系数需调整 { // 按照摇杆的输出大小进行角度增量,增益系数需调整
gimbal_cmd_send.yaw += 0.005f * (float)rc_data[TEMP].rc.rocker_l_; gimbal_cmd_send.yaw += 0.005f * (float)rc_data[TEMP].rc.rocker_l_;
gimbal_cmd_send.pitch += 0.001f * (float)rc_data[TEMP].rc.rocker_l1; gimbal_cmd_send.pitch += 0.001f * (float)rc_data[TEMP].rc.rocker_l1;
// 摇杆控制的软件限位
// if (gimbal_cmd_send.pitch <= PITCH_MIN_ECD)
// {
// gimbal_cmd_send.pitch = PITCH_MIN_ECD;
// }
// else if (gimbal_cmd_send.pitch >= PITCH_MAX_ECD)
// {
// gimbal_cmd_send.pitch = PITCH_MAX_ECD;
// }
} }
// 云台软件限位
// 底盘参数,目前没有加入小陀螺(调试似乎暂时没有必要),系数需要调整 // 底盘参数,目前没有加入小陀螺(调试似乎暂时没有必要),系数需要调整
chassis_cmd_send.vx = 10.0f * (float)rc_data[TEMP].rc.rocker_r_; // _水平方向 chassis_cmd_send.vx = 10.0f * (float)rc_data[TEMP].rc.rocker_r_; // _水平方向
@ -266,12 +261,14 @@ static void EmergencyHandler()
shoot_cmd_send.shoot_mode = SHOOT_OFF; shoot_cmd_send.shoot_mode = SHOOT_OFF;
shoot_cmd_send.friction_mode = FRICTION_OFF; shoot_cmd_send.friction_mode = FRICTION_OFF;
shoot_cmd_send.load_mode = LOAD_STOP; shoot_cmd_send.load_mode = LOAD_STOP;
LOGERROR("[CMD] emergency stop!");
} }
// 遥控器右侧开关为[上],恢复正常运行 // 遥控器右侧开关为[上],恢复正常运行
if (switch_is_up(rc_data[TEMP].rc.switch_right)) if (switch_is_up(rc_data[TEMP].rc.switch_right))
{ {
robot_state = ROBOT_READY; robot_state = ROBOT_READY;
shoot_cmd_send.shoot_mode = SHOOT_ON; shoot_cmd_send.shoot_mode = SHOOT_ON;
LOGINFO("[CMD] reinstate, robot ready");
} }
} }

View File

@ -13,6 +13,8 @@
#include "daemon.h" #include "daemon.h"
#include "HT04.h" #include "HT04.h"
#include "bsp_log.h"
osThreadId insTaskHandle; osThreadId insTaskHandle;
osThreadId robotTaskHandle; osThreadId robotTaskHandle;
osThreadId motorTaskHandle; osThreadId motorTaskHandle;
@ -54,12 +56,15 @@ void StartINSTASK(void const *argument)
{ {
static float ins_start, ins_dt; static float ins_start, ins_dt;
INS_Init(); // 确保BMI088被正确初始化. INS_Init(); // 确保BMI088被正确初始化.
LOGINFO("[freeRTOS] INS Task Start");
while (1) while (1)
{ {
// 1kHz // 1kHz
ins_start = DWT_GetTimeline_ms(); ins_start = DWT_GetTimeline_ms();
INS_Task(); INS_Task();
ins_dt = DWT_GetTimeline_ms() - ins_start; ins_dt = DWT_GetTimeline_ms() - ins_start;
if (ins_dt > 1)
LOGERROR("[freeRTOS] INS Task is being DELAY! dt = [%f]", &ins_dt);
VisionSend(); // 解算完成后发送视觉数据,但是当前的实现不太优雅,后续若添加硬件触发需要重新考虑结构的组织 VisionSend(); // 解算完成后发送视觉数据,但是当前的实现不太优雅,后续若添加硬件触发需要重新考虑结构的组织
osDelay(1); osDelay(1);
} }
@ -68,21 +73,30 @@ void StartINSTASK(void const *argument)
void StartMOTORTASK(void const *argument) void StartMOTORTASK(void const *argument)
{ {
static float motor_dt, motor_start; static float motor_dt, motor_start;
LOGINFO("[freeRTOS] MOTOR Task Start");
while (1) while (1)
{ {
motor_start = DWT_GetTimeline_ms(); motor_start = DWT_GetTimeline_ms();
MotorControlTask(); MotorControlTask();
motor_dt = DWT_GetTimeline_ms() - motor_start; motor_dt = DWT_GetTimeline_ms() - motor_start;
if (motor_dt > 1)
LOGERROR("[freeRTOS] MOTOR Task is being DELAY! dt = [%f]", &motor_dt);
osDelay(1); osDelay(1);
} }
} }
void StartDAEMONTASK(void const *argument) void StartDAEMONTASK(void const *argument)
{ {
static float daemon_dt, daemon_start;
LOGINFO("[freeRTOS] Daemon Task Start");
while (1) while (1)
{ {
// 100Hz // 100Hz
daemon_start = DWT_GetTimeline_ms();
DaemonTask(); DaemonTask();
daemon_dt = DWT_GetTimeline_ms() - daemon_start;
if (daemon_dt > 10)
LOGERROR("[freeRTOS] Daemon Task is being DELAY! dt = [%f]", &daemon_dt);
osDelay(10); osDelay(10);
} }
} }
@ -90,19 +104,24 @@ void StartDAEMONTASK(void const *argument)
void StartROBOTTASK(void const *argument) void StartROBOTTASK(void const *argument)
{ {
static float robot_dt, robot_start; static float robot_dt, robot_start;
LOGINFO("[freeRTOS] ROBOT core Task Start");
// 200Hz-500Hz,若有额外的控制任务如平衡步兵可能需要提升至1kHz // 200Hz-500Hz,若有额外的控制任务如平衡步兵可能需要提升至1kHz
while (1) while (1)
{ {
robot_start = DWT_GetTimeline_ms(); robot_start = DWT_GetTimeline_ms();
RobotTask(); RobotTask();
robot_dt = DWT_GetTimeline_ms() - robot_start; robot_dt = DWT_GetTimeline_ms() - robot_start;
if (robot_dt > 5)
LOGERROR("[freeRTOS] ROBOT core Task is being DELAY! dt = [%f]", &robot_dt);
osDelay(5); osDelay(5);
} }
} }
void StartUITASK(void const *argument) void StartUITASK(void const *argument)
{ {
LOGINFO("[freeRTOS] UI Task Start");
MyUIInit(); MyUIInit();
LOGINFO("[freeRTOS] UI Init Done, communication with ref has established");
while (1) while (1)
{ {
// 每给裁判系统发送一包数据会挂起一次,详见UITask函数的refereeSend() // 每给裁判系统发送一包数据会挂起一次,详见UITask函数的refereeSend()

View File

@ -174,11 +174,12 @@ Dma.USART6_TX.1.PeriphInc=DMA_PINC_DISABLE
Dma.USART6_TX.1.Priority=DMA_PRIORITY_HIGH Dma.USART6_TX.1.Priority=DMA_PRIORITY_HIGH
Dma.USART6_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,FIFOThreshold,MemBurst,PeriphBurst Dma.USART6_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,FIFOThreshold,MemBurst,PeriphBurst
FREERTOS.INCLUDE_vTaskDelayUntil=1 FREERTOS.INCLUDE_vTaskDelayUntil=1
FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configMAX_TASK_NAME_LEN,configUSE_TIMERS,configUSE_POSIX_ERRNO,INCLUDE_vTaskDelayUntil,configTOTAL_HEAP_SIZE FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configMAX_TASK_NAME_LEN,configUSE_TIMERS,configUSE_POSIX_ERRNO,INCLUDE_vTaskDelayUntil,configTOTAL_HEAP_SIZE,configUSE_COUNTING_SEMAPHORES
FREERTOS.Tasks01=defaultTask,0,128,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL FREERTOS.Tasks01=defaultTask,0,128,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL
FREERTOS.configENABLE_FPU=1 FREERTOS.configENABLE_FPU=1
FREERTOS.configMAX_TASK_NAME_LEN=32 FREERTOS.configMAX_TASK_NAME_LEN=32
FREERTOS.configTOTAL_HEAP_SIZE=20000 FREERTOS.configTOTAL_HEAP_SIZE=20000
FREERTOS.configUSE_COUNTING_SEMAPHORES=1
FREERTOS.configUSE_POSIX_ERRNO=0 FREERTOS.configUSE_POSIX_ERRNO=0
FREERTOS.configUSE_TIMERS=0 FREERTOS.configUSE_TIMERS=0
File.Version=6 File.Version=6
@ -308,6 +309,7 @@ NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:fals
NVIC.EXTI3_IRQn=true\:5\:0\:true\:false\:true\:true\:true\:true\:true NVIC.EXTI3_IRQn=true\:5\:0\:true\:false\:true\:true\:true\:true\:true
NVIC.EXTI4_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true NVIC.EXTI4_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.EXTI9_5_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true NVIC.EXTI9_5_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.FLASH_IRQn=true\:6\:0\:true\:false\:true\:true\:true\:true\:true
NVIC.ForceEnableDMAVector=true NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.I2C2_ER_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true NVIC.I2C2_ER_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true

View File

@ -2,7 +2,7 @@
#include "bsp_log.h" #include "bsp_log.h"
#include "bsp_dwt.h" #include "bsp_dwt.h"
#include "bsp_usb.h" #include "bsp_usb.h"
#include "bsp_buzzer.h" #include "buzzer.h"
#include "bsp_led.h" #include "bsp_led.h"
#include "bsp_temperature.h" #include "bsp_temperature.h"
@ -15,5 +15,5 @@ void BSPInit()
// legacy support待删除,将在实现了led/tempctrl/buzzer的module之后移动到app层进行XXXRegister() // legacy support待删除,将在实现了led/tempctrl/buzzer的module之后移动到app层进行XXXRegister()
LEDInit(); LEDInit();
IMUTempInit(); IMUTempInit();
BuzzerInit(); buzzer_init();
} }

View File

@ -1,28 +0,0 @@
#include "bsp_buzzer.h"
#include "main.h"
#warning this is a legacy support file, please use the new version
extern TIM_HandleTypeDef htim4;
static uint8_t tmp_warning_level = 0;
void BuzzerInit()
{
HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_3);
}
void BuzzerOn(uint16_t psc, uint16_t pwm, uint8_t level)
{
if (level > tmp_warning_level)
{
tmp_warning_level = level;
__HAL_TIM_PRESCALER(&htim4, psc);
__HAL_TIM_SetCompare(&htim4, TIM_CHANNEL_3, pwm);
}
}
void BuzzerOff(void)
{
__HAL_TIM_SetCompare(&htim4, TIM_CHANNEL_3, 0);
tmp_warning_level = 0;
}

View File

@ -1,10 +0,0 @@
#ifndef BSP_BUZZER_H
#define BSP_BUZZER_H
#include <stdint.h>
void BuzzerInit();
extern void BuzzerOn(uint16_t psc, uint16_t pwm, uint8_t level);
extern void BuzzerOff(void);
#endif

View File

@ -65,15 +65,20 @@ CANInstance *CANRegister(CAN_Init_Config_s *config)
if (!idx) if (!idx)
{ {
CANServiceInit(); // 第一次注册,先进行硬件初始化 CANServiceInit(); // 第一次注册,先进行硬件初始化
LOGINFO("[bsp_can] CAN Service Init");
} }
if (idx >= CAN_MX_REGISTER_CNT) // 超过最大实例数 if (idx >= CAN_MX_REGISTER_CNT) // 超过最大实例数
{
while (1) while (1)
; LOGERROR("[bsp_can] CAN instance exceeded MAX num, consider balance the load of CAN bus");
}
for (size_t i = 0; i < idx; i++) for (size_t i = 0; i < idx; i++)
{ // 重复注册 | id重复 { // 重复注册 | id重复
if (can_instance[i]->rx_id == config->rx_id && can_instance[i]->can_handle == config->can_handle) if (can_instance[i]->rx_id == config->rx_id && can_instance[i]->can_handle == config->can_handle)
{
while (1) while (1)
; LOGERROR("[}bsp_can] CAN id crash ,tx [%d] or rx [%d] already registered", &config->tx_id, &config->rx_id);
}
} }
CANInstance *instance = (CANInstance *)malloc(sizeof(CANInstance)); // 分配空间 CANInstance *instance = (CANInstance *)malloc(sizeof(CANInstance)); // 分配空间
@ -107,7 +112,7 @@ uint8_t CANTransmit(CANInstance *_instance, float timeout)
{ {
if (DWT_GetTimeline_ms() - dwt_start > timeout) // 超时 if (DWT_GetTimeline_ms() - dwt_start > timeout) // 超时
{ {
LOGWARNING("CAN BUSY sending! cnt:%d", busy_count); LOGWARNING("[bsp_can] CAN MAILbox full! failed to add msg to mailbox. Cnt [%d]", busy_count);
busy_count++; busy_count++;
return 0; return 0;
} }
@ -116,7 +121,7 @@ uint8_t CANTransmit(CANInstance *_instance, float timeout)
// tx_mailbox会保存实际填入了这一帧消息的邮箱,但是知道是哪个邮箱发的似乎也没啥用 // tx_mailbox会保存实际填入了这一帧消息的邮箱,但是知道是哪个邮箱发的似乎也没啥用
if (HAL_CAN_AddTxMessage(_instance->can_handle, &_instance->txconf, _instance->tx_buff, &_instance->tx_mailbox)) if (HAL_CAN_AddTxMessage(_instance->can_handle, &_instance->txconf, _instance->tx_buff, &_instance->tx_mailbox))
{ {
LOGWARNING("CAN BUSY bus! cnt:%d", busy_count); LOGWARNING("[bsp_can] CAN bus BUS! cnt:%d", busy_count);
busy_count++; busy_count++;
return 0; return 0;
} }
@ -125,9 +130,10 @@ uint8_t CANTransmit(CANInstance *_instance, float timeout)
void CANSetDLC(CANInstance *_instance, uint8_t length) void CANSetDLC(CANInstance *_instance, uint8_t length)
{ {
// 发送长度错误!检查调用参数是否出错,或出现野指针/越界访问
if (length > 8 || length == 0) // 安全检查 if (length > 8 || length == 0) // 安全检查
while (1) while (1)
; // 发送长度错误!检查调用参数是否出错,或出现野指针/越界访问 LOGERROR("[bsp_can] CAN DLC error! check your code or wild pointer");
_instance->txconf.DLC = length; _instance->txconf.DLC = length;
} }

View File

@ -22,7 +22,7 @@ static osMutexId DWT_MUTEX;
* @brief ,DWT CYCCNT寄存器是否溢出,CYCCNT_RountCount * @brief ,DWT CYCCNT寄存器是否溢出,CYCCNT_RountCount
* @attention * @attention
* *
* @todo dwt的时间更新单独设置一个任务 * @todo dwt的时间更新单独设置一个任务?
* ,使dwt的初衷是定时不被中断/, * ,使dwt的初衷是定时不被中断/,
* *
*/ */
@ -131,6 +131,5 @@ void DWT_Delay(float Delay)
float wait = Delay; float wait = Delay;
while ((DWT->CYCCNT - tickstart) < wait * (float)CPU_FREQ_Hz) while ((DWT->CYCCNT - tickstart) < wait * (float)CPU_FREQ_Hz)
{ ;
}
} }

View File

@ -2,7 +2,8 @@
****************************************************************************** ******************************************************************************
* @file bsp_dwt.h * @file bsp_dwt.h
* @author Wang Hongxi * @author Wang Hongxi
* @version V1.1.0 * @author modified by NeoZng
* @version V1.2.0
* @date 2022/3/8 * @date 2022/3/8
* @brief * @brief
****************************************************************************** ******************************************************************************
@ -15,6 +16,7 @@
#include "main.h" #include "main.h"
#include "stdint.h" #include "stdint.h"
#include "bsp_log.h"
typedef struct typedef struct
{ {
@ -23,6 +25,19 @@ typedef struct
uint16_t us; uint16_t us;
} DWT_Time_t; } DWT_Time_t;
/**
* @brief ,/s,float类型
* float类型的变量,
* RTT打印到日志终端,dt变量添加到查看
*/
#define TIME_ELAPSE(dt, code) \
do \
{ \
float tstart = DWT_GetTimeline_s(); \
code; \
dt = DWT_GetTimeline_s() - tstart; \
LOGINFO("[DWT] " #dt " = %f s\r\n", dt); \
} while (0)
/** /**
* @brief DWT,CPU频率,MHz * @brief DWT,CPU频率,MHz
@ -83,6 +98,4 @@ void DWT_Delay(float Delay);
*/ */
void DWT_SysTimeUpdate(void); void DWT_SysTimeUpdate(void);
#endif /* BSP_DWT_H_ */ #endif /* BSP_DWT_H_ */

View File

@ -2,8 +2,6 @@
DWT是stm32内部的一个"隐藏资源",他的用途是给下载器提供准确的定时,从而为调试信息加上时间戳.并在固定的时间间隔将调试数据发送到你的xxlink上. DWT是stm32内部的一个"隐藏资源",他的用途是给下载器提供准确的定时,从而为调试信息加上时间戳.并在固定的时间间隔将调试数据发送到你的xxlink上.
## 常用功能 ## 常用功能
### 计算两次进入同一个函数的时间间隔 ### 计算两次进入同一个函数的时间间隔
@ -28,3 +26,29 @@ for(uint8_t i=0;i<10;i++)
end = DWT_DetTimeline_ms()-start; end = DWT_DetTimeline_ms()-start;
``` ```
我们还提供了一个宏用于调试计时:
```c
#define TIME_ELAPSE(dt, code) \
do \
{ \
float tstart = DWT_GetTimeline_s(); \
code; \
dt = DWT_GetTimeline_s() - tstart; \
LOGINFO("[DWT] " #dt " = %f s\r\n", dt); \
} while (0)
```
传入一个float类型的变量,并将你要执行的代码写入第二个参数:
```c
static float my_func_dt;
TIME_ELAPSE(my_func_dt,
Function1(vara);
Function2(some, var);
Function3(your,param);
// something more
);
// my_func_dt can be used for other purpose then;
```

289
bsp/flash/bsp_flash.c Normal file
View File

@ -0,0 +1,289 @@
#include "bsp_flash.h"
#include "main.h"
#include "string.h"
static uint32_t ger_sector(uint32_t address);
/**
* @brief erase flash
* @param[in] address: flash address
* @param[in] len: page num
* @retval none
*/
/**
* @brief flash
* @param[in] address: flash
* @param[in] len:
* @retval none
*/
void flash_erase_address(uint32_t address, uint16_t len)
{
FLASH_EraseInitTypeDef flash_erase;
uint32_t error;
flash_erase.Sector = ger_sector(address);
flash_erase.TypeErase = FLASH_TYPEERASE_SECTORS;
flash_erase.VoltageRange = FLASH_VOLTAGE_RANGE_3;
flash_erase.NbSectors = len;
HAL_FLASH_Unlock();
HAL_FLASHEx_Erase(&flash_erase, &error);
HAL_FLASH_Lock();
}
/**
* @brief write data to one page of flash
* @param[in] start_address: flash address
* @param[in] buf: data point
* @param[in] len: data num
* @retval success 0, fail -1
*/
/**
* @brief flash写数据
* @param[in] start_address: flash
* @param[in] buf:
* @param[in] len:
* @retval success 0, fail -1
*/
int8_t flash_write_single_address(uint32_t start_address, uint32_t *buf, uint32_t len)
{
static uint32_t uw_address;
static uint32_t end_address;
static uint32_t *data_buf;
static uint32_t data_len;
HAL_FLASH_Unlock();
uw_address = start_address;
end_address = get_next_flash_address(start_address);
data_buf = buf;
data_len = 0;
while (uw_address <= end_address)
{
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD,uw_address, *data_buf) == HAL_OK)
{
uw_address += 4;
data_buf++;
data_len++;
if (data_len == len)
{
break;
}
}
else
{
HAL_FLASH_Lock();
return -1;
}
}
HAL_FLASH_Lock();
return 0;
}
/**
* @brief write data to some pages of flash
* @param[in] start_address: flash start address
* @param[in] end_address: flash end address
* @param[in] buf: data point
* @param[in] len: data num
* @retval success 0, fail -1
*/
/**
* @brief flash写数据
* @param[in] start_address: flash
* @param[in] end_address: flash
* @param[in] buf:
* @param[in] len:
* @retval success 0, fail -1
*/
int8_t flash_write_muli_address(uint32_t start_address, uint32_t end_address, uint32_t *buf, uint32_t len)
{
uint32_t uw_address = 0;
uint32_t *data_buf;
uint32_t data_len;
HAL_FLASH_Unlock();
uw_address = start_address;
data_buf = buf;
data_len = 0;
while (uw_address <= end_address)
{
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD,uw_address, *data_buf) == HAL_OK)
{
uw_address += 4;
data_buf++;
data_len++;
if (data_len == len)
{
break;
}
}
else
{
HAL_FLASH_Lock();
return -1;
}
}
HAL_FLASH_Lock();
return 0;
}
/**
* @brief read data for flash
* @param[in] address: flash address
* @param[out] buf: data point
* @param[in] len: data num
* @retval none
*/
/**
* @brief flash读数据
* @param[in] start_address: flash
* @param[out] buf:
* @param[in] len:
* @retval none
*/
void flash_read(uint32_t address, uint32_t *buf, uint32_t len)
{
memcpy(buf, (void*)address, len *4);
}
/**
* @brief get the sector number of flash
* @param[in] address: flash address
* @retval sector number
*/
/**
* @brief flash的sector号
* @param[in] address: flash
* @retval sector号
*/
static uint32_t ger_sector(uint32_t address)
{
uint32_t sector = 0;
if ((address < ADDR_FLASH_SECTOR_1) && (address >= ADDR_FLASH_SECTOR_0))
{
sector = FLASH_SECTOR_0;
}
else if ((address < ADDR_FLASH_SECTOR_2) && (address >= ADDR_FLASH_SECTOR_1))
{
sector = FLASH_SECTOR_1;
}
else if ((address < ADDR_FLASH_SECTOR_3) && (address >= ADDR_FLASH_SECTOR_2))
{
sector = FLASH_SECTOR_2;
}
else if ((address < ADDR_FLASH_SECTOR_4) && (address >= ADDR_FLASH_SECTOR_3))
{
sector = FLASH_SECTOR_3;
}
else if ((address < ADDR_FLASH_SECTOR_5) && (address >= ADDR_FLASH_SECTOR_4))
{
sector = FLASH_SECTOR_4;
}
else if ((address < ADDR_FLASH_SECTOR_6) && (address >= ADDR_FLASH_SECTOR_5))
{
sector = FLASH_SECTOR_5;
}
else if ((address < ADDR_FLASH_SECTOR_7) && (address >= ADDR_FLASH_SECTOR_6))
{
sector = FLASH_SECTOR_6;
}
else if ((address < ADDR_FLASH_SECTOR_8) && (address >= ADDR_FLASH_SECTOR_7))
{
sector = FLASH_SECTOR_7;
}
else if ((address < ADDR_FLASH_SECTOR_9) && (address >= ADDR_FLASH_SECTOR_8))
{
sector = FLASH_SECTOR_8;
}
else if ((address < ADDR_FLASH_SECTOR_10) && (address >= ADDR_FLASH_SECTOR_9))
{
sector = FLASH_SECTOR_9;
}
else if ((address < ADDR_FLASH_SECTOR_11) && (address >= ADDR_FLASH_SECTOR_10))
{
sector = FLASH_SECTOR_10;
}
else if ((address < ADDR_FLASH_SECTOR_12) && (address >= ADDR_FLASH_SECTOR_11))
{
sector = FLASH_SECTOR_11;
}
else
{
sector = FLASH_SECTOR_11;
}
return sector;
}
/**
* @brief get the next page flash address
* @param[in] address: flash address
* @retval next page flash address
*/
/**
* @brief flash地址
* @param[in] address: flash
* @retval flash地址
*/
uint32_t get_next_flash_address(uint32_t address)
{
uint32_t sector = 0;
if ((address < ADDR_FLASH_SECTOR_1) && (address >= ADDR_FLASH_SECTOR_0))
{
sector = ADDR_FLASH_SECTOR_1;
}
else if ((address < ADDR_FLASH_SECTOR_2) && (address >= ADDR_FLASH_SECTOR_1))
{
sector = ADDR_FLASH_SECTOR_2;
}
else if ((address < ADDR_FLASH_SECTOR_3) && (address >= ADDR_FLASH_SECTOR_2))
{
sector = ADDR_FLASH_SECTOR_3;
}
else if ((address < ADDR_FLASH_SECTOR_4) && (address >= ADDR_FLASH_SECTOR_3))
{
sector = ADDR_FLASH_SECTOR_4;
}
else if ((address < ADDR_FLASH_SECTOR_5) && (address >= ADDR_FLASH_SECTOR_4))
{
sector = ADDR_FLASH_SECTOR_5;
}
else if ((address < ADDR_FLASH_SECTOR_6) && (address >= ADDR_FLASH_SECTOR_5))
{
sector = ADDR_FLASH_SECTOR_6;
}
else if ((address < ADDR_FLASH_SECTOR_7) && (address >= ADDR_FLASH_SECTOR_6))
{
sector = ADDR_FLASH_SECTOR_7;
}
else if ((address < ADDR_FLASH_SECTOR_8) && (address >= ADDR_FLASH_SECTOR_7))
{
sector = ADDR_FLASH_SECTOR_8;
}
else if ((address < ADDR_FLASH_SECTOR_9) && (address >= ADDR_FLASH_SECTOR_8))
{
sector = ADDR_FLASH_SECTOR_9;
}
else if ((address < ADDR_FLASH_SECTOR_10) && (address >= ADDR_FLASH_SECTOR_9))
{
sector = ADDR_FLASH_SECTOR_10;
}
else if ((address < ADDR_FLASH_SECTOR_11) && (address >= ADDR_FLASH_SECTOR_10))
{
sector = ADDR_FLASH_SECTOR_11;
}
else /*(address < FLASH_END_ADDR) && (address >= ADDR_FLASH_SECTOR_23))*/
{
sector = FLASH_END_ADDR;
}
return sector;
}

80
bsp/flash/bsp_flash.h Normal file
View File

@ -0,0 +1,80 @@
#ifndef _BSP_FLASH_H
#define _BSP_FLASH_H
#include "main.h"
/* Base address of the Flash sectors */
#define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base address of Sector 0, 16 Kbytes */
#define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08004000) /* Base address of Sector 1, 16 Kbytes */
#define ADDR_FLASH_SECTOR_2 ((uint32_t)0x08008000) /* Base address of Sector 2, 16 Kbytes */
#define ADDR_FLASH_SECTOR_3 ((uint32_t)0x0800C000) /* Base address of Sector 3, 16 Kbytes */
#define ADDR_FLASH_SECTOR_4 ((uint32_t)0x08010000) /* Base address of Sector 4, 64 Kbytes */
#define ADDR_FLASH_SECTOR_5 ((uint32_t)0x08020000) /* Base address of Sector 5, 128 Kbytes */
#define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08040000) /* Base address of Sector 6, 128 Kbytes */
#define ADDR_FLASH_SECTOR_7 ((uint32_t)0x08060000) /* Base address of Sector 7, 128 Kbytes */
#define ADDR_FLASH_SECTOR_8 ((uint32_t)0x08080000) /* Base address of Sector 8, 128 Kbytes */
#define ADDR_FLASH_SECTOR_9 ((uint32_t)0x080A0000) /* Base address of Sector 9, 128 Kbytes */
#define ADDR_FLASH_SECTOR_10 ((uint32_t)0x080C0000) /* Base address of Sector 10, 128 Kbytes */
#define ADDR_FLASH_SECTOR_11 ((uint32_t)0x080E0000) /* Base address of Sector 11, 128 Kbytes */
#define FLASH_END_ADDR ((uint32_t)0x08100000) /* Base address of Sector 23, 128 Kbytes */
#define ADDR_FLASH_SECTOR_12 ((uint32_t)0x08100000) /* Base address of Sector 12, 16 Kbytes */
#define ADDR_FLASH_SECTOR_13 ((uint32_t)0x08104000) /* Base address of Sector 13, 16 Kbytes */
#define ADDR_FLASH_SECTOR_14 ((uint32_t)0x08108000) /* Base address of Sector 14, 16 Kbytes */
#define ADDR_FLASH_SECTOR_15 ((uint32_t)0x0810C000) /* Base address of Sector 15, 16 Kbytes */
#define ADDR_FLASH_SECTOR_16 ((uint32_t)0x08110000) /* Base address of Sector 16, 64 Kbytes */
#define ADDR_FLASH_SECTOR_17 ((uint32_t)0x08120000) /* Base address of Sector 17, 128 Kbytes */
#define ADDR_FLASH_SECTOR_18 ((uint32_t)0x08140000) /* Base address of Sector 18, 128 Kbytes */
#define ADDR_FLASH_SECTOR_19 ((uint32_t)0x08160000) /* Base address of Sector 19, 128 Kbytes */
#define ADDR_FLASH_SECTOR_20 ((uint32_t)0x08180000) /* Base address of Sector 20, 128 Kbytes */
#define ADDR_FLASH_SECTOR_21 ((uint32_t)0x081A0000) /* Base address of Sector 21, 128 Kbytes */
#define ADDR_FLASH_SECTOR_22 ((uint32_t)0x081C0000) /* Base address of Sector 22, 128 Kbytes */
#define ADDR_FLASH_SECTOR_23 ((uint32_t)0x081E0000) /* Base address of Sector 23, 128 Kbytes */
/**
* @brief erase flash
* @param[in] address: flash address
* @param[in] len: page num
* @retval none
*/
void flash_erase_address(uint32_t address, uint16_t len);
/**
* @brief write data to one page of flash
* @param[in] start_address: flash address
* @param[in] buf: data point
* @param[in] len: data num
* @retval success 0, fail -1
*/
int8_t flash_write_single_address(uint32_t start_address, uint32_t *buf, uint32_t len);
/**
* @brief write data to some pages of flash
* @param[in] start_address: flash start address
* @param[in] end_address: flash end address
* @param[in] buf: data point
* @param[in] len: data num
* @retval success 0, fail -1
*/
int8_t flash_write_muli_address(uint32_t start_address, uint32_t end_address, uint32_t *buf, uint32_t len);
/**
* @brief read data for flash
* @param[in] address: flash address
* @param[out] buf: data point
* @param[in] len: data num
* @retval none
*/
void flash_read(uint32_t address, uint32_t *buf, uint32_t len);
/**
* @brief get the next page flash address
* @param[in] address: flash address
* @retval next page flash address
*/
uint32_t get_next_flash_address(uint32_t address);
#endif

0
bsp/flash/bsp_flash.md Normal file
View File

View File

@ -7,8 +7,6 @@
#define BUFFER_INDEX 0 #define BUFFER_INDEX 0
/** /**
* @brief * @brief
* *
@ -26,7 +24,7 @@ void BSPLogInit();
##__VA_ARGS__, \ ##__VA_ARGS__, \
RTT_CTRL_RESET) RTT_CTRL_RESET)
/*------下面是日志输出的接口--------*/ /*----------------------------------------下面是日志输出的接口-------------------------------------------------*/
/* 清屏 */ /* 清屏 */
#define LOG_CLEAR() SEGGER_RTT_WriteString(0, " " RTT_CTRL_CLEAR) #define LOG_CLEAR() SEGGER_RTT_WriteString(0, " " RTT_CTRL_CLEAR)
@ -34,16 +32,20 @@ void BSPLogInit();
/* 无颜色日志输出 */ /* 无颜色日志输出 */
#define LOG(format, ...) LOG_PROTO("", "", format, ##__VA_ARGS__) #define LOG(format, ...) LOG_PROTO("", "", format, ##__VA_ARGS__)
/* 有颜色格式日志输出,建议使用这些宏来输出日志 */ /**
* ,使
* @attention ,,使Float2Str()
*/
// information level // information level
#define LOGINFO(format,...) LOG_PROTO("I", RTT_CTRL_TEXT_BRIGHT_GREEN , format, ##__VA_ARGS__) #define LOGINFO(format, ...) LOG_PROTO("I:", RTT_CTRL_TEXT_BRIGHT_GREEN, format, ##__VA_ARGS__)
// warning level // warning level
#define LOGWARNING(format,...) LOG_PROTO("W", RTT_CTRL_TEXT_BRIGHT_YELLOW, format, ##__VA_ARGS__) #define LOGWARNING(format, ...) LOG_PROTO("W:", RTT_CTRL_TEXT_BRIGHT_YELLOW, format, ##__VA_ARGS__)
// error level // error level
#define LOGERROR(format,...) LOG_PROTO("E", RTT_CTRL_TEXT_BRIGHT_RED , format, ##__VA_ARGS__) #define LOGERROR(format, ...) LOG_PROTO("E:", RTT_CTRL_TEXT_BRIGHT_RED, format, ##__VA_ARGS__)
/** /**
* @brief segger RTT打印日志,,printf. * @brief segger RTT打印日志,,printf.
* @attention !! ,,使Float2Str() !!
* *
* @param fmt * @param fmt
* @param ... * @param ...
@ -53,6 +55,7 @@ int PrintLog(const char *fmt, ...);
/** /**
* @brief sprintf(),float转换为字符串进行打印 * @brief sprintf(),float转换为字符串进行打印
* @attention RTT打印
* *
* @param str * @param str
* @param va float * @param va float

View File

@ -2,11 +2,6 @@
<p align='right'>neozng1@hnu.edu.cn</p> <p align='right'>neozng1@hnu.edu.cn</p>
> TODO:
>
> 1. 在未接入调试器的时候将日志写入flash中并提供接口读取
> 2. 增加日志分级提供info、warning、error三个等级的日志
## 使用说明 ## 使用说明
bsp_log是基于segger RTT实现的日志打印模块。 bsp_log是基于segger RTT实现的日志打印模块。
@ -19,11 +14,11 @@ bsp_log是基于segger RTT实现的日志打印模块。
#define LOGERROR(format,...) #define LOGERROR(format,...)
``` ```
分别用于输出不同等级的日志。 分别用于输出不同等级的日志。注意RTT不支持直接使用`%f`进行浮点格式化,要使用`void Float2Str(char *str, float va);`转化成字符串之后再发送。
**若想启用RTT必须通过`launch.json`的`debug-jlink`启动调试(不论使用什么调试器)。** **若想启用RTT必须通过`launch.json`的`debug-jlink`启动调试(不论使用什么调试器)。** 按照`VSCode+Ozone环境配置`完成配置之后的cmsis dap和daplink是可以支持Jlink全家桶的。
注意若你使用的是cmsis-dap和daplink**请在调试任务启动之后再打开`log`任务。**(均在项目文件夹下的.vsocde/task.json中有注释自行查看 另外若你使用的是cmsis-dap和daplink**请在 *jlink* 调试任务启动之后再打开`log`任务。**(均在项目文件夹下的.vsocde/task.json中有注释自行查看否则可能出线RTT viewer无法连接客户端的情况。
在ozone中查看log输出直接打开console调试任务台和terminal调试中断便可看到调试输出。 在ozone中查看log输出直接打开console调试任务台和terminal调试中断便可看到调试输出。
@ -35,7 +30,7 @@ bsp_log是基于segger RTT实现的日志打印模块。
```c ```c
int printf_log(const char *fmt, ...); int printf_log(const char *fmt, ...);
void Float2Str(char *str, float va); void Float2Str(char *str, float va); // 输出浮点需要先用此函数进行转换
``` ```
调用第一个函数可以通过jlink或dap-link向调试器连接的上位机发送信息格式和printf相同示例如下 调用第一个函数可以通过jlink或dap-link向调试器连接的上位机发送信息格式和printf相同示例如下
@ -53,8 +48,3 @@ char* str_buff[64];
Float2Str(str_buff,current_feedback); Float2Str(str_buff,current_feedback);
printf_log("Motor %d met some problem, error code %d!\n",3,1); printf_log("Motor %d met some problem, error code %d!\n",3,1);
``` ```
或直接通过`%f`格式符直接使用`printf_log()`发送日志,可以设置小数点位数以降低带宽开销。

View File

@ -8,6 +8,8 @@ static PWMInstance *pwm_instance[PWM_DEVICE_CNT] = {NULL}; // 所有的pwm insta
/** /**
* @brief pwm dma传输完成回调函数 * @brief pwm dma传输完成回调函数
* @attention HAL库的设计问题,pulse完成(tim的计数超过比较寄存器)
* PWM的TIM,,DMA传输完成中断打开
* *
* @param htim * @param htim
*/ */
@ -15,7 +17,7 @@ void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
{ {
for (uint8_t i = 0; i < idx; i++) for (uint8_t i = 0; i < idx; i++)
{ // 来自同一个定时器的中断且通道相同 { // 来自同一个定时器的中断且通道相同
if (pwm_instance[i]->htim == htim && htim->Channel == pwm_instance[i]->channel) if (pwm_instance[i]->htim == htim && htim->Channel == (1<<(pwm_instance[i]->channel/4)))
{ {
if (pwm_instance[i]->callback) // 如果有回调函数 if (pwm_instance[i]->callback) // 如果有回调函数
pwm_instance[i]->callback(pwm_instance[i]); pwm_instance[i]->callback(pwm_instance[i]);
@ -39,7 +41,7 @@ PWMInstance *PWMRegister(PWM_Init_Config_s *config)
pwm->callback = config->callback; pwm->callback = config->callback;
pwm->id = config->id; pwm->id = config->id;
// 启动PWM // 启动PWM
HAL_TIM_PWM_Start(pwm->htim, pwm->channel); HAL_TIM_PWM_Start_IT(pwm->htim, pwm->channel);
__HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse); // 设置占空比 __HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse); // 设置占空比
pwm_instance[idx++] = pwm; pwm_instance[idx++] = pwm;
@ -65,7 +67,11 @@ void PWMSetPulse(PWMInstance *pwm, uint32_t pulse)
pwm->pulse = pulse; pwm->pulse = pulse;
__HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse); __HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse);
} }
void PWMSetPeriod(PWMInstance *pwm, uint32_t period)
{
pwm->period = period;
__HAL_TIM_PRESCALER(pwm->htim, pwm->period);
}
/* 只是对HAL的函数进行了形式上的封装 */ /* 只是对HAL的函数进行了形式上的封装 */
void PWMStartDMA(PWMInstance *pwm, uint32_t *pData, uint32_t Size) void PWMStartDMA(PWMInstance *pwm, uint32_t *pData, uint32_t Size)
{ {

View File

@ -9,6 +9,7 @@
* *
*/ */
#include "bsp_usart.h" #include "bsp_usart.h"
#include "bsp_log.h"
#include "stdlib.h" #include "stdlib.h"
#include "memory.h" #include "memory.h"
@ -38,7 +39,13 @@ USARTInstance *USARTRegister(USART_Init_Config_s *init_config)
{ {
if (idx >= DEVICE_USART_CNT) // 超过最大实例数 if (idx >= DEVICE_USART_CNT) // 超过最大实例数
while (1) while (1)
; LOGERROR("[bsp_usart] USART exceed max instance count!");
for (uint8_t i = 0; i < idx; i++) // 检查是否已经注册过
if (usart_instance[i]->usart_handle == init_config->usart_handle)
while (1)
LOGERROR("[bsp_usart] USART instance already registered!");
USARTInstance *instance = (USARTInstance *)malloc(sizeof(USARTInstance)); USARTInstance *instance = (USARTInstance *)malloc(sizeof(USARTInstance));
memset(instance, 0, sizeof(USARTInstance)); memset(instance, 0, sizeof(USARTInstance));
@ -76,14 +83,10 @@ void USARTSend(USARTInstance *_instance, uint8_t *send_buf, uint16_t send_size,
uint8_t USARTIsReady(USARTInstance *_instance) uint8_t USARTIsReady(USARTInstance *_instance)
{ {
if (_instance->usart_handle->gState | HAL_UART_STATE_BUSY_TX) if (_instance->usart_handle->gState | HAL_UART_STATE_BUSY_TX)
{
return 0; return 0;
}
else else
{
return 1; return 1;
} }
}
/** /**
* @brief dma/idle中断发生时.uart实例会调用对应的回调进行进一步的处理 * @brief dma/idle中断发生时.uart实例会调用对应的回调进行进一步的处理
@ -129,6 +132,7 @@ void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart)
{ {
HAL_UARTEx_ReceiveToIdle_DMA(usart_instance[i]->usart_handle, usart_instance[i]->recv_buff, usart_instance[i]->recv_buff_size); HAL_UARTEx_ReceiveToIdle_DMA(usart_instance[i]->usart_handle, usart_instance[i]->recv_buff, usart_instance[i]->recv_buff_size);
__HAL_DMA_DISABLE_IT(usart_instance[i]->usart_handle->hdmarx, DMA_IT_HT); __HAL_DMA_DISABLE_IT(usart_instance[i]->usart_handle->hdmarx, DMA_IT_HT);
LOGWARNING("[bsp_usart] USART error callback triggered, instance idx [%d]", i);
return; return;
} }
} }

View File

@ -11,9 +11,9 @@
需要在串口实例下设定接收的数据包的长度,实例对应的串口硬件(通过`UART_HandleTypeDef`指定,如`&huart1`),解析接收数据对应的回调函数这三个参数。然后,调用`USARTRegister()`并传入配置好的`usart_instance`指针即可。 需要在串口实例下设定接收的数据包的长度,实例对应的串口硬件(通过`UART_HandleTypeDef`指定,如`&huart1`),解析接收数据对应的回调函数这三个参数。然后,调用`USARTRegister()`并传入配置好的`usart_instance`指针即可。
若要发送数据,调用`USARTSend()`。注意buffsize务必小于buff的大小否则造成指针越界后果未知。 若要发送数据,调用`USARTSend()`。注意buffsize务必小于你创建的buff的大小否则造成指针越界后果未知。
串口硬件收到数据时,会将其存入`usart_instance.recv_buff[]`中,当收到完整一包数据,会调用设定的回调函数`module_callback`(即你提供的解析函数)。在此函数中,你可以通过`usart_instance.recv_buff[]`访问串口收到的数据。 串口硬件收到数据时,会将其存入`usart_instance.recv_buff[]`中,当收到完整一包数据,会调用设定的回调函数`module_callback`(即你注册时提供的解析函数)。在此函数中,你可以通过`usart_instance.recv_buff[]`访问串口收到的数据。
## 代码结构 ## 代码结构

View File

@ -11,16 +11,17 @@
#include "bsp_usb.h" #include "bsp_usb.h"
#include "bsp_log.h" #include "bsp_log.h"
#include "bsp_dwt.h"
static uint8_t *bsp_usb_rx_buffer; // 接收到的数据会被放在这里,buffer size为2048 static uint8_t *bsp_usb_rx_buffer; // 接收到的数据会被放在这里,buffer size为2048
// 注意usb单个数据包(Full speed模式下)最大为64byte,超出可能会出现丢包情况 // 注意usb单个数据包(Full speed模式下)最大为64byte,超出可能会出现丢包情况
uint8_t *USBInit(USB_Init_Config_s usb_conf) uint8_t *USBInit(USB_Init_Config_s usb_conf)
{ {
// 上电后重新枚举usb设备 // usb的软件复位(模拟拔插)在usbd_conf.c中的HAL_PCD_MspInit()中
LOGINFO("USB init success");
bsp_usb_rx_buffer = CDCInitRxbufferNcallback(usb_conf.tx_cbk, usb_conf.rx_cbk); // 获取接收数据指针 bsp_usb_rx_buffer = CDCInitRxbufferNcallback(usb_conf.tx_cbk, usb_conf.rx_cbk); // 获取接收数据指针
// usb的接收回调函数会在这里被设置,并将数据保存在bsp_usb_rx_buffer中 // usb的接收回调函数会在这里被设置,并将数据保存在bsp_usb_rx_buffer中
LOGINFO("USB init success");
return bsp_usb_rx_buffer; return bsp_usb_rx_buffer;
} }

View File

@ -55,9 +55,7 @@ static void BMI088GyroRead(BMI088Instance *bmi088, uint8_t reg, uint8_t *dataptr
*/ */
static void BMI088AccelWriteSingleReg(BMI088Instance *bmi088, uint8_t reg, uint8_t data) static void BMI088AccelWriteSingleReg(BMI088Instance *bmi088, uint8_t reg, uint8_t data)
{ {
static uint8_t tx[2]; uint8_t tx[2] = {reg, data};
tx[0] = reg;
tx[1] = data;
SPITransmit(bmi088->spi_acc, tx, 2); SPITransmit(bmi088->spi_acc, tx, 2);
} }
@ -71,17 +69,15 @@ static void BMI088AccelWriteSingleReg(BMI088Instance *bmi088, uint8_t reg, uint8
*/ */
static void BMI088GyroWriteSingleReg(BMI088Instance *bmi088, uint8_t reg, uint8_t data) static void BMI088GyroWriteSingleReg(BMI088Instance *bmi088, uint8_t reg, uint8_t data)
{ {
static uint8_t tx[2]; uint8_t tx[2] = {reg, data};
tx[0] = reg;
tx[1] = data;
SPITransmit(bmi088->spi_gyro, tx, 2); SPITransmit(bmi088->spi_gyro, tx, 2);
} }
// -------------------------以上为私有函数,封装了BMI088寄存器读写函数,blocking--------------------------------// // -------------------------以上为私有函数,封装了BMI088寄存器读写函数,blocking--------------------------------//
// -------------------------以下为私有函数,用于初始化BMI088acc和gyro的硬件和配置--------------------------------// // -------------------------以下为私有函数,用于初始化BMI088acc和gyro的硬件和配置--------------------------------//
#define REG 0 #define BMI088REG 0
#define DATA 1 #define BMI088DATA 1
#define ERROR 2 #define BMI088ERROR 2
// BMI088初始化配置数组for accel,第一列为reg地址,第二列为写入的配置值,第三列为错误码(如果出错) // BMI088初始化配置数组for accel,第一列为reg地址,第二列为写入的配置值,第三列为错误码(如果出错)
static uint8_t BMI088_Accel_Init_Table[BMI088_WRITE_ACCEL_REG_NUM][3] = static uint8_t BMI088_Accel_Init_Table[BMI088_WRITE_ACCEL_REG_NUM][3] =
{ {
@ -106,7 +102,7 @@ static uint8_t BMI088_Gyro_Init_Table[BMI088_WRITE_GYRO_REG_NUM][3] =
* @brief BMI088加速度计, * @brief BMI088加速度计,
* *
* @param bmi088 BMI088实例 * @param bmi088 BMI088实例
* @return uint8_t ERROR CODE if any problems here * @return uint8_t BMI088ERROR CODE if any problems here
*/ */
static uint8_t BMI088AccelInit(BMI088Instance *bmi088) static uint8_t BMI088AccelInit(BMI088Instance *bmi088)
{ {
@ -130,14 +126,14 @@ static uint8_t BMI088AccelInit(BMI088Instance *bmi088)
// 使用sizeof而不是magic number,这样如果修改了数组大小,不用修改这里的代码;或者使用宏定义 // 使用sizeof而不是magic number,这样如果修改了数组大小,不用修改这里的代码;或者使用宏定义
for (uint8_t i = 0; i < sizeof(BMI088_Accel_Init_Table) / sizeof(BMI088_Accel_Init_Table[0]); i++) for (uint8_t i = 0; i < sizeof(BMI088_Accel_Init_Table) / sizeof(BMI088_Accel_Init_Table[0]); i++)
{ {
reg = BMI088_Accel_Init_Table[i][REG]; reg = BMI088_Accel_Init_Table[i][BMI088REG];
data = BMI088_Accel_Init_Table[i][DATA]; data = BMI088_Accel_Init_Table[i][BMI088DATA];
BMI088AccelWriteSingleReg(bmi088, reg, data); // 写入寄存器 BMI088AccelWriteSingleReg(bmi088, reg, data); // 写入寄存器
DWT_Delay(0.01); DWT_Delay(0.01);
BMI088AccelRead(bmi088, reg, &data, 1); // 写完之后立刻读回检查 BMI088AccelRead(bmi088, reg, &data, 1); // 写完之后立刻读回检查
DWT_Delay(0.01); DWT_Delay(0.01);
if (data != BMI088_Accel_Init_Table[i][DATA]) if (data != BMI088_Accel_Init_Table[i][BMI088DATA])
error |= BMI088_Accel_Init_Table[i][ERROR]; error |= BMI088_Accel_Init_Table[i][BMI088ERROR];
//{i--;} 可以设置retry次数,如果retry次数用完了,则返回error //{i--;} 可以设置retry次数,如果retry次数用完了,则返回error
} }
return error; return error;
@ -147,7 +143,7 @@ static uint8_t BMI088AccelInit(BMI088Instance *bmi088)
* @brief BMI088陀螺仪, * @brief BMI088陀螺仪,
* *
* @param bmi088 BMI088实例 * @param bmi088 BMI088实例
* @return uint8_t ERROR CODE * @return uint8_t BMI088ERROR CODE
*/ */
static uint8_t BMI088GyroInit(BMI088Instance *bmi088) static uint8_t BMI088GyroInit(BMI088Instance *bmi088)
{ {
@ -169,14 +165,14 @@ static uint8_t BMI088GyroInit(BMI088Instance *bmi088)
// 使用sizeof而不是magic number,这样如果修改了数组大小,不用修改这里的代码;或者使用宏定义 // 使用sizeof而不是magic number,这样如果修改了数组大小,不用修改这里的代码;或者使用宏定义
for (uint8_t i = 0; i < sizeof(BMI088_Gyro_Init_Table) / sizeof(BMI088_Gyro_Init_Table[0]); i++) for (uint8_t i = 0; i < sizeof(BMI088_Gyro_Init_Table) / sizeof(BMI088_Gyro_Init_Table[0]); i++)
{ {
reg = BMI088_Gyro_Init_Table[i][REG]; reg = BMI088_Gyro_Init_Table[i][BMI088REG];
data = BMI088_Gyro_Init_Table[i][DATA]; data = BMI088_Gyro_Init_Table[i][BMI088DATA];
BMI088GyroWriteSingleReg(bmi088, reg, data); // 写入寄存器 BMI088GyroWriteSingleReg(bmi088, reg, data); // 写入寄存器
DWT_Delay(0.001); DWT_Delay(0.001);
BMI088GyroRead(bmi088, reg, &data, 1); // 写完之后立刻读回对应寄存器检查是否写入成功 BMI088GyroRead(bmi088, reg, &data, 1); // 写完之后立刻读回对应寄存器检查是否写入成功
DWT_Delay(0.001); DWT_Delay(0.001);
if (data != BMI088_Gyro_Init_Table[i][DATA]) if (data != BMI088_Gyro_Init_Table[i][BMI088DATA])
error |= BMI088_Gyro_Init_Table[i][ERROR]; error |= BMI088_Gyro_Init_Table[i][BMI088ERROR];
//{i--;} 可以设置retry次数,尝试重新写入.如果retry次数用完了,则返回error //{i--;} 可以设置retry次数,尝试重新写入.如果retry次数用完了,则返回error
} }
@ -386,7 +382,7 @@ void BMI088CalibrateIMU(BMI088Instance *_bmi088)
BMI088Instance *BMI088Register(BMI088_Init_Config_s *config) BMI088Instance *BMI088Register(BMI088_Init_Config_s *config)
{ {
// 申请内存 // 申请内存
BMI088Instance *bmi088_instance = (BMI088Instance *)zero_malloc(sizeof(BMI088Instance)); BMI088Instance *bmi088_instance = (BMI088Instance *)zmalloc(sizeof(BMI088Instance));
// 从右向左赋值,让bsp instance保存指向bmi088_instance的指针(父指针),便于在底层中断中访问bmi088_instance // 从右向左赋值,让bsp instance保存指向bmi088_instance的指针(父指针),便于在底层中断中访问bmi088_instance
config->acc_int_config.id = config->acc_int_config.id =
config->gyro_int_config.id = config->gyro_int_config.id =

View File

@ -7,24 +7,24 @@
```c ```c
BMI088_Init_Config_s imu_config = { BMI088_Init_Config_s imu_config = {
.spi_acc_config={ .spi_acc_config={
.GPIOx=GPIOC, .GPIOx=GPIOA,
.GPIOx=GPIO_PIN_4, .GPIOx=GPIO_PIN_4,
.spi_handle=&hspi1, .spi_handle=&hspi1,
}, },
.spi_gyro_config={ .spi_gyro_config={
.GPIOx=GPIOC, .GPIOx=GPIOB,
.GPIOx=GPIO_PIN_4, .GPIOx=GPIO_PIN_0,
.spi_handle=&hspi1, .spi_handle=&hspi1,
}, },
.acc_int_config={ .acc_int_config={
.exti_mode=EXTI_TRIGGER_FALLING, .exti_mode=EXTI_TRIGGER_FALLING,
.GPIO_Pin=GPIO_PIN_10, .GPIO_Pin=GPIO_PIN_4,
.GPIOx=GPIOA, .GPIOx=GPIOC,
}, },
.gyro_int_config={ .gyro_int_config={
.exti_mode=EXTI_TRIGGER_FALLING, .exti_mode=EXTI_TRIGGER_FALLING,
.GPIO_Pin=GPIO_PIN_11, .GPIO_Pin=GPIO_PIN_5,
.GPIOx=GPIOA, .GPIOx=GPIOC,
}, },
.heat_pid_config={ .heat_pid_config={
.Kp=0.0f, .Kp=0.0f,

88
modules/alarm/buzzer.c Normal file
View File

@ -0,0 +1,88 @@
#include "bsp_pwm.h"
#include "buzzer.h"
#include "bsp_dwt.h"
static PWMInstance *buzzer;
static alarm_level_e now_alarm_level = ALARM_OFFLINE;
void BuzzerOn(PWMInstance *buzzer );
/**
*
* @brief
* @param alarm_level
*/
void BuzzerPlay(alarm_level_e alarm_level)
{
static alarm_level_e last_alarm_level = ALARM_LEVEL_LOW;
if(((int)DWT_GetTimeline_s() % 5)<1) //每5秒检查一次
{
last_alarm_level = ALARM_LEVEL_LOW;
now_alarm_level = ALARM_OFFLINE;
}
if(last_alarm_level <= now_alarm_level) //如果当前报警级别大于等于上一次报警级别,则更新报警级别
{
now_alarm_level = alarm_level;
}
last_alarm_level = alarm_level;
}
/**
* @brief
*
*/
void buzzer_init()
{
PWM_Init_Config_s buzzer_config = {
.htim = &htim4,
.channel= TIM_CHANNEL_3,
.period = 1,
.pulse = 10000,
.callback = BuzzerOn,
};
buzzer = PWMRegister(&buzzer_config);
}
/**
* @brief
*
* @param buzzer
*/
//*@todo: 优化报警声应类似D__,DDD,B__,BBB等报警声
void BuzzerOn(PWMInstance *buzzer )
{
switch (now_alarm_level)
{
case ALARM_LEVEL_LOW:
PWMSetPeriod(buzzer, 1);
PWMSetPulse(buzzer, 10000);
break;
case ALARM_LEVEL_BELOW_MEDIUM:
PWMSetPeriod(buzzer, 2);
PWMSetPulse(buzzer, 10000);
break;
case ALARM_LEVEL_MEDIUM:
PWMSetPeriod(buzzer, 3);
PWMSetPulse(buzzer, 10000);
break;
case ALARM_LEVEL_ABOVE_MEDIUM:
PWMSetPeriod(buzzer, 4);
PWMSetPulse(buzzer, 10000);
break;
case ALARM_LEVEL_HIGH:
PWMSetPeriod(buzzer, 5);
PWMSetPulse(buzzer, 10000);
break;
default:
PWMSetPulse(buzzer, 0);
break;
}
}

7
modules/alarm/buzzer.h Normal file
View File

@ -0,0 +1,7 @@
#ifndef BUZZER_H
#define BUZZER_H
#include "daemon.h"
void buzzer_init();
#endif // !BUZZER_H

View File

@ -23,9 +23,7 @@
#define user_malloc malloc #define user_malloc malloc
#endif #endif
uint8_t GlobalDebugMode = 7; void *zmalloc(size_t size)
void *zero_malloc(size_t size)
{ {
void *ptr = malloc(size); void *ptr = malloc(size);
memset(ptr, 0, size); memset(ptr, 0, size);
@ -207,3 +205,10 @@ float AverageFilter(float new_data, float *buf, uint8_t len)
sum += new_data; sum += new_data;
return sum / len; return sum / len;
} }
void MatInit(mat *m, uint8_t row, uint8_t col)
{
m->numCols = col;
m->numRows = row;
m->pData = (float *)zmalloc(row * col * sizeof(float));
}

View File

@ -13,18 +13,13 @@
#ifndef _USER_LIB_H #ifndef _USER_LIB_H
#define _USER_LIB_H #define _USER_LIB_H
#include "stdint.h" #include "stdint.h"
#include "main.h" #include "main.h"
#include "cmsis_os.h" #include "cmsis_os.h"
#include "stm32f407xx.h"
#include "arm_math.h"
#define msin(x) (arm_sin_f32(x))
#define mcos(x) (arm_cos_f32(x))
extern uint8_t GlobalDebugMode;
#ifndef user_malloc #ifndef user_malloc
#ifdef _CMSIS_OS_H #ifdef _CMSIS_OS_H
#define user_malloc pvPortMalloc #define user_malloc pvPortMalloc
@ -33,6 +28,18 @@ extern uint8_t GlobalDebugMode;
#endif #endif
#endif #endif
#define msin(x) (arm_sin_f32(x))
#define mcos(x) (arm_cos_f32(x))
typedef arm_matrix_instance_f32 mat;
// 若运算速度不够,可以使用q31代替f32,但是精度会降低
#define MatAdd arm_mat_add_f32
#define MatSubtract arm_mat_sub_f32
#define MatMultiply arm_mat_mult_f32
#define MatTranspose arm_mat_trans_f32
#define MatInverse arm_mat_inverse_f32
void MatInit(mat *m, uint8_t row, uint8_t col);
/* boolean type definitions */ /* boolean type definitions */
#ifndef TRUE #ifndef TRUE
#define TRUE 1 /**< boolean true */ #define TRUE 1 /**< boolean true */
@ -42,12 +49,6 @@ extern uint8_t GlobalDebugMode;
#define FALSE 0 /**< boolean fails */ #define FALSE 0 /**< boolean fails */
#endif #endif
/* math relevant */
/* radian coefficient */
#ifndef RADIAN_COEF
#define RADIAN_COEF 57.295779513f
#endif
/* circumference ratio */ /* circumference ratio */
#ifndef PI #ifndef PI
#define PI 3.14159265354f #define PI 3.14159265354f
@ -89,7 +90,7 @@ extern uint8_t GlobalDebugMode;
* @param size * @param size
* @return void* * @return void*
*/ */
void *zero_malloc(size_t size); void *zmalloc(size_t size);
// <20><><EFBFBD>ٿ<EFBFBD><D9BF><EFBFBD> // <20><><EFBFBD>ٿ<EFBFBD><D9BF><EFBFBD>
float Sqrt(float x); float Sqrt(float x);

View File

@ -3,6 +3,7 @@
#include "stdlib.h" #include "stdlib.h"
#include "crc8.h" #include "crc8.h"
#include "bsp_dwt.h" #include "bsp_dwt.h"
#include "bsp_log.h"
/** /**
* @brief CAN comm的接收状态和buffer * @brief CAN comm的接收状态和buffer
@ -69,6 +70,13 @@ static void CANCommRxCallback(CANInstance *_instance)
} }
} }
static void CANCommLostCallback(void *cancomm)
{
CANCommInstance *comm = (CANCommInstance *)cancomm;
CANCommResetRx(comm);
LOGWARNING("[can_comm] can comm rx[%d] lost, reset rx state.", &comm->can_ins->rx_id);
}
CANCommInstance *CANCommInit(CANComm_Init_Config_s *comm_config) CANCommInstance *CANCommInit(CANComm_Init_Config_s *comm_config)
{ {
CANCommInstance *ins = (CANCommInstance *)malloc(sizeof(CANCommInstance)); CANCommInstance *ins = (CANCommInstance *)malloc(sizeof(CANCommInstance));

View File

@ -2,6 +2,7 @@
#include "bsp_dwt.h" // 后续通过定时器来计时? #include "bsp_dwt.h" // 后续通过定时器来计时?
#include "stdlib.h" #include "stdlib.h"
#include "memory.h" #include "memory.h"
#include "buzzer.h"
// 用于保存所有的daemon instance // 用于保存所有的daemon instance
static DaemonInstance *daemon_instances[DAEMON_MX_CNT] = {NULL}; static DaemonInstance *daemon_instances[DAEMON_MX_CNT] = {NULL};
@ -13,9 +14,13 @@ DaemonInstance *DaemonRegister(Daemon_Init_Config_s *config)
memset(instance, 0, sizeof(DaemonInstance)); memset(instance, 0, sizeof(DaemonInstance));
instance->owner_id = config->owner_id; instance->owner_id = config->owner_id;
instance->reload_count = config->reload_count == 0 ? 100 : config->reload_count; instance->reload_count = config->reload_count == 0 ? 100 : config->reload_count; // 默认值为100
instance->callback = config->callback; instance->callback = config->callback;
instance->temp_count = config->init_count == 0 ? 100 : config->init_count; // 默认值为100,初始计数
instance->alarm_state = config->alarm_state;
instance->alarm_level = config->alarm_level;
instance->temp_count = config->reload_count;
daemon_instances[idx++] = instance; daemon_instances[idx++] = instance;
return instance; return instance;
} }
@ -36,6 +41,7 @@ void DaemonTask()
DaemonInstance *dins; // 提高可读性同时降低访存开销 DaemonInstance *dins; // 提高可读性同时降低访存开销
for (size_t i = 0; i < idx; ++i) for (size_t i = 0; i < idx; ++i)
{ {
dins = daemon_instances[i]; dins = daemon_instances[i];
if (dins->temp_count > 0) // 如果计数器还有值,说明上一次喂狗后还没有超时,则计数器减一 if (dins->temp_count > 0) // 如果计数器还有值,说明上一次喂狗后还没有超时,则计数器减一
dins->temp_count--; dins->temp_count--;
@ -43,6 +49,11 @@ void DaemonTask()
{ {
dins->callback(dins->owner_id); // module内可以将owner_id强制类型转换成自身类型从而调用特定module的offline callback dins->callback(dins->owner_id); // module内可以将owner_id强制类型转换成自身类型从而调用特定module的offline callback
// @todo 为蜂鸣器/led等增加离线报警的功能,非常关键! // @todo 为蜂鸣器/led等增加离线报警的功能,非常关键!
if(dins->alarm_state == ALARM_ON)
{
BuzzerPlay(dins->alarm_level);
}
} }
} }
} }

View File

@ -2,17 +2,33 @@
#define MONITOR_H #define MONITOR_H
#include "stdint.h" #include "stdint.h"
#include "string.h"
#define DAEMON_MX_CNT 64 #define DAEMON_MX_CNT 64
/* 模块离线处理函数指针 */ /* 模块离线处理函数指针 */
typedef void (*offline_callback)(void *); typedef void (*offline_callback)(void *);
typedef enum
{
ALARM_OFF = 0,
ALARM_ON = 1,
}alarm_state_e;
typedef enum
{
ALARM_LEVEL_LOW = 0,
ALARM_LEVEL_BELOW_MEDIUM = 1,
ALARM_LEVEL_MEDIUM = 2,
ALARM_LEVEL_ABOVE_MEDIUM = 3,
ALARM_LEVEL_HIGH = 4,
ALARM_OFFLINE = 5,
}alarm_level_e;
/* daemon结构体定义 */ /* daemon结构体定义 */
typedef struct daemon_ins typedef struct daemon_ins
{ {
uint16_t reload_count; // 重载值 uint16_t reload_count; // 重载值
offline_callback callback; // 异常处理函数,当模块发生异常时会被调用 offline_callback callback; // 异常处理函数,当模块发生异常时会被调用
alarm_state_e alarm_state; // 蜂鸣器状态
alarm_level_e alarm_level; //警报级别
uint16_t temp_count; // 当前值,减为零说明模块离线或异常 uint16_t temp_count; // 当前值,减为零说明模块离线或异常
void *owner_id; // daemon实例的地址,初始化的时候填入 void *owner_id; // daemon实例的地址,初始化的时候填入
@ -22,7 +38,11 @@ typedef struct daemon_ins
typedef struct typedef struct
{ {
uint16_t reload_count; // 实际上这是app唯一需要设置的值? uint16_t reload_count; // 实际上这是app唯一需要设置的值?
uint16_t init_count; // 上线等待时间,有些模块需要收到主控的指令才会反馈报文,或pc等需要开机时间
offline_callback callback; // 异常处理函数,当模块发生异常时会被调用 offline_callback callback; // 异常处理函数,当模块发生异常时会被调用
alarm_state_e alarm_state; // 蜂鸣器状态
alarm_level_e alarm_level; //警报级别
void *owner_id; // id取拥有daemon的实例的地址,如DJIMotorInstance*,cast成void*类型 void *owner_id; // id取拥有daemon的实例的地址,如DJIMotorInstance*,cast成void*类型
} Daemon_Init_Config_s; } Daemon_Init_Config_s;

View File

@ -2,6 +2,7 @@
#include "BMI088reg.h" #include "BMI088reg.h"
#include "BMI088Middleware.h" #include "BMI088Middleware.h"
#include "bsp_dwt.h" #include "bsp_dwt.h"
#include "bsp_log.h"
#include <math.h> #include <math.h>
#warning this is a legacy support. test the new BMI088 module as soon as possible. #warning this is a legacy support. test the new BMI088 module as soon as possible.
@ -129,7 +130,7 @@ void Calibrate_MPU_Offset(IMU_Data_t *bmi088)
startTime = DWT_GetTimeline_s(); startTime = DWT_GetTimeline_s();
do do
{ {
if (DWT_GetTimeline_s() - startTime > 10) if (DWT_GetTimeline_s() - startTime > 12)
{ {
// <20><>???? // <20><>????
bmi088->GyroOffset[0] = GxOFFSET; bmi088->GyroOffset[0] = GxOFFSET;
@ -137,6 +138,7 @@ void Calibrate_MPU_Offset(IMU_Data_t *bmi088)
bmi088->GyroOffset[2] = GzOFFSET; bmi088->GyroOffset[2] = GzOFFSET;
bmi088->gNorm = gNORM; bmi088->gNorm = gNORM;
bmi088->TempWhenCali = 40; bmi088->TempWhenCali = 40;
LOGERROR("[BMI088] Calibrate Failed! Use offline params");
break; break;
} }
@ -206,7 +208,11 @@ void Calibrate_MPU_Offset(IMU_Data_t *bmi088)
gyroDiff[0] > 0.15f || gyroDiff[0] > 0.15f ||
gyroDiff[1] > 0.15f || gyroDiff[1] > 0.15f ||
gyroDiff[2] > 0.15f) gyroDiff[2] > 0.15f)
{
LOGWARNING("[bmi088] calibration was interrupted\n");
break; break;
}
DWT_Delay(0.0005); DWT_Delay(0.0005);
} }
@ -252,7 +258,10 @@ uint8_t bmi088_accel_init(void)
// check the "who am I" // check the "who am I"
if (res != BMI088_ACC_CHIP_ID_VALUE) if (res != BMI088_ACC_CHIP_ID_VALUE)
{
LOGERROR("[bmi088] Can not read bmi088 acc chip id");
return BMI088_NO_SENSOR; return BMI088_NO_SENSOR;
}
// set accel sonsor config and check // set accel sonsor config and check
for (write_reg_num = 0; write_reg_num < BMI088_WRITE_ACCEL_REG_NUM; write_reg_num++) for (write_reg_num = 0; write_reg_num < BMI088_WRITE_ACCEL_REG_NUM; write_reg_num++)
@ -294,7 +303,10 @@ uint8_t bmi088_gyro_init(void)
// check the "who am I" // check the "who am I"
if (res != BMI088_GYRO_CHIP_ID_VALUE) if (res != BMI088_GYRO_CHIP_ID_VALUE)
{
LOGERROR("[bmi088] Can not read bmi088 gyro chip id");
return BMI088_NO_SENSOR; return BMI088_NO_SENSOR;
}
// set gyro sonsor config and check // set gyro sonsor config and check
for (write_reg_num = 0; write_reg_num < BMI088_WRITE_GYRO_REG_NUM; write_reg_num++) for (write_reg_num = 0; write_reg_num < BMI088_WRITE_GYRO_REG_NUM; write_reg_num++)

View File

@ -8,7 +8,7 @@ static LEDInstance *bsp_led_ins[LED_MAX_NUM] = {NULL};
LEDInstance *LEDRegister(LED_Init_Config_s *led_config) LEDInstance *LEDRegister(LED_Init_Config_s *led_config)
{ {
LEDInstance *led_ins = (LEDInstance *)zero_malloc(sizeof(LEDInstance)); LEDInstance *led_ins = (LEDInstance *)zmalloc(sizeof(LEDInstance));
// 剩下的值暂时都被置零 // 剩下的值暂时都被置零
led_ins->led_pwm = PWMRegister(&led_config->pwm_config); led_ins->led_pwm = PWMRegister(&led_config->pwm_config);
led_ins->led_switch = led_config->init_swtich; led_ins->led_switch = led_config->init_swtich;

View File

@ -10,11 +10,13 @@
*/ */
#include "master_process.h" #include "master_process.h"
#include "seasky_protocol.h" #include "seasky_protocol.h"
#include "daemon.h"
#include "bsp_log.h" #include "bsp_log.h"
#include "robot_def.h" #include "robot_def.h"
static Vision_Recv_s recv_data; static Vision_Recv_s recv_data;
static Vision_Send_s send_data; static Vision_Send_s send_data;
static DaemonInstance *vision_daemon_instance;
void VisionSetFlag(Enemy_Color_e enemy_color, Work_Mode_e work_mode, Bullet_Speed_e bullet_speed) void VisionSetFlag(Enemy_Color_e enemy_color, Work_Mode_e work_mode, Bullet_Speed_e bullet_speed)
{ {
@ -30,13 +32,26 @@ void VisionSetAltitude(float yaw, float pitch, float roll)
send_data.roll = roll; send_data.roll = roll;
} }
/**
* @brief 线,daemon.c中被daemon task调用
* @attention HAL库的设计问题,DMA接收之后同时发送有概率出现__HAL_LOCK(),使
* .daemon判断数据更新,.
*
* @param id vision_usart_instance的地址,.
*/
static void VisionOfflineCallback(void *id)
{
#ifdef VISION_USE_UART
USARTServiceInit(vision_usart_instance);
#endif // !VISION_USE_UART
LOGWARNING("[vision] vision offline, restart communication.");
}
#ifdef VISION_USE_UART #ifdef VISION_USE_UART
#include "bsp_usart.h" #include "bsp_usart.h"
#include "daemon.h"
static USARTInstance *vision_usart_instance; static USARTInstance *vision_usart_instance;
static DaemonInstance *vision_daemon_instance;
/** /**
* @brief ,bsp_usart.c中被usart rx callback调用 * @brief ,bsp_usart.c中被usart rx callback调用
@ -51,21 +66,8 @@ static void DecodeVision()
// TODO: code to resolve flag_register; // TODO: code to resolve flag_register;
} }
/**
* @brief 线,daemon.c中被daemon task调用
* @attention HAL库的设计问题,DMA接收之后同时发送有概率出现__HAL_LOCK(),使
* .daemon判断数据更新,.
*
* @param id vision_usart_instance的地址,.
*/
static void VisionOfflineCallback(void *id)
{
USARTServiceInit(vision_usart_instance);
}
Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle) Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle)
{ {
#ifdef VISION_USE_UART
USART_Init_Config_s conf; USART_Init_Config_s conf;
conf.module_callback = DecodeVision; conf.module_callback = DecodeVision;
conf.recv_buff_size = VISION_RECV_SIZE; conf.recv_buff_size = VISION_RECV_SIZE;
@ -79,7 +81,6 @@ Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle)
.reload_count = 10, .reload_count = 10,
}; };
vision_daemon_instance = DaemonRegister(&daemon_conf); vision_daemon_instance = DaemonRegister(&daemon_conf);
#endif // VISION_USE_UART
return &recv_data; return &recv_data;
} }
@ -125,9 +126,17 @@ static void DecodeVision(uint16_t recv_len)
Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle) Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle)
{ {
UNUSED(_handle); // 仅为了消除警告 UNUSED(_handle); // 仅为了消除警告
USB_Init_Config_s conf = {0}; USB_Init_Config_s conf = {.rx_cbk = DecodeVision};
conf.rx_cbk = DecodeVision;
vis_recv_buff = USBInit(conf); vis_recv_buff = USBInit(conf);
// 为master process注册daemon,用于判断视觉通信是否离线
Daemon_Init_Config_s daemon_conf = {
.callback = VisionOfflineCallback, // 离线时调用的回调函数,会重启串口接收
.owner_id = NULL,
.reload_count = 5, // 50ms
};
vision_daemon_instance = DaemonRegister(&daemon_conf);
return &recv_data; return &recv_data;
} }

View File

@ -4,14 +4,15 @@
#include "bsp_log.h" #include "bsp_log.h"
static uint8_t idx = 0; // register idx,是该文件的全局电机索引,在注册时使用 static uint8_t idx = 0; // register idx,是该文件的全局电机索引,在注册时使用
/* DJI电机的实例,此处仅保存指针,内存的分配将通过电机实例初始化时通过malloc()进行 */ /* DJI电机的实例,此处仅保存指针,内存的分配将通过电机实例初始化时通过malloc()进行 */
static DJIMotorInstance *dji_motor_instance[DJI_MOTOR_CNT] = {NULL}; static DJIMotorInstance *dji_motor_instance[DJI_MOTOR_CNT] = {NULL}; // 会在control任务中遍历该指针数组进行pid计算
/** /**
* @brief DJI电机发送以四个一组的形式进行,,6(2can*3group)can_instance专门负责发送 * @brief DJI电机发送以四个一组的形式进行,,6(2can*3group)can_instance专门负责发送
* DJIMotorControl() 使, MotorSenderGrouping() * DJIMotorControl() 使, MotorSenderGrouping()
* *
* @note ,bsp_can中注册
*
* C610(m2006)/C620(m3508):0x1ff,0x200; * C610(m2006)/C620(m3508):0x1ff,0x200;
* GM6020:0x1ff,0x2ff * GM6020:0x1ff,0x2ff
* (rx_id): GM6020: 0x204+id ; C610/C620: 0x200+id * (rx_id): GM6020: 0x204+id ; C610/C620: 0x200+id
@ -69,9 +70,10 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf
{ {
if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id) if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id)
{ {
LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information."); // 后续可以把id和CAN打印出来 LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information.");
while (1) uint16_t can_bus = config->can_handle == &hcan1 ? 1 : 2;
; // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) (1!5!,LTC! (((不是) while (1) // 后续可以把id和CAN打印出来 // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) (1!5!,LTC! (((不是)
LOGERROR("[dji_motor] id [%d], can_bus [%d]", config->rx_id, can_bus);
} }
} }
break; break;
@ -98,16 +100,16 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf
if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id) if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id)
{ {
LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information."); LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information.");
while (1) uint16_t can_bus = config->can_handle == &hcan1 ? 1 : 2;
; // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) while (1) // 后续可以把id和CAN打印出来 // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) (1!5!,LTC! (((不是)
LOGERROR("[dji_motor] id [%d], can_bus [%d]", config->rx_id, can_bus);
} }
} }
break; break;
default: // other motors should not be registered here default: // other motors should not be registered here
LOGERROR("You must not register other motors using the API of DJI motor.");
while (1) while (1)
; // 其他电机不应该在这里注册 LOGERROR("[dji_motor]You must not register other motors using the API of DJI motor."); // 其他电机不应该在这里注册
} }
} }
@ -148,6 +150,9 @@ static void DecodeDJIMotor(CANInstance *_instance)
static void DJIMotorLostCallback(void *motor_ptr) static void DJIMotorLostCallback(void *motor_ptr)
{ {
DJIMotorInstance *motor = (DJIMotorInstance *)motor_ptr;
uint16_t can_bus = motor->motor_can_instance->can_handle == &hcan1 ? 1 : 2;
LOGWARNING("[dji_motor] Motor lost, can bus [%d] , id [%d]", can_bus, motor->motor_can_instance->tx_id);
} }
// 电机初始化,返回一个电机实例 // 电机初始化,返回一个电机实例
@ -182,7 +187,7 @@ DJIMotorInstance *DJIMotorInit(Motor_Init_Config_s *config)
Daemon_Init_Config_s daemon_config = { Daemon_Init_Config_s daemon_config = {
.callback = DJIMotorLostCallback, .callback = DJIMotorLostCallback,
.owner_id = instance, .owner_id = instance,
.reload_count = 1, // 10ms未收到数据则丢失 .reload_count = 2, // 20ms未收到数据则丢失
}; };
instance->daemon = DaemonRegister(&daemon_config); instance->daemon = DaemonRegister(&daemon_config);
@ -195,18 +200,12 @@ DJIMotorInstance *DJIMotorInit(Motor_Init_Config_s *config)
void DJIMotorChangeFeed(DJIMotorInstance *motor, Closeloop_Type_e loop, Feedback_Source_e type) void DJIMotorChangeFeed(DJIMotorInstance *motor, Closeloop_Type_e loop, Feedback_Source_e type)
{ {
if (loop == ANGLE_LOOP) if (loop == ANGLE_LOOP)
{
motor->motor_settings.angle_feedback_source = type; motor->motor_settings.angle_feedback_source = type;
}
else if (loop == SPEED_LOOP) else if (loop == SPEED_LOOP)
{
motor->motor_settings.speed_feedback_source = type; motor->motor_settings.speed_feedback_source = type;
}
else else
{
LOGERROR("[dji_motor] loop type error, check memory access and func param"); // 检查是否传入了正确的LOOP类型,或发生了指针越界 LOGERROR("[dji_motor] loop type error, check memory access and func param"); // 检查是否传入了正确的LOOP类型,或发生了指针越界
} }
}
void DJIMotorStop(DJIMotorInstance *motor) void DJIMotorStop(DJIMotorInstance *motor)
{ {
@ -299,12 +298,10 @@ void DJIMotorControl()
sender_assignment[group].tx_buff[2 * num] = (uint8_t)(set >> 8); // 低八位 sender_assignment[group].tx_buff[2 * num] = (uint8_t)(set >> 8); // 低八位
sender_assignment[group].tx_buff[2 * num + 1] = (uint8_t)(set & 0x00ff); // 高八位 sender_assignment[group].tx_buff[2 * num + 1] = (uint8_t)(set & 0x00ff); // 高八位
// 电机是否停止运行 // 若该电机处于停止状态,直接将buff置零
if (motor->stop_flag == MOTOR_STOP) if (motor->stop_flag == MOTOR_STOP)
{ // 若该电机处于停止状态,直接将buff置零
memset(sender_assignment[group].tx_buff + 2 * num, 0, 16u); memset(sender_assignment[group].tx_buff + 2 * num, 0, 16u);
} }
}
// 遍历flag,检查是否要发送这一帧报文 // 遍历flag,检查是否要发送这一帧报文
for (size_t i = 0; i < 6; ++i) for (size_t i = 0; i < 6; ++i)

View File

@ -6,6 +6,7 @@
#include "string.h" #include "string.h"
#include "daemon.h" #include "daemon.h"
#include "stdlib.h" #include "stdlib.h"
#include "bsp_log.h"
static uint8_t idx; static uint8_t idx;
static HTMotorInstance *ht_motor_instance[HT_MOTOR_CNT]; static HTMotorInstance *ht_motor_instance[HT_MOTOR_CNT];
@ -64,17 +65,14 @@ static void HTMotorDecode(CANInstance *motor_can)
tmp = (uint16_t)(((rxbuff[4] & 0x0f) << 8) | rxbuff[5]); tmp = (uint16_t)(((rxbuff[4] & 0x0f) << 8) | rxbuff[5]);
measure->real_current = CURRENT_SMOOTH_COEF * uint_to_float(tmp, T_MIN, T_MAX, 12) + measure->real_current = CURRENT_SMOOTH_COEF * uint_to_float(tmp, T_MIN, T_MAX, 12) +
(1 - CURRENT_SMOOTH_COEF) * measure->real_current; (1 - CURRENT_SMOOTH_COEF) * measure->real_current;
} }
static void HTMotorLostCallback(void *motor_ptr) static void HTMotorLostCallback(void *motor_ptr)
{ {
HTMotorInstance *motor = (HTMotorInstance *)motor_ptr; HTMotorInstance *motor = (HTMotorInstance *)motor_ptr;
if (motor->stop_flag == MOTOR_STOP) LOGWARNING("[ht_motor] motor %d lost\n", motor->motor_can_instace->tx_id);
return;
if (++motor->lost_cnt % 10 != 0) if (++motor->lost_cnt % 10 != 0)
HTMotorSetMode(CMD_MOTOR_MODE, motor); // 若不在停止模式,尝试重新让电机进入控制模式 HTMotorSetMode(CMD_MOTOR_MODE, motor); // 尝试重新让电机进入控制模式
} }
/* 海泰电机一生黑,什么垃圾协议! */ /* 海泰电机一生黑,什么垃圾协议! */
@ -99,7 +97,7 @@ void HTMotorCalibEncoder(HTMotorInstance *motor)
memcpy(zero_buff, buf, 6); // 初始化的时候至少调用一次,故将其他指令为0时发送的报文保存一下,详见ht04电机说明 memcpy(zero_buff, buf, 6); // 初始化的时候至少调用一次,故将其他指令为0时发送的报文保存一下,详见ht04电机说明
CANTransmit(motor->motor_can_instace, 1); CANTransmit(motor->motor_can_instace, 1);
DWT_Delay(0.005); DWT_Delay(0.005);
HTMotorSetMode(CMD_ZERO_POSITION, motor); HTMotorSetMode(CMD_ZERO_POSITION, motor); // sb 玩意校准完了编码器也不为0
DWT_Delay(0.005); DWT_Delay(0.005);
// HTMotorSetMode(CMD_MOTOR_MODE, motor); // HTMotorSetMode(CMD_MOTOR_MODE, motor);
} }
@ -215,7 +213,7 @@ void HTMotorControlInit()
char ht_id_buff[2] = {0}; char ht_id_buff[2] = {0};
__itoa(i, ht_id_buff, 10); __itoa(i, ht_id_buff, 10);
strcat(ht_task_name, ht_id_buff); // 似乎没什么吊用,osthreaddef会把第一个变量当作宏字符串传入,作为任务名 strcat(ht_task_name, ht_id_buff); // 似乎没什么吊用,osthreaddef会把第一个变量当作宏字符串传入,作为任务名
// todo 还需要一个更优雅的方案来区分不同的电机任务 // @todo 还需要一个更优雅的方案来区分不同的电机任务
osThreadDef(ht_task_name, HTMotorTask, osPriorityNormal, 0, 128); osThreadDef(ht_task_name, HTMotorTask, osPriorityNormal, 0, 128);
ht_task_handle[i] = osThreadCreate(osThread(ht_task_name), ht_motor_instance[i]); ht_task_handle[i] = osThreadCreate(osThread(ht_task_name), ht_motor_instance[i]);
} }

View File

@ -40,3 +40,5 @@ static void HTMotorDecode(CANInstance *motor_can)
} }
} }
``` ```
第一次收到数据时默认电机处于限位处,将速度和角度都设置为零,记录当前的编码器数据,之后每次收到都减去该值.

View File

@ -3,6 +3,7 @@
#include "general_def.h" #include "general_def.h"
#include "daemon.h" #include "daemon.h"
#include "bsp_dwt.h" #include "bsp_dwt.h"
#include "bsp_log.h"
static uint8_t idx; static uint8_t idx;
static LKMotorInstance *lkmotor_instance[LK_MOTOR_MX_CNT] = {NULL}; static LKMotorInstance *lkmotor_instance[LK_MOTOR_MX_CNT] = {NULL};
@ -43,6 +44,12 @@ static void LKMotorDecode(CANInstance *_instance)
measure->total_angle = measure->total_round * 360 + measure->angle_single_round; measure->total_angle = measure->total_round * 360 + measure->angle_single_round;
} }
static void LKMotorLostCallback(void *motor_ptr)
{
LKMotorInstance *motor = (LKMotorInstance *)motor_ptr;
LOGWARNING("[LKMotor] motor lost, id: %d", motor->motor_can_ins->tx_id);
}
LKMotorInstance *LKMotorInit(Motor_Init_Config_s *config) LKMotorInstance *LKMotorInit(Motor_Init_Config_s *config)
{ {
LKMotorInstance *motor = (LKMotorInstance *)malloc(sizeof(LKMotorInstance)); LKMotorInstance *motor = (LKMotorInstance *)malloc(sizeof(LKMotorInstance));
@ -75,7 +82,7 @@ LKMotorInstance *LKMotorInit(Motor_Init_Config_s *config)
Daemon_Init_Config_s daemon_config = { Daemon_Init_Config_s daemon_config = {
.callback = NULL, .callback = NULL,
.owner_id = motor, .owner_id = motor,
.reload_count = 5, // 0.05秒 .reload_count = 5, // 50ms
}; };
motor->daemon = DaemonRegister(&daemon_config); motor->daemon = DaemonRegister(&daemon_config);

View File

@ -1,115 +0,0 @@
#include "ps_handle.h"
uint8_t PS2_RawData[9] = {0};
PS2_Instance PS2_Data = {0};
void PS2_CS(uint8_t Val)
{
if (Val)
HAL_GPIO_WritePin(PS2_CS_GPIOx, PS2_CS_Pin, GPIO_PIN_SET);
else
HAL_GPIO_WritePin(PS2_CS_GPIOx, PS2_CS_Pin, GPIO_PIN_RESET);
}
void PS2_CLK(uint8_t Val)
{
if (Val)
HAL_GPIO_WritePin(PS2_CLK_GPIOx, PS2_CLK_Pin, GPIO_PIN_SET);
else
HAL_GPIO_WritePin(PS2_CLK_GPIOx, PS2_CLK_Pin, GPIO_PIN_RESET);
}
void PS2_DO(uint8_t Val)
{
if (Val)
HAL_GPIO_WritePin(PS2_DO_GPIOx, PS2_DO_Pin, GPIO_PIN_SET);
else
HAL_GPIO_WritePin(PS2_DO_GPIOx, PS2_DO_Pin, GPIO_PIN_RESET);
}
uint8_t PS2_Read_DI()
{
return HAL_GPIO_ReadPin(PS2_DI_GPIOx, PS2_DI_Pin);
}
void PS2_Delay()
{
for (int i = 0; i < 0xBf; i++)
__NOP();
}
uint8_t PS2_ReadWrite_Byte(uint8_t TxData)
{
uint8_t TX = TxData;
uint8_t RX = 0;
for (int i = 0; i < 8; i++)
{
if (TX & 0x01)
PS2_DO(1);
else
PS2_DO(0);
TX >>= 1;
PS2_CLK(1);
PS2_Delay();
PS2_CLK(0);
RX >>= 1;
RX |= (PS2_Read_DI() << 7);
PS2_Delay();
PS2_CLK(1);
PS2_Delay();
}
return RX;
}
static void PS2_Decode()
{
if (PS2_RawData[2] == 0x5A)
{
PS2_Data.Key_Select = (~PS2_RawData[3] >> 0) & 0x01; //选择键
PS2_Data.Key_Start = (~PS2_RawData[3] >> 3) & 0x01; //开始键
//左侧按键
PS2_Data.Key_L_Up = (~PS2_RawData[3] >> 4) & 0x01;
PS2_Data.Key_L_Right = (~PS2_RawData[3] >> 5) & 0x01;
PS2_Data.Key_L_Down = (~PS2_RawData[3] >> 6) & 0x01;
PS2_Data.Key_L_Left = (~PS2_RawData[3] >> 7) & 0x01;
//后侧按键
PS2_Data.Key_L2 = (~PS2_RawData[4] >> 0) & 0x01;
PS2_Data.Key_R2 = (~PS2_RawData[4] >> 1) & 0x01;
PS2_Data.Key_L1 = (~PS2_RawData[4] >> 2) & 0x01;
PS2_Data.Key_R1 = (~PS2_RawData[4] >> 3) & 0x01;
//右侧按键
PS2_Data.Key_R_Up = (~PS2_RawData[4] >> 4) & 0x01;
PS2_Data.Key_R_Right = (~PS2_RawData[4] >> 5) & 0x01;
PS2_Data.Key_R_Down = (~PS2_RawData[4] >> 6) & 0x01;
PS2_Data.Key_R_Left = (~PS2_RawData[4] >> 7) & 0x01;
if (PS2_RawData[1] == 0x41)
{ //无灯模式(摇杆值八向)
PS2_Data.Rocker_LX = 127 * (PS2_Data.Key_L_Right - PS2_Data.Key_L_Left);
PS2_Data.Rocker_LY = 127 * (PS2_Data.Key_L_Up - PS2_Data.Key_L_Down);
PS2_Data.Rocker_RX = 127 * (PS2_Data.Key_R_Right - PS2_Data.Key_R_Left);
PS2_Data.Rocker_RY = 127 * (PS2_Data.Key_R_Up - PS2_Data.Key_R_Down);
}
else if (PS2_RawData[1] == 0x73)
{ //红灯模式(摇杆值模拟)
//摇杆按键
PS2_Data.Key_Rocker_Left = (~PS2_RawData[3] >> 1) & 0x01;
PS2_Data.Key_Rocker_Right = (~PS2_RawData[3] >> 2) & 0x01;
//摇杆值
PS2_Data.Rocker_LX = PS2_RawData[7] - 0x80;
PS2_Data.Rocker_LY = -1 - (PS2_RawData[8] - 0x80);
PS2_Data.Rocker_RX = PS2_RawData[5] - 0x80;
PS2_Data.Rocker_RY = -1 - (PS2_RawData[6] - 0x80);
}
}
}
void PS2_Read_Data(void)
{
PS2_CS(0);
PS2_RawData[0] = PS2_ReadWrite_Byte(0x01); // 0
PS2_RawData[1] = PS2_ReadWrite_Byte(0x42); // 1
for (int i = 2; i < 9; i++)
PS2_RawData[i] = PS2_ReadWrite_Byte(0xff);
PS2_CS(1);
PS2_Decode();
}

View File

@ -1,38 +0,0 @@
#ifndef PS_HANDLE_H
#define PS_HANDLE_H
#include "bsp_spi.h"
#include "bsp_gpio.h"
#include "bsp_dwt.h"
#define PS2_CS_GPIOx GPIOB
#define PS2_CS_Pin GPIO_PIN_12
#define PS2_CLK_GPIOx GPIOB
#define PS2_CLK_Pin GPIO_PIN_13
#define PS2_DO_GPIOx GPIOB
#define PS2_DO_Pin GPIO_PIN_15
#define PS2_DI_GPIOx GPIOB
#define PS2_DI_Pin GPIO_PIN_14
typedef struct
{
uint8_t A_D; //模拟(红灯)为1 数字(无灯)为0
int8_t Rocker_RX, Rocker_RY, Rocker_LX, Rocker_LY; //摇杆值(模拟状态为实际值0-0xFF)(数字态为等效的值0,0x80,0xFF)
//按键值0为未触发,1为触发态
uint8_t Key_L1, Key_L2, Key_R1, Key_R2; //后侧大按键
uint8_t Key_L_Right, Key_L_Left, Key_L_Up, Key_L_Down; //左侧按键
uint8_t Key_R_Right, Key_R_Left, Key_R_Up, Key_R_Down; //右侧按键
uint8_t Key_Select; //选择键
uint8_t Key_Start; //开始键
uint8_t Key_Rocker_Left, Key_Rocker_Right; //摇杆按键
} PS2_Instance;
#endif // !PS_HANDLE_H#define PS_HANDLE_H

View File

@ -1,3 +0,0 @@
# ps_handle
提供ps手柄的支持,其通信协议和spi类似,可以使用bsp_spi来兼容.待编写.

View File

@ -15,8 +15,9 @@
#include "bsp_usart.h" #include "bsp_usart.h"
#include "task.h" #include "task.h"
#include "daemon.h" #include "daemon.h"
#include "bsp_log.h"
#define RE_RX_BUFFER_SIZE 200 #define RE_RX_BUFFER_SIZE 255u // 裁判系统接收缓冲区大小
static USARTInstance *referee_usart_instance; // 裁判系统串口实例 static USARTInstance *referee_usart_instance; // 裁判系统串口实例
static DaemonInstance *referee_daemon; // 裁判系统守护进程 static DaemonInstance *referee_daemon; // 裁判系统守护进程
@ -114,6 +115,7 @@ static void RefereeRxCallback()
static void RefereeLostCallback(void *arg) static void RefereeLostCallback(void *arg)
{ {
USARTServiceInit(referee_usart_instance); USARTServiceInit(referee_usart_instance);
LOGWARNING("[rm_ref] lost referee data");
} }
/* 裁判系统通信初始化 */ /* 裁判系统通信初始化 */
@ -122,7 +124,7 @@ referee_info_t *RefereeInit(UART_HandleTypeDef *referee_usart_handle)
USART_Init_Config_s conf; USART_Init_Config_s conf;
conf.module_callback = RefereeRxCallback; conf.module_callback = RefereeRxCallback;
conf.usart_handle = referee_usart_handle; conf.usart_handle = referee_usart_handle;
conf.recv_buff_size = RE_RX_BUFFER_SIZE; conf.recv_buff_size = RE_RX_BUFFER_SIZE; // mx 255(u8)
referee_usart_instance = USARTRegister(&conf); referee_usart_instance = USARTRegister(&conf);
Daemon_Init_Config_s daemon_conf = { Daemon_Init_Config_s daemon_conf = {
@ -143,5 +145,5 @@ void RefereeSend(uint8_t *send, uint16_t tx_len)
{ {
static TickType_t xLastWakeTime; static TickType_t xLastWakeTime;
USARTSend(referee_usart_instance, send, tx_len, USART_TRANSFER_DMA); USARTSend(referee_usart_instance, send, tx_len, USART_TRANSFER_DMA);
vTaskDelayUntil(&xLastWakeTime, 120); vTaskDelayUntil(&xLastWakeTime, 120); // 裁判系统接收ui数据和多机通信最大支持频率为10Hz
} }

View File

@ -4,6 +4,7 @@
#include "memory.h" #include "memory.h"
#include "stdlib.h" #include "stdlib.h"
#include "daemon.h" #include "daemon.h"
#include "bsp_log.h"
#define REMOTE_CONTROL_FRAME_SIZE 18u // 遥控器接收的buffer大小 #define REMOTE_CONTROL_FRAME_SIZE 18u // 遥控器接收的buffer大小
@ -104,6 +105,7 @@ static void RCLostCallback(void *id)
{ {
memset(rc_ctrl, 0, sizeof(rc_ctrl)); // 清空遥控器数据 memset(rc_ctrl, 0, sizeof(rc_ctrl)); // 清空遥控器数据
USARTServiceInit(rc_usart_instance); // 尝试重新启动接收 USARTServiceInit(rc_usart_instance); // 尝试重新启动接收
LOGWARNING("[rc] remote control lost");
} }
RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle) RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle)

View File

@ -0,0 +1,7 @@
# 利用Ozone进行model-based PID tunning
Ozone的实时变量可视化监测(示波器)功能可以很好地帮助我们观察控制器在时域的表现,典型的有上升时间、超调量和稳态时间等。
## 调试顺序
先内环,后外环。若有已知的外部扰动如阻力、重力等可以在**保持kp不变**的情况下添加积分环节,并查看达到稳态时积分的输出,该输出值可以作为**前馈**作用通过feedforward_ptr一同送入下一个串级控制器。