PH47框架下BBDB飞控基础开发平台极简教程

news2024/11/25 3:44:11

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)。



// 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

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/2211662.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

鸿蒙面试的一些可能问到的点

页面跳转 router 鸿蒙中跳转主要有两种,一种是router,一种是Navigation,官方推荐使用Navigation。 Router适用于模块间与模块内页面切换,通过每个页面的url实现模块间解耦。模块内页面跳转时,为了实现更好的转场动效…

7.2-I2C的DMA中断

I2C的DMA中断 请先阅读完I2C的普通中断模式以后再阅读本教程 i2c的DMA模式 1.添加通道 ,添加后的参数保持默认 2.可以看到自动给我们DMA添加了中断向量。 保存后只需要将下面_ IT改为_ DMA即可 运行代码 i2c1) { aht20State 4; } } /* USER CODE END 0 */ 以上就…

ssm基于java的网上手机销售系统

系统包含:源码论文 所用技术:SpringBootVueSSMMybatisMysql 免费提供给大家参考或者学习,获取源码请私聊我 需要定制请私聊 目 录 目 录 III 1 绪论 1 1.1 研究背景 1 1.2 目的和意义 1 1.3 论文结构安排 2 2 相关技术 3 2.1 SSM框…

yolov5环境GPU搭建 ,用GPU跑polov5算法

win10NVIDIA GeForce RTX 3050torch1.13.1torchaudio0.13.1torchvision 0.14.1 cuda11.7python3.8cudnn8.7.0 在环境搭建中踩了许多坑,yolov5环境的搭建需要依赖很多环境,用cpu跑很容易跑单张识别,用GPU跑却踩了很多坑,不过GPU环…

Mac 备忘录妙用

之前使用 Windows 的过程中,最痛苦的事是没有一款可以满足我快速进行记录的应用 基本都得先打开该笔记软件,然后创建新笔记,最后才能输入,这么多步骤太麻烦了 在切换到 MacOS 之后,让我惊喜的就是自带的备忘录&#…

【java面经thinking】一

目录 类加载过程 加载: 连接 初始化 GC回收机制(垃圾回收) 区域 判断对象是否存活 回收机制 HashMap 类加载器 加载标识 加载机制 缓存 自定义加载器: JVM内存结构 常量池 string设置成final 按下网址发生 类加…

C语言有关结构体的知识(后有通讯录的实现)

一、结构体的声明 1.1 结构体的定义 结构体是一些值的集合,这些值被称为成员变量。结构的每个成员可以是不同的类型 1.2 结构体的声明 这里以描述一个学生为例: struct stu {char name[10];//名字int age;//年龄char id[20];//学号char sex[5];//性别 }…

TIM定时器(标准库)

目录 一. 前言 二. 定时器的框图 三. 定时中断的基本结构 四. TIM定时器相关代码 五. 最终现象展示 一. 前言 什么是定时器? 定时器可以对输入的时钟进行计数,并在计数值达到设定值时触发中断。 TIM定时器不仅具备基本的定时中断功能,而且…

【LeetCode】708. 循环有序列表的插入

目录 一、题目二、解法完整代码 一、题目 给定循环单调非递减列表中的一个点,写一个函数向这个列表中插入一个新元素 insertVal ,使这个列表仍然是循环非降序的。 给定的可以是这个列表中任意一个顶点的指针,并不一定是这个列表中最小元素的…

2024免费mac苹果电脑清理垃圾软件CleanMyMac X4.15.8

对于苹果电脑用户来说,设备上积累的垃圾文件可能会导致存储空间变得紧张,影响电脑的性能和使用体验。尤其是那些经常下载和安装新应用、编辑视频或处理大量照片的用户,更容易感受到存储空间的压力。面对这种情况,寻找一种有效的苹…

springboot3使用Excel导入数据库数据

一、导入依赖 <!-- https://mvnrepository.com/artifact/org.apache.poi/poi-ooxml --><dependency><groupId>org.apache.poi</groupId><artifactId>poi-ooxml</artifactId><version>5.3.0</version></dependency> 二、…

Xilinx远程固件升级(二)——STARTUPE2原语的使用

通过&#xff08;一&#xff09;可以看出&#xff0c;对于远程固件升级实际上是通过调用flash不同区域的bit实现&#xff0c;通过golden image和update image共同保障了系统的稳定性。在项目中如果将flash的时钟直接绑定FPGA后进行约束&#xff0c;在综合编译时是无法通过的。这…

Spark:DataFrame介绍及使用

1. DataFrame详解 DataFrame是基于RDD进行封装的结构化数据类型&#xff0c;增加了schema元数据&#xff0c;最终DataFrame类型在计算时&#xff0c;还是转为rdd计算。DataFrame的结构化数据有Row&#xff08;行数据&#xff09;和schema元数据构成。 Row 类型 表示一行数据 …

MySQL 8.4修改初始化后的默认密码

MySQL 8.4修改初始化后的默认密码 &#xff08;1&#xff09;初始化mysql&#xff1a; mysqld --initialize --console &#xff08;2&#xff09;之后,mysql会生成一个默认复杂的密码&#xff0c;如果打算修改这个密码&#xff0c;可以先用旧密码登录&#xff1a; mysql -u…

Redis set类型 zset类型

set类型 类型介绍 集合类型也是保存多个字符串类型的元素的&#xff0c;但和列表类型不同的是&#xff0c;集合中 1&#xff09;元素之间是⽆序 的 2&#xff09;元素不允许重复 ⼀个集合中最多可以存储 个元素。Redis 除了⽀持 集合内的增删查改操作&#xff0c;同时还⽀持多…

【图书推荐】《R语言医学数据分析实践》

本书重点 梅俏、卢龙、丁健、张晟、黄龙、胡志坚、张琼瑶、林志刚等业内专家联袂推荐。 以公共医学数据为例&#xff0c;精选大量的实用案例&#xff0c;深入浅出地介绍统计建模分析方法。 帮助读者解决医学数据分析中遇到的实际问题。 通过实际操作引导读者入门科研论文数…

生信分析流程:从数据准备到结果解释的完整指南

介绍 生物信息学&#xff08;生信&#xff09;分析是一个复杂的过程&#xff0c;涉及从数据准备到结果解释的多个步骤。随着高通量测序技术的发展和生物数据的迅猛增长&#xff0c;了解和掌握生信分析的标准流程变得尤为重要。这不仅有助于提高分析的准确性&#xff0c;还能优…

HarmonyOS NEXT 应用开发实战(五、页面的生命周期及使用介绍)

HarmonyOS NEXT是华为推出的最新操作系统&#xff0c;arkUI是其提供的用户界面框架。arkUI的页面生命周期管理对于开发者来说非常重要&#xff0c;因为它涉及到页面的创建、显示、隐藏、销毁等各个阶段。以下是arkUI页面生命周期的介绍及使用举例。 页面的生命周期的作用 页面…

7-I2C与AHT20温湿度传感器

I2C与AHT20温湿度传感器 嵌入式领域另一种常见的通信IIC通信&#xff0c;并用其与AHT20传感器进行交互&#xff0c;获取房间的温度与湿度。 I2C有一条用于传递数据的数据线称为SDA&#xff08;Serial Data&#xff09;&#xff0c;另一条是用于提供同步时钟脉冲的时钟线SCL&am…

看图识微分与导数概念。

可建立如草图所示的局部坐标系。增量Δydy余项是草图中曲线的方程&#xff0c;微分dyydx&#xff08;是关于dx的一次函数&#xff09;是草图中切线的方程。草图形象直观地显示曲线Δy不切线dy。