Toggle navigation
首页
问答
文章
积分商城
专家
专区
更多专区...
文档中心
返回主站
搜索
提问
会员
中心
登录
注册
RoboMaster
stm32F4
基于 RT-Thread 的 RoboMaster 电控框架(四)
发布于 2023-09-18 22:01:34 浏览:607
订阅该版
[tocm] # 基于 RT-Thread 的 RoboMaster 电控框架(四) *由于 RT-Thread 稳定高效的内核,丰富的文档教程,积极活跃的社区氛围,以及设备驱动框架、Kconfig、Scons、日志系统、海量的软件包......很难不选择 RT-Thread 进行项目开发。但也正是因为这些优点的覆盖面较广,很多初学者会觉得无从下手,但只要步入 RT-Thread 的大门,你就发现她的美好。这系列文档将作为本人基于 RT-Thread 开发 RoboMaster 电控框架的记录与分享,希望能帮助到更多初识 RT-Thread 的小伙伴,也欢迎大家交流分享,指正不足,共同进步。* ## 背景 使用的开发板为大疆的 RoboMaster-C 型开发板,基础工程为 rt-thread>bsp>stm32f407-robomaster-c ## IMU姿态解算 使用 BMI088 robomaster-c 开发板上集成的6轴 imu 进行姿态解算,使用的方案其实是RM中比较普遍成熟的一套,主要使用了四元数和卡尔曼滤波进行融合解算,解算频率为 1Khz。 ```c dt = dwt_get_delta(&ins_dwt); imu_ops.gyro_read(ins.gyro); imu_ops.accel_read(ins.accel); // 核心函数,EKF更新四元数 IMU_QuaternionEKF_Update(ins.gyro[X], ins.gyro[Y], ins.gyro[Z], ins.accel[X], ins.accel[Y], ins.accel[Z], dt); memcpy(ins.q, QEKF_INS.q, sizeof(QEKF_INS.q)); // 机体系基向量转换到导航坐标系,本例选取惯性系为导航系 BodyFrameToEarthFrame(xb, ins.xn, ins.q); BodyFrameToEarthFrame(yb, ins.yn, ins.q); BodyFrameToEarthFrame(zb, ins.zn, ins.q); // 将重力从导航坐标系n转换到机体系b,随后根据加速度计数据计算运动加速度 float gravity_b[3]; EarthFrameToBodyFrame(gravity, gravity_b, ins.q); for (uint8_t i = 0; i < 3; ++i) // 同样过一个低通滤波 { ins.motion_accel_b[i] = (ins.accel[i] - gravity_b[i]) * dt / (ins.accel_lpf + dt) + ins.motion_accel_b[i] * ins.accel_lpf / (ins.accel_lpf + dt); } BodyFrameToEarthFrame(ins.motion_accel_b, ins.motion_accel_b, ins.q); // 转换回导航系n ins.yaw = QEKF_INS.Yaw; ins.pitch = QEKF_INS.Pitch; ins.roll = QEKF_INS.Roll; ins.yaw_total_angle = QEKF_INS.YawTotalAngle; ``` ### 恒温控制 C型开发板上的 BMI088 周围是又一圈加热电阻的,可以通过 PWM 控制加热功率,从而实现恒温控制,有助于抑制陀螺仪漂移,根据手册提示恒温控制在40摄氏度较好, ```c static pid_obj_t *imu_temp_pid; static pid_config_t imu_temp_config = { .Kp = 50000, .Ki = 8000, .Kd = 0, .IntegralLimit = 50000, .Improve = PID_Integral_Limit, .MaxOut = 250000, }; static rt_err_t temp_pwm_init(rt_uint32_t period, rt_uint32_t pulse) { temp_pwm_dev = (struct rt_device_pwm *)rt_device_find(TEMP_PWM_DEV_NAME); if (temp_pwm_dev == RT_NULL) { LOG_E("Can't find %s device!", TEMP_PWM_DEV_NAME); return -RT_ERROR; } /* 设置PWM周期和脉冲宽度默认值 */ rt_pwm_set(temp_pwm_dev, TEMP_PWM_DEV_CHANNEL, period, pulse); /* 使能设备 */ rt_pwm_enable(temp_pwm_dev, TEMP_PWM_DEV_CHANNEL); } ``` 在 ins_task 中以 500hz 的频率进行恒温控制,需要注意,使用加热电阻外围电路需要给C板额外供电。 ```c void ins_thread_entry(void *argument) { static uint32_t count; temp_pwm_init(period, pulse); /* 注册 PID 实例 */ imu_temp_pid = pid_register(&imu_temp_config); imu_ops.imu_init(); LOG_I("Example Task Start"); for (;;) { example_start = dwt_get_time_ms(); imu_ops.gyro_read(gyro); imu_ops.accel_read(acc); if(count % 2 == 0){ temp = imu_ops.temp_read(); pulse = pid_calculate(imu_temp_pid, temp, IMU_TARGET_TEMP); rt_pwm_set_pulse(temp_pwm_dev, TEMP_PWM_DEV_CHANNEL, pulse); } count++; rt_thread_delay(1); } } ``` 实际效果测试如下: - 不加恒温控制,室温下(23摄氏度左右)十分钟内,yaw 轴偏移近20度; - 加入恒温控制后(40摄氏度),十分钟内,yaw 轴偏移10度 ### arm_math库使用 有一个小插曲就是arm_math库的移植使用,需要通过修改 Scons 文件,将 arm_math 库链接到工程中,并添加需要的宏定义: ```python # 使用 arm_math.h 需要添加相关内核定义 CPPDEFINES = ['ARM_MATH_CM4'] LIBPATH = [cwd + '/arm_math'] LIBS = ['libarm_cortexM4lf_math.a'] path += [cwd + '/arm_math'] group = DefineGroup('RM_Algorithms', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES, LIBS = LIBS, LIBPATH=LIBPATH) ``` 到此就可以使用解算得到的欧拉角等数据去对云台等进行闭环控制啦 仓库地址放这里了 [HNU_RM_SHARK_C ](https://github.com/Z8MAN8/HNU_RM_SHARK_C) ,觉得不错可以点个 Star ! ## 存在问题及优化方向 1. 虽然通过陀螺仪校准和恒温控制等有效抑制了零漂,但yaw的零飘依然存在; 1. 之后考虑通过融合磁力计数据,解决零飘问题;
3
条评论
默认排序
按发布时间排序
登录
注册新账号
关于作者
螺丝松掉的人
这家伙很懒,什么也没写!
文章
42
回答
0
被采纳
0
关注TA
发私信
相关文章
1
编译stm32F407动态模块报错
2
RTT-STUDIO STM32F4 如何配置 开启FPU功能
3
STM32F405RG CAN1发送波特率设置
4
STM32F401RC 用 RT-Thread Studio 烧写不了程序
5
为什么单片机STM32F405RG只能成功烧录一次?
6
rt-thread studio生成的程序写入stm32f405rg无法运行
7
MCU探索版+RT_Thread+Webnet的疑问
8
STM32F407VG启动硬件定时器系统忙类死机
9
STM32F4的虚拟串口 的USB时钟如何配置
10
stm32客户端TCP Client连接不上pc端的TCP Server
推荐文章
1
RT-Thread应用项目汇总
2
玩转RT-Thread系列教程
3
国产MCU移植系列教程汇总,欢迎查看!
4
机器人操作系统 (ROS2) 和 RT-Thread 通信
5
五分钟玩转RT-Thread新社区
6
【技术三千问】之《玩转ART-Pi》,看这篇就够了!干货汇总
7
关于STM32H7开发板上使用SDIO接口驱动SD卡挂载文件系统的问题总结
8
STM32的“GPU”——DMA2D实例详解
9
RT-Thread隐藏的宝藏之completion
10
【ART-PI】RT-Thread 开启RTC 与 Alarm组件
热门标签
RT-Thread Studio
串口
Env
LWIP
SPI
AT
Bootloader
Hardfault
CAN总线
FinSH
ART-Pi
USB
DMA
文件系统
RT-Thread
SCons
RT-Thread Nano
线程
MQTT
STM32
RTC
FAL
rt-smart
ESP8266
I2C_IIC
UART
WIZnet_W5500
ota在线升级
PWM
cubemx
flash
freemodbus
BSP
packages_软件包
潘多拉开发板_Pandora
定时器
ADC
GD32
flashDB
socket
中断
编译报错
Debug
rt_mq_消息队列_msg_queue
SFUD
msh
keil_MDK
ulog
MicroPython
C++_cpp
本月问答贡献
出出啊
1517
个答案
342
次被采纳
小小李sunny
1444
个答案
290
次被采纳
张世争
812
个答案
177
次被采纳
crystal266
547
个答案
161
次被采纳
whj467467222
1222
个答案
148
次被采纳
本月文章贡献
出出啊
1
篇文章
2
次点赞
小小李sunny
1
篇文章
1
次点赞
张世争
1
篇文章
2
次点赞
crystal266
2
篇文章
2
次点赞
whj467467222
2
篇文章
2
次点赞
回到
顶部
发布
问题
投诉
建议
回到
底部