1 硬件准备
1.1 一块WeAct 的Stm32F411核心板
1.2 2个USB-TTL模块。
1.3 Stm32开发所必须的如STlink烧写器。
1.4 必要的线材。
2 软件准备
2.1 Stm32开发所必备的Keil开发环境。
2.2 PH47框架代码,下载链接
2.3 CSS及BBDB 控制站工程,下载链接
2.4 一个串口调试工具软件。
3 硬件电路连接
3.1 Stm32F411核心板Usart1遥测串口、Usart6调试串口分别连接一个USB-TTL模块。
3.2 两个USB-TTL插入电脑,使用CSS打开遥测串口,使用串口调试工具打开调试串口,波特率均为115200。
3.3 Stm32F411核心板SWD调试口连接如Stlink的烧写器。
4 二次开发
4.1 用户代码位于DevStudio\Application\App_BBDB.cpp(.h)中。
4.2 框架回调功能函数:
CAppBBDB.Init():PH7 框架完全启动后的的初始化函数。用户初始化代码可位于该函数中实现。
CAppBBDB.FastThread_1000Hz():框架快速线程函数,调用频率在400---500hz之间波动。
CAppBBDB.NormalThread_250Hz():框架普通线程函数,调用频率固定为250hz。
CAppBBDB.SlowThread_50Hz():框架慢速线程函数,调用频率固定为50hz。
用户的算法及逻辑实现代码,根据更新频率,以及实际运行时间,合理置于上述三个函数中予以实现即可。相关高级功能使用,见PH47框架二次开发教程。
4.3 PH47框架全局函数、数据总线、参数系统、遥测通讯系统等等的使用示例,见CController_Demo示例类文件:\DevStudio\Algorithms\Controller_Demo.cpp(.h)。
cpp
// Demo_12. 算法层创建自定义控制器类(3/7) - 通用控制器抽象类派生类 CController_Demo 实现
#include "./Controller_Demo.h"
/*
CController_Demo 类为 PH47 控制代码框架 BBDB 固件特意设计的二次开发 Demo 代码集合.
本代码对以下二次开发功能进行了示例(使用 IDE 查找功能在整个项目范围内查找如 "Demo_12." 即可找到该示例的全部操作步骤)
Demo_1. 二次开发代码中基本文件包含
Demo_2. TRACE/gPrintf 调试信息输出语句的使用
Demo_3. 全局时间函数的基本使用
Demo_4. 获取代码运行时间
Demo_5. PH47 代码框架启动完成标志
Demo_6. 数据总线基本操作
Demo_7. 机载参数基本操作
Demo_8. 使用 FreqDiv 类进行循环频率控制
Demo_9. 如何实现调试串口自定义控制命令( 位于 CAppBBDB.HandleConsoleCmd() 函数实现)
Demo_10.下行发送 mavlink 控制命令及状态信息
Demo_11. 解析及响应 GCS 上行控制命令
Demo_12. 算法层创建自定义控制器类
Demo_13. 对自定义控制器类内部运行实施控制
Demo_14. 自定义总线数据项 ( 分别位于DevStudio\BoardConfig\Board_BBDB\DataBus_BBDB.h, BusItemDef4User.h 中)
Demo_15. 自定义全局状态变量 OptiFlowTof_MTF01 (位于 DevStudio\BoardConfig\Board_BBDB\StateVarDef_BBDB.h 文件中)
Demo_16. 自定义机载控制参数 P_TEST_USER_1 (位于 \DevStudio\BoardConfig\Board_BBDB\ParamDict_BBDB.h / .cpp 文件中)
Demo_17. PostMessage 机制使用
Demo_18. Pwm 输入输出控制
在调试串口当中输入命令 debug; 即可对上述示例代码运行效果进行切换
*/
// Demo_1. 二次开发文件包含 - 在 .cpp 文件中对 UseGlobalObject.h 进行文件包含
#include "../Frame/UseGlobalObject.h"
void CController_Demo::Init()
{
// Demo_2. TRACE()/gPrintf() 调试信息输出语句使用:
// 1. TRACE 为使用邮件队列方式显示格式化字符串, 特点是具有线程安全性,且连续调用能够确保顺序正确.
// 依赖于 PH47 框架的启动完成, 框架启动前不能正常工作.
// 显示时刻会晚于函数调用时刻(滞后不高于 10ms 级别)
// 2. gPrintf() 为使用中断方式显示格式化字符串, 不依赖于框架的启动完成
// 连续密集调用时显示的先后顺序可能会发生改变
TRACE("\r\ndemo> 1. TRACE at %.3fms", gGetMills_f());
gPrintf("\r\ndemo> 2. gPrintf at %.3fms", gGetMills_f());
// Demo_3. 全局时间函数的基本使用
// 1. HAL_Delay() 或 osDelay() 函数可用于 ms 级延时, 区别在于 osDelay() 依赖于 FreeRTOS 启动完成(可以简单理解为PH47代码框架启动完成), HAL_Delay 则不依赖
// osDelay() 在延时期间可以将系统资源轮换给其他线程使用, HAL_Delay()则不能
// 2. gDelay_us() 可用于 us 级别延时, 延时时间不要超过 1000us
// 3. gGetMills() 获取调用时刻距离 mcu 加电启动时刻的 ms 时间间隔, 获取数据范围为 4294967296ms,即 1193 hour
// 4. gGetMills_f() 可以获取精确到小数点后3位的 ms 时间, 即可以精确到 us. 但是 gGetMills_f() 在运行时间超过4800s后会溢出重置为 0 后重新开始计时
// 5. gGetMicros() 获取 mcu 加电以来的 us 时间, 注意: us 计时器溢出时间为 600s
osDelay(1);
TRACE("\r\ndemo> 3. TRACE at %dms %.3fms %dus", gGetMills(), gGetMills_f(), gGetMicros());
// Demo_4. 获取代码运行时间 (Step1/2) - 记录代码段执行开始时间
uint32_t uPrevUs = gGetMicros();
// 代码执行...
gDelay_us(200);
// Demo_4. 获取代码运行时间 (Step2/2) - 获取代码段实际执行时间
TRACE("\r\ndemo> 4. Time usage:%dus", gGetTmUsage_us(uPrevUs));
// Demo_5. PH47 代码框架启动完成标志:
// core.blSysInitCompleted 为 true 表示 PH47 代码框架初始化已经全部完成, 此后框架提供的各种功能, 机制均可正常使用
TRACE("\r\ndemo> 5. PH47 init status:%d", core.blSysInitCompleted);
// Demo_8. FreqDiv 类进行循环频率控制(2/3) - 设定循环控制间隔为 1000ms, 即 1Hz
_FreqDemo_1Hz.SetRunInv_ms(1000);
//osDelay(2);
}
void CController_Demo::Reset()
{
}
void CController_Demo::Update(float fDt)
{
// Demo_8. FreqDiv 类进行循环频率控制(2/3)
// 1Hz 循环控制代码实现, 此处注意,_FreqDemo_1Hz 对象的 IsSetRunInv_ms() 函数调用不能在同一循环的多个不同位置重复出现
if(_FreqDemo_1Hz.IsSetRunInv_ms())
{
// Demo_13. 对自定义控制器类内部运行实施控制(2/3)
if(_uUpdateType == DEMO_READ_AHRS)
Demo_Read_Ahrs();
else if(_uUpdateType == DEMO_READ_BARO)
Demo_Read_Baro();
else if(_uUpdateType == DEMO_MAVLINK_SEND)
Demo_Mavlink_Send();
else if(_uUpdateType == DEMO_GET_SET_PWM)
Demo_Get_Set_Pwm();
}
// Demo_17. PostMessage 机制使用 (3/3) - 在循环中队是否有 postmessage 进行检查
if(frm.CheckPostMsg(P_MSG_USER_DEF_DEMO)) // frm.CheckPostMsg() 必须位于一个持续循环中被调用
{
gShowInfo(true, true, MAV_SEVERITY_WARNING, "Get message P_MSG_USER_DEF_DEMO at %.3f", gGetMills_f());
}
}
bool CController_Demo::Function(uint8_t uCallType, void *pData)
{
// 控制器通用操作执行函数
// uCallType 执行操作类型, pData 数据交换指针
bool blRet = false;
// Demo_13. 对自定义控制器类内部运行实施控制(2/3)
_uUpdateType = uCallType;
if(_uUpdateType == DEMO_READ_AHRS)
TRACE("\r\n\r\ndemo> Output ahrs data.");
else if(_uUpdateType == DEMO_READ_BARO)
TRACE("\r\n\r\ndemo> Output baro data.");
else if(_uUpdateType == DEMO_WRITE)
Demo_Write();
else if(_uUpdateType == DEMO_MAVLINK_SEND)
TRACE("\r\n\r\ndemo> Send string and short cmd frame to gcs.");
else if(_uUpdateType == DEMO_GET_SET_PWM)
TRACE("\r\n\r\ndemo> Get pwm in value and set pwm out.");
return blRet;
}
void CController_Demo::Demo_Read_Ahrs()
{
// Demo_7. 机载参数基本操作 - 读取参数
TRACE("\r\n\r\n> %.3f - Firmware:%.0f Tele baud:%.0f",
gGetMills_f(),
core.para.Get(P_FIRMWARE_TYPE),
core.para.Get(P_TELE_USART_BAUD_RATE) ); // 遥测串口通讯速率
// Demo_6. 数据总线基本操作 - 读取数据总线数值示例
Vector3f vAcc = bus.sImu.AccRaw.Get();
Vector3f vGyr = bus.sImu.GyrRaw.Get();
TRACE("\r\n> Acc %.2f %.2f %.2f; Gyr %.2f %.2f %.2f", vAcc.x, vAcc.y, vAcc.z, vGyr.x, vGyr.y, vGyr.z);
// Demo_6. 数据总线基本操作 - 获取总线数据 AccRaw 的时间戳
TRACE("\r\n> AccRaw timeTag:%d.%dms dt:%dus",
bus.sImu.AccRaw.GetTimeStamp_ms(), // 获取 AccRaw 以 ms 为单位时间戳的整数部分
bus.sImu.AccRaw.GetTmStampDec_us(), // 获取 AccRaw 以 ms 为单位时间戳的 3 位小数部分(即精确到 us)
bus.sImu.AccRaw.GetDt2Prev_us()); // 获取 AccRaw 数据项最近两次被设置(Set)之间的时间间隔(us)
/*
此处需要对前后两次调用 bus.sImu.AccRaw.GetTmStampDec_us() 计算得出的时间间隔与 bus.sImu.AccFilted.GetDt2Prev_us()
得出的总线数据 AccRaw 被设置的时间间隔不一致问题进行解释:
bus.sImu. 数据是 idle 线程被设置,该线程循环频率大概是 1500-2000hz 之间波动
GetTimeStamp_ms及GetTmStampDec_us() 函数获取的总线数据最近一一次被设置的时间,由于上述代码被调用频率为 1hz,故计算出的时间间隔
大概在1000ms左右
GetDt2Prev_us() 函数获取的是总线数据最近两次被设置的时间间隔,所以该时间间隔为 idle 线程运行时间间隔
*/
TRACE("\r\n> Roll %.1f Pitch %.1f Yaw %.1f",
degrees(bus.sAhrs.Roll.Get()), // degrees() 弧度 --> 角度
degrees(bus.sAhrs.Pitch.Get()),
degrees(bus.sAhrs.Yaw.Get()));
}
void CController_Demo::Demo_Read_Baro()
{
// Demo_6. 数据总线基本操作 - 读取数据总线数值示例
BARO_RAW sBaroRaw = bus.sBaro.Raw.Get();
BARO_EXT sBaroExt = bus.sBaro.Ext.Get();
TRACE("\r\n> Press:%.1f Temp:%.1f Alt:%.2f", sBaroRaw.fAbsPress, sBaroRaw.fRawTemp, sBaroExt.altitude);
TRACE("\r\n> arDbg[0]=%.1f", bus.arDbg_2[0].Get());
// Demo_6. 数据总线基本操作 - 全局状态变量读取, gGetStatus() 等同于 core.GetStatus()
TRACE("\r\n> Global status - ImuStill:%d RcAlive:%d", gGetStatus(S_IMU_STILL), core.GetStatus(S_RC_ALIVE));
}
void CController_Demo::Demo_Write()
{
// Demo_6. 数据总线基本操作 - 写入数据总线数值
TRACE("\r\n\r\n>>> Write bus arDbg[0] to 2.234f, and set para to change pilot placement.");
bus.arDbg_2[0].Set(2.234);
// Demo_7. 机载参数基本操作 - 设置存储机载数据参数 P_PILOT_PLACEMENT(飞控板安装方向)
// Set pilot placement to head forward and right side down)
core.para.Set(P_PILOT_PLACEMENT, ROTATE_ROLL_90); // 仅仅更新内存中的参数设置
// core.para.Set(P_PILOT_PLACEMENT, ROTATE_ROLL_90, true); // 更新内存中的参数设置, 并保存至存储器
}
void CController_Demo::Demo_Mavlink_Send()
{
// Demo_10.下行发送 mavlink 控制命令及状态信息 - 状态信息发送
char szSend[32];
gFormat(szSend, "String to GCS at %d", gGetMills());
core.mavlink.AddMsg_StatusText(szSend, MAV_SEVERITY_INFO);
// 上述代码实际效果与如下语句相同:
// gShowInfo(false, true, MAV_SEVERITY_INFO, "String to GCS at %d", gGetMills());
// Demo_10.下行发送 mavlink 控制命令及状态信息 - 自定义短控制命令发送
Vector3f vTmp = bus.sImu.MagRaw.Get();
mavlink_user_def_data_t packet;
packet.ID = 0xA5;
packet.Para_16 = (int16_t) vTmp.x;
packet.Para_32 = gGetMills();
core.mavlink.AddMsg_UserDefData(&packet);
}
void CController_Demo::Demo_Get_Set_Pwm()
{
// Demo_18. Pwm 输入输出控制
int16_t uPwmIn_1 = drv._pPwm->GetPwmIn(PWM_IN_CH1);
int16_t uPwmIn_2 = drv._pPwm->GetPwmIn(PWM_IN_CH2);
int16_t uPwmIn_3 = drv._pPwm->GetPwmIn(PWM_IN_CH3);
int16_t uPwmIn_4 = drv._pPwm->GetPwmIn(PWM_IN_CH4);
TRACE("\r\n> Pmw in: %d %d %d %d", uPwmIn_1, uPwmIn_2, uPwmIn_3, uPwmIn_4);
drv._pPwm->SetPwmWidth(PWM_IN_CH1, constrain_int16(uPwmIn_1, 1000, 2000));
drv._pPwm->SetPwmWidth(PWM_IN_CH2, constrain_int16(uPwmIn_2, 1000, 2000));
drv._pPwm->SetPwmWidth(PWM_IN_CH3, constrain_int16(uPwmIn_3, 1000, 2000));
drv._pPwm->SetPwmWidth(PWM_IN_CH4, constrain_int16(uPwmIn_4, 1000, 2000));
}
4.4 编译、连接、烧写。
使用 css 打开遥测串口。若电路连接及配置正确,则 css 显示飞控工作时间及接收帧计数等相关信息。同时,调试串口输出相关信息。
由于当前硬件配置为最小系统配置,未连接任何传感器,故相关数据尾0或无效。但 ph47框架所有功能均已齐备,可以开展一定范围内的二次开发工作。
5 完全功能的二次开发
5.1 准备一块BBP v2或BBP FEI或BBP mini飞控板,然后重复步骤2---4。
更多内容见CSDN博客专栏:无人机飞控
相关资源:https://gitee.com/ss15/ph47