修复了HT电机PID计算的bug

This commit is contained in:
NeoZng 2023-02-14 17:36:02 +08:00
parent cff796dbff
commit 53bdf1707c
18 changed files with 83 additions and 53 deletions

View File

@ -112,6 +112,7 @@ void HardFault_Handler(void)
/* USER CODE END HardFault_IRQn 0 */ /* USER CODE END HardFault_IRQn 0 */
while (1) while (1)
{ {
asm("bx lr");
/* USER CODE BEGIN W1_HardFault_IRQn 0 */ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */ /* USER CODE END W1_HardFault_IRQn 0 */
} }

View File

@ -18,7 +18,6 @@
VSCode可通过Cortex-Debug利用OpenOCD进行调试jlink/stlink/dap-link都支持具体的使用方法和环境配置教程在[VSCode+Ozone使用方法](./VSCode+Ozone使用方法.md)中。**请使用UTF-8编码查看\&编辑此项目**。 VSCode可通过Cortex-Debug利用OpenOCD进行调试jlink/stlink/dap-link都支持具体的使用方法和环境配置教程在[VSCode+Ozone使用方法](./VSCode+Ozone使用方法.md)中。**请使用UTF-8编码查看\&编辑此项目**。
- **分层** - **分层**
本框架主要代码分为**BSP、Module、APP**三层。三层的代码分别存放在同名的三个文件夹中这三个文件夹存放在根目录下。开发过程中主要编写APP层代码Module层与BSP层不建议修改。如需添加module如oled屏幕、其他传感器和外设等请按照规范编写并联系组长提交commit到dev分支或对应的功能名分支完善后合并至主分支。在配置git的时候将自己的`user.name`配置成英文缩写或易懂的nick name。 本框架主要代码分为**BSP、Module、APP**三层。三层的代码分别存放在同名的三个文件夹中这三个文件夹存放在根目录下。开发过程中主要编写APP层代码Module层与BSP层不建议修改。如需添加module如oled屏幕、其他传感器和外设等请按照规范编写并联系组长提交commit到dev分支或对应的功能名分支完善后合并至主分支。在配置git的时候将自己的`user.name`配置成英文缩写或易懂的nick name。
@ -104,8 +103,6 @@
} CANInstance; } CANInstance;
``` ```
## BSP层(Board Sopport Package) ## BSP层(Board Sopport Package)
- TODO - TODO
@ -175,11 +172,10 @@ Module层主要存放的是类型定义和实例指针数组在该层没有
- 对于单板的情况所有应用之间的信息交互通过message center完成。而使用双板时需要通过板间通信传递控制信息默认遥控器接收机和pc在云台板裁判系统在底盘板因此需要互发信息。当前通过**条件编译**来控制信息的去向发往message center/接收还是通过can comm发送/接收后续考虑将双板通信纳入message center的实现中根据`robot_def.h`的开发板定义自动处理通信,降低应用层级的逻辑复杂度。 - 对于单板的情况所有应用之间的信息交互通过message center完成。而使用双板时需要通过板间通信传递控制信息默认遥控器接收机和pc在云台板裁判系统在底盘板因此需要互发信息。当前通过**条件编译**来控制信息的去向发往message center/接收还是通过can comm发送/接收后续考虑将双板通信纳入message center的实现中根据`robot_def.h`的开发板定义自动处理通信,降低应用层级的逻辑复杂度。
## 文件树 ## 文件树
板级支持包的每个组件,每个moduel,以及每个app都有对应的说明文档. 板级支持包的每个组件,每个moduel,以及每个app都有对应的说明文档.
```shell ```shell
ROOT:. ROOT:.
│ .gitignore # git版本管理忽略文件 │ .gitignore # git版本管理忽略文件
@ -394,14 +390,10 @@ ROOT:.
vofa.h vofa.h
``` ```
## BSP/Module/Application介绍 ## BSP/Module/Application介绍
在对应应用、模块和板级支持包文件夹下。每个.c文件或完整的功能模块都有说明文档。在编写新代码时注意按照规范编写说明文档。 在对应应用、模块和板级支持包文件夹下。每个.c文件或完整的功能模块都有说明文档。在编写新代码时注意按照规范编写说明文档。
## 整体架构 ## 整体架构
### 软件分层 ### 软件分层
@ -424,4 +416,3 @@ HAL库初始化 --> BSP初始化 --> Application初始化 --> app调用其拥有
APP会调用其所有的模块的初始化函数注册函数这是因为本框架的设计思想是任何模块在被注册构造/初始化)之前,都是不存在的,当且仅当定义了一个模块结构体(也称实例)的时候,才有一个实体的概念。 APP会调用其所有的模块的初始化函数注册函数这是因为本框架的设计思想是任何模块在被注册构造/初始化)之前,都是不存在的,当且仅当定义了一个模块结构体(也称实例)的时候,才有一个实体的概念。
main函数唯一需要的函数是app层的`robot.c`中的`RobotInit()`函数它首先会调用BSP初始化然后进行所有应用的初始化每个应用会调用对应模块的初始化一些依赖通信外设的模块会将通信支持相关的bsp进行初始化。初始化结束之后实时系统启动。 main函数唯一需要的函数是app层的`robot.c`中的`RobotInit()`函数它首先会调用BSP初始化然后进行所有应用的初始化每个应用会调用对应模块的初始化一些依赖通信外设的模块会将通信支持相关的bsp进行初始化。初始化结束之后实时系统启动。

View File

@ -89,7 +89,7 @@
#### LQR #### LQR
- [ ] 通用的LQR控制器 - [ ] 通用的LQR控制器(矩阵运算)
@ -183,8 +183,7 @@
#### ==robot_cmd== #### ==robot_cmd==
- [ ] 键盘控制 - [ ] 键鼠控制
- [ ] 鼠标控制
- [x] 双板兼容(待测试) - [x] 双板兼容(待测试)
#### ==chassis== #### ==chassis==

View File

@ -267,7 +267,7 @@ typedef struct
> **如果你使用basic_framework不需要重新生成代码。** > **如果你使用basic_framework不需要重新生成代码。**
- **建议将ozone和jlink的目录一同加入环境变量方便我们后续的一键下载和一键调试配置**
## VSCode编译和调试配置 ## VSCode编译和调试配置
@ -483,18 +483,20 @@ VSCode `ctrl+,`进入设置,通过`搜索`找到cortex-debug插件的设置。
2. Hex Editor在查看汇编代码和机器代码的时候提供2、10、16进制转换并且可以以16进制或2进制的格式编辑文件。 2. Hex Editor在查看汇编代码和机器代码的时候提供2、10、16进制转换并且可以以16进制或2进制的格式编辑文件。
3. GitLens提供强大的可视化Git支持 3. GitLens和git graph提供强大的可视化commit记录和UI支持
4. Blockman - Highlight Nested Code Blocks 此插件会高亮嵌套的代码块即花括号包围的部分或for/while/ifelse代码块 4. Blockman - Highlight Nested Code Blocks 此插件会高亮嵌套的代码块即花括号包围的部分或for/while/ifelse代码块,对于多层条件和循环嵌套效果非常炸裂
5. bookmark 提供代码中插入书签的功能,从而快速在页面间跳转。 5. bookmark 提供代码中插入书签的功能,从而快速在页面间跳转。
6. Code Issue Manager为团队提供issues和todo管理方便协同开发 6. Code Issue Manager为团队提供issues和todo管理方便协同开发
7. github copilot超强超快需要一些小钱 7. github copilot超强超快需要一些小钱10块用一年你也可以在github上申请student pack需要学信网认证和学生卡但有一定概率无法通过 在插件中你也可以找到一些免费的copilot替代品。
8. `ctrl+k ctrl+s`配置属于你的快捷键,提高效率! 8. `ctrl+k ctrl+s`配置属于你的快捷键,提高效率!
9. live share和你的小伙伴一起结对编程
@ -575,7 +577,7 @@ Project.SetOSPlugin(“plugin_name”)
![image-20221119174445067](assets/image-20221119174445067.png) ![image-20221119174445067](assets/image-20221119174445067.png)
我们的项目是F4的板子内核时Cortex-M4CM4因此选用`FreeRTOSPlugin_CM4.js`输入的时候js后缀不用输 我们的项目是F4的板子内核时Cortex-M4CM4因此选用`FreeRTOSPlugin_CM4.js`输入的时候js后缀不用输 ozone默认输入的命令似乎有误需要手动修改这好像和ozone的版本有关请留意
### 常用调试窗口和功能 ### 常用调试窗口和功能
@ -672,6 +674,14 @@ CPU选项卡可以查看CPU的寄存器。
| 右键+break on change | 当变量发生变化的时候进入此断点 | | 右键+break on change | 当变量发生变化的时候进入此断点 |
| ctrl+H | 展示调用图,会列出该函数调用的所有函数(内部调用栈) | | ctrl+H | 展示调用图,会列出该函数调用的所有函数(内部调用栈) |
如果你使用拥有多个按键的鼠标,推荐将侧键前设置为ctrl+点击以查看声明/定义,侧键后设置为添加到watch(debug),侧滚轮设置为前进后退(历史)
你还可以按ctrl+K ctrl+S进入快捷键设置页面,将tab设置为下一个提示,用enter接受intelliSense建议,这样不需要将手移出主键盘区域. 将ctrl+;设置为移动到行尾,同时打开c/c++的函数括号不全,这样不需要手动敲击括号.
将alt+k设置为左移,alt+l设置为右移,这样不需要方向键.
选择最适合自己的配置!
### 保存调试项目 ### 保存调试项目
退出时可以将调试项目保存在项目的根目录下方便下次调试使用不需要重新设置。可以为jlink和daplink分别保存一套调试配置。 退出时可以将调试项目保存在项目的根目录下方便下次调试使用不需要重新设置。可以为jlink和daplink分别保存一套调试配置。
@ -883,6 +893,7 @@ $(BUILD_DIR): # 如果makefile所处的文件目录下没有build文件夹,这
####################################### #######################################
clean: clean:
rm -r $(BUILD_DIR) rm -r $(BUILD_DIR)
# 你的makefile可能会使用cmd而不是powershell来调用内核,而cmd不支持rm命令,因此可能要修改为rd (remove directory),cmd传入参数的方式为 /x ,x为要传入的参数
####################################### #######################################

View File

@ -92,9 +92,13 @@ CANInstance *CANRegister(CAN_Init_Config_s *config)
uint8_t CANTransmit(CANInstance *_instance,uint8_t timeout) uint8_t CANTransmit(CANInstance *_instance,uint8_t timeout)
{ {
float dwt_start = DWT_GetTimeline_ms(); float dwt_start = DWT_GetTimeline_ms();
while (HAL_CAN_GetTxMailboxesFreeLevel(_instance->can_handle) == 0) // 等待邮箱空闲 while (HAL_CAN_GetTxMailboxesFreeLevel(_instance->can_handle) == 0);// 等待邮箱空闲
{
if (DWT_GetTimeline_ms() - dwt_start > timeout) // 超时 if (DWT_GetTimeline_ms() - dwt_start > timeout) // 超时
{
return 0; return 0;
}
}
// tx_mailbox会保存实际填入了这一帧消息的邮箱,但是知道是哪个邮箱发的似乎也没啥用 // tx_mailbox会保存实际填入了这一帧消息的邮箱,但是知道是哪个邮箱发的似乎也没啥用
HAL_CAN_AddTxMessage(_instance->can_handle, &_instance->txconf, _instance->tx_buff, &_instance->tx_mailbox); HAL_CAN_AddTxMessage(_instance->can_handle, &_instance->txconf, _instance->tx_buff, &_instance->tx_mailbox);
return 1; // 发送成功 return 1; // 发送成功

View File

@ -10,7 +10,7 @@
* @copyright Copyright (c) 2023 * @copyright Copyright (c) 2023
* *
*/ */
#pragma once
#include "usb_device.h" #include "usb_device.h"
#include "usbd_cdc.h" #include "usbd_cdc.h"
#include "usbd_conf.h" #include "usbd_conf.h"

View File

@ -0,0 +1,6 @@
# encoder
提供对光电和霍尔磁编码器的支持.
可能需要新增bsp_tim以提供period lapse和tim编码器计数的功能.

View File

@ -6,7 +6,8 @@
* @date 2022-11-01 * @date 2022-11-01
* *
* @todo 1. 使 * @todo 1. 使
2. M2006和M3508增加开环的零位校准函数 2. M2006和M3508增加开环的零位校准函数,()
3.
* @copyright Copyright (c) 2022 HNU YueLu EC all rights reserved * @copyright Copyright (c) 2022 HNU YueLu EC all rights reserved
* *

View File

@ -177,7 +177,7 @@ void DJIMotorChangeFeed(dji_motor_instance *motor,
Feedback_Source_e type); Feedback_Source_e type);
``` ```
调用第一个并传入设定值它会自动根据你设定的PID参数进行动作。 调用第一个并传入设定值它会自动根据你设定的PID参数进行动作。 如果对不同闭环都有参考输入,则设置最外层的闭环(通过此函数)并将剩下的参考输入通过前馈数据指针进行设定
调用第二个并设定要修改的反馈环节和反馈类型,它会将反馈数据指针切换到你设定好的变量(需要在初始化的时候设置反馈指针)。 调用第二个并设定要修改的反馈环节和反馈类型,它会将反馈数据指针切换到你设定好的变量(需要在初始化的时候设置反馈指针)。

View File

@ -6,17 +6,17 @@ static uint8_t idx;
HTMotorInstance *ht_motor_instance[HT_MOTOR_CNT]; HTMotorInstance *ht_motor_instance[HT_MOTOR_CNT];
/** /**
* @brief * @brief ,[0xff,0xff,0xff,0xff,0xff,0xff,0xff,cmd]
* *
* @param cmd * @param cmd
* @param motor * @param motor
*/ */
static void HTMotorSetMode(HTMotor_Mode_t cmd, HTMotorInstance *motor) static void HTMotorSetMode(HTMotor_Mode_t cmd, HTMotorInstance *motor)
{ {
static uint8_t buf[8] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00}; memset(motor->motor_can_instace->tx_buff, 0xff, 7); // 发送电机指令的时候前面7bytes都是0xff
buf[7] = (uint8_t)cmd; motor->motor_can_instace->tx_buff[7] = (uint8_t)cmd; // 最后一位是命令id
memcpy(motor->motor_can_instace->tx_buff, buf, sizeof(buf));
CANTransmit(motor->motor_can_instace, 1); CANTransmit(motor->motor_can_instace, 1);
memset(motor->motor_can_instace->tx_buff, 0, 6); // 发送控制指令的时候前面6bytes都是0
} }
/* 两个用于将uint值和float值进行映射的函数,在设定发送值和解析反馈值时使用 */ /* 两个用于将uint值和float值进行映射的函数,在设定发送值和解析反馈值时使用 */
@ -53,7 +53,7 @@ static void HTMotorDecode(CANInstance *motor_can)
measure->total_angle = RAD_2_ANGLE * uint_to_float(tmp, P_MIN, P_MAX, 16); measure->total_angle = RAD_2_ANGLE * uint_to_float(tmp, P_MIN, P_MAX, 16);
tmp = (uint16_t)((rxbuff[3] << 4) | (rxbuff[4] >> 4)); tmp = (uint16_t)((rxbuff[3] << 4) | (rxbuff[4] >> 4));
measure->speed_aps = RAD_2_ANGLE * SPEED_SMOOTH_COEF * uint_to_float(tmp, V_MIN, V_MAX, 12) + measure->speed_aps = SPEED_SMOOTH_COEF * uint_to_float(tmp, V_MIN, V_MAX, 12) +
(1 - SPEED_SMOOTH_COEF) * measure->speed_aps; (1 - SPEED_SMOOTH_COEF) * measure->speed_aps;
tmp = (uint16_t)(((rxbuff[4] & 0x0f) << 8) | rxbuff[5]); tmp = (uint16_t)(((rxbuff[4] & 0x0f) << 8) | rxbuff[5]);
@ -102,7 +102,7 @@ void HTMotorControl()
motor = ht_motor_instance[i]; motor = ht_motor_instance[i];
measure = &motor->motor_measure; measure = &motor->motor_measure;
setting = &motor->motor_settings; setting = &motor->motor_settings;
motor_can = motor_can; motor_can = motor->motor_can_instace;
pid_ref = motor->pid_ref; pid_ref = motor->pid_ref;
if ((setting->close_loop_type & ANGLE_LOOP) && setting->outer_loop_type == ANGLE_LOOP) if ((setting->close_loop_type & ANGLE_LOOP) && setting->outer_loop_type == ANGLE_LOOP)
@ -111,8 +111,8 @@ void HTMotorControl()
pid_measure = *motor->other_angle_feedback_ptr; pid_measure = *motor->other_angle_feedback_ptr;
else else
pid_measure = measure->real_current; pid_measure = measure->real_current;
// measure单位是rad,ref是角度,统一到angle下计算,方便建模
pid_ref = PID_Calculate(&motor->angle_PID, pid_measure, pid_ref); pid_ref = PID_Calculate(&motor->angle_PID, pid_measure*RAD_2_ANGLE, pid_ref);
} }
if ((setting->close_loop_type & SPEED_LOOP) && setting->outer_loop_type & (ANGLE_LOOP | SPEED_LOOP)) if ((setting->close_loop_type & SPEED_LOOP) && setting->outer_loop_type & (ANGLE_LOOP | SPEED_LOOP))
@ -124,8 +124,8 @@ void HTMotorControl()
pid_measure = *motor->other_speed_feedback_ptr; pid_measure = *motor->other_speed_feedback_ptr;
else else
pid_measure = measure->speed_aps; pid_measure = measure->speed_aps;
// measure单位是rad / s ,ref是angle per sec,统一到angle下计算
pid_ref = PID_Calculate(&motor->angle_PID, pid_measure, pid_ref); pid_ref = PID_Calculate(&motor->speed_PID, pid_measure*RAD_2_ANGLE, pid_ref);
} }
if (setting->close_loop_type & CURRENT_LOOP) if (setting->close_loop_type & CURRENT_LOOP)
@ -140,8 +140,9 @@ void HTMotorControl()
if (setting->reverse_flag == MOTOR_DIRECTION_REVERSE) if (setting->reverse_flag == MOTOR_DIRECTION_REVERSE)
set *= -1; set *= -1;
tmp = float_to_uint(set, T_MIN, T_MAX, 12); LIMIT_MIN_MAX(set, T_MIN, T_MAX); // 限幅,实际上这似乎和pid输出限幅重复了
motor_can->tx_buff[6] = tmp >> 8; tmp = float_to_uint(set, T_MIN, T_MAX, 12); // 数值最后在 -12~+12之间
motor_can->tx_buff[6] = (tmp >> 8);
motor_can->tx_buff[7] = tmp & 0xff; motor_can->tx_buff[7] = tmp & 0xff;
if (motor->stop_flag == MOTOR_STOP) if (motor->stop_flag == MOTOR_STOP)
@ -155,11 +156,13 @@ void HTMotorControl()
void HTMotorStop(HTMotorInstance *motor) void HTMotorStop(HTMotorInstance *motor)
{ {
HTMotorSetMode(CMD_RESET_MODE, motor); HTMotorSetMode(CMD_RESET_MODE, motor);
motor->stop_flag = MOTOR_STOP;
} }
void HTMotorEnable(HTMotorInstance *motor) void HTMotorEnable(HTMotorInstance *motor)
{ {
HTMotorSetMode(CMD_MOTOR_MODE, motor); HTMotorSetMode(CMD_MOTOR_MODE, motor);
motor->stop_flag = MOTOR_ENALBED;
} }
void HTMotorCalibEncoder(HTMotorInstance *motor) void HTMotorCalibEncoder(HTMotorInstance *motor)

View File

@ -18,9 +18,9 @@
#define T_MAX 18.0f #define T_MAX 18.0f
typedef struct // HT04 typedef struct // HT04
{ // 角度为多圈角度,范围是-95.5~95.5,单位为rad {
float last_angle; float last_angle;
float total_angle; float total_angle; // 角度为多圈角度,范围是-95.5~95.5,单位为rad
float speed_aps; float speed_aps;
float real_current; float real_current;
} HTMotor_Measure_t; } HTMotor_Measure_t;

View File

@ -11,14 +11,14 @@ void MotorControlTask()
// static uint8_t cnt = 0; 设定任务频率 // static uint8_t cnt = 0; 设定任务频率
// if(cnt%5==0) //200hz // if(cnt%5==0) //200hz
// if(cnt%10==0) //100hz // if(cnt%10==0) //100hz
DJIMotorControl(); DJIMotorControl();
//LKMotorControl(); /* 如果有对应的电机则取消注释,可以加入条件编译或者register对应的idx判断是否注册了电机 */
LKMotorControl();
//HTMotorControl(); HTMotorControl();
//ServeoMotorControl(); ServeoMotorControl();
//StepMotorControl(); //StepMotorControl();
} }

View File

@ -16,6 +16,8 @@
* @brief ,RTOS中应该设定为1Khz运行 * @brief ,RTOS中应该设定为1Khz运行
* 20Hz或更低 * 20Hz或更低
* *
* @note ,,.
*
*/ */
void MotorControlTask(); void MotorControlTask();

View File

@ -80,7 +80,7 @@ void Servo_Motor_Type_Select(ServoInstance *Servo_Motor, int16_t mode)
* @brief * @brief
* *
*/ */
void Servo_Motor_Control() void ServeoMotorControl()
{ {
static ServoInstance *Servo_Motor; static ServoInstance *Servo_Motor;

View File

@ -86,5 +86,5 @@ typedef struct
ServoInstance *ServoInit(Servo_Init_Config_s *Servo_Init_Config); ServoInstance *ServoInit(Servo_Init_Config_s *Servo_Init_Config);
void Servo_Motor_FreeAngle_Set(ServoInstance *Servo_Motor, int16_t S_angle); void Servo_Motor_FreeAngle_Set(ServoInstance *Servo_Motor, int16_t S_angle);
void Servo_Motor_Type_Select(ServoInstance *Servo_Motor,int16_t mode); void Servo_Motor_Type_Select(ServoInstance *Servo_Motor,int16_t mode);
void Servo_Motor_Control(); void ServeoMotorControl();
#endif // SERVO_MOTOR_H #endif // SERVO_MOTOR_H

View File

@ -1,6 +1,10 @@
##舵机的使用 ##舵机的使用
<p align='left' >panrui@hnu.edu.cn</p> <p align='left' >panrui@hnu.edu.cn</p>
> todo: 由于新增了bsp_pwm的支持,舵机模块需要部分重构
### 舵机基础知识 ### 舵机基础知识
已最常见的SG90舵机为例SG90舵机要求工作在频率为50HZ——周期为20ms的PWM波且对应信号的高低电平在0.5ms - 2.5ms之间对应的舵机转动角度如下表所示当然也可以按照这个线性的对应关系去达到转动自己想要的角度如想要转动60°则高电平脉宽为大概为1.2ms,具体能不能转到特定的角度还和舵机的精度有关) 已最常见的SG90舵机为例SG90舵机要求工作在频率为50HZ——周期为20ms的PWM波且对应信号的高低电平在0.5ms - 2.5ms之间对应的舵机转动角度如下表所示当然也可以按照这个线性的对应关系去达到转动自己想要的角度如想要转动60°则高电平脉宽为大概为1.2ms,具体能不能转到特定的角度还和舵机的精度有关)
>0.5ms-------------0度 2.5% >0.5ms-------------0度 2.5%

View File

@ -1,3 +1,5 @@
# 推荐安装powershell7 以获得更好的shell体验!
JLinkGDBServer: JLinkGDBServer:
$(Q)JLinkGDBServer -select USB -device $(CHIP) \ $(Q)JLinkGDBServer -select USB -device $(CHIP) \

View File

@ -1,3 +1,9 @@
# 禁止在临界区使用延时,这会导致因中断关闭定时器无法进入中断更新时间,进而卡死系统 # 禁止在临界区使用延时,这会导致因中断关闭使得定时器无法进入中断更新时间,进而卡死系统
除非你使用的是基于计数寄存器差值的延时方法,或阻塞式的for延时
# 禁止摸鱼 # 禁止摸鱼
提供工作效率!
#