应用mavros操作无人机的软硬件架构
应用mavros操作无人机的软硬件架构安装mavrosROS创建节点与编译ROS会创建一个连接所有节点的网络图中5个节点通过3种方式进行通信通信方式对比话题多对多广播式通信发布/订阅模式服务点对点请求/响应模式更可靠高效参数服务器通过关键词存储系统核心数据支持动态配置如launch种的reparamROS文件系统重新理解ROS话题订阅和发布的消息队列spinomce每次进入回调会取出subscriber队列中时间戳最早的那一个进入回调函数。也就是最旧的消息。这样不会遗漏消息数据但是会有延迟。参考文章【ROS进阶】一文搞懂ROS话题通信机制与消息队列 和 ROS消息队列函数ROS_INFO()类似于printf():ROS_INFO(收到的值为%fdata);1.4应用mavros控制无人机的消息流mavros消息订阅与发布1、mavros通过mavlink与PX4进行通信。px4的mavlink module负责解析/打包mavlink协议解析的mavlink协议通过uorb(o不发音)消息的方式发布给其他module。所以mavlink module相当于是uorb消息与mavlink协议之间的转换包。mavros可以将mavlink协议转换为ros消息几个官网mavros,mavlink,uorbmavros说明文档里面SET_POSITION_TARGET_LOCAL_NED指的是对应的mavlink协议。mavros要订阅的话题也就是我们ros需要发布的话题。真正控制无人机的是mavlink协议需要对这个有深入了解。mvros与mavlink协议的对应关系并不是一对一有可能是多对1。查找顺序确定需求的功能-在mavros说明找到可以实现这个功能的mavros并找到对应的mavlink协议-去mavlink协议说明文档看是否能实现这个功能。注当mavros的说明不详细可以去阅读mavros源码找到其对应的mavlink协议。mavlink协议转为uorb消息不是重点。有颜色的框代表是px4固件里面的module。px4固件包含的uorb如下所示2、PX4官网提供的offboard例子进行解析这个代码是example node节点的代码与mavros进行通信的代码。offboard模式通过mavros使PX4进入该模式允许机载电脑直接控制无人机区别于位置模式、姿态模式等其他飞行模式。待机状态配置通过mavros使无人机进入待机状态旋翼以最小PWM值转动该状态可通过遥控器/地面站替代设置。以上两种只需要一次就配置好不需要循环发送数据所以用服务来完成服务更适合用来做一些配置。悬停控制需要持续发送位置指令使无人机维持在2米高度属于需要循环处理的数据流。这里的mavros就是类似ros的功能包的作用。服务解释这里贴出来这几个服务/话题对应的mavros说明。机载电脑上的mavros通过有线与px4固件上的mavlink进行通信。使用mavros控制无人机前提是要保证mavros与PX4建立起了通信。mavros位置的发布都是基于东北天坐标系ENU。上面的5) b是发给mavros的话题然后mavros会将订阅的ros消息打包转换为mavlink协议。这里对if else有疑惑发布位置数据要在arm之后但是这里循环一次就发布一次是不是不太对。mavros_msgs::SetMode不是消息类型(message),而是服务类型(service)!使用 rosmsg show 只能查询 消息类型应该使用 rossrv show 来查询 服务类型(base) pcpc-Default-string:~/catkin_ws/src/offb_node$ rossrv show mavros_msgs/SetMode uint8 MAV_MODE_PREFLIGHT0 uint8 MAV_MODE_STABILIZE_DISARMED80 uint8 MAV_MODE_STABILIZE_ARMED208 uint8 MAV_MODE_MANUAL_DISARMED64 uint8 MAV_MODE_MANUAL_ARMED192 uint8 MAV_MODE_GUIDED_DISARMED88 uint8 MAV_MODE_GUIDED_ARMED216 uint8 MAV_MODE_AUTO_DISARMED92 uint8 MAV_MODE_AUTO_ARMED220 uint8 MAV_MODE_TEST_DISARMED66 uint8 MAV_MODE_TEST_ARMED194 uint8 base_mode string custom_mode --- bool mode_sent服务结构说明# 请求部分 (request) uint8 base_mode # 基础模式 string custom_mode # 自定义模式名称(例如 OFFBOARD) --- # 响应部分 (response) bool mode_sent # 模式是否设置成功为什么是 offb_set_mode.request.custom_mode?在 ROS 服务中:.request:表示服务的请求部分,包含发送给服务端的参数.response:表示服务的响应部分,包含服务端返回的结果所以:offb_set_mode.request.custom_mode OFFBOARD 设置请求参数调用服务后,通过 offb_set_mode.response.mode_sent 获取响应结果//创建一个客户端该客户端用来请求进入offboard模式 ros::ServiceClient set_mode_client nh.serviceClientmavros_msgs::SetMode (mavros/set_mode); // 1. 创建服务请求对象 mavros_msgs::SetMode offb_set_mode; // 2. 设置请求参数 offb_set_mode.request.custom_mode OFFBOARD; // 3. 调用服务 set_mode_client.call(offb_set_mode) // 4. 检查响应 offb_set_mode.response.mode_sent // 返回 true/falseset_mode_client.call(offb_set_mode) 返回一个 bool 类型的值:true: 服务调用成功(服务端收到请求并处理了)false: 服务调用失败(服务端不可用、网络问题、超时等)第一层: call() 返回 true → 服务通信成功第二层: response.mode_sent 为 true → 模式设置成功两者都为 true,才表示真正完成了模式切换!call() 返回response.mode_sent说明false(无法获取)服务调用失败,可能服务端不可用truefalse服务调用成功,但飞控拒绝切换模式(例如:条件不满足)truetrue完全成功!总结✅ 使用 rossrv show 查看服务类型✅ 使用 rosmsg show 查看消息类型SetMode 是服务,所以有 request 和 response 两部分custom_mode 是该服务请求中的一个字符串参数,用于指定飞行模式在工作空间下有多个功能包只catkin_make其中一个功能包catkin_make --only-pkg-with-deps 功能包名字//这是一个在ros上编写的一个offboard代码将消息话题/服务发布给mavros从而控制无人机 #include ros/ros.h #include geometry_msgs/PoseStamped.h #include mavros_msgs/CommandBool.h #include mavros_msgs/SetMode.h #include mavros_msgs/State.h mavros_msgs::State current_state;//声明全局变量 void state_cb(const mavros_msgs::State::ConstPtr msg){ current_state *msg;//逆向引用直接返回msg指针指向的对象本身 } int main(int argc,char **argv){ //初始化节点给节点命名 ros::init(argc,argv,offb_node); ros::NodeHandle nh; ros::Subscriber state_sub nh.subscribemavros_msgs::State(/iris_0/mavros/state,10,state_cb);//iris_0/mavros/state ros::ServiceClient set_mode_client nh.serviceClientmavros_msgs::SetMode(/iris_0/mavros/set_mode); ros::ServiceClient arming_client nh.serviceClientmavros_msgs::CommandBool(/iris_0/mavros/cmd/arming); ros::Publisher local_pos_pub nh.advertisegeometry_msgs::PoseStamped(/iris_0/mavros/setpoint_position/local,10);// /iris_0/mavros/setpoint_position/local ros::Rate rate(20.0);//设置循环频率实现20hz频率的循环 //1.等待机载计算机与飞控板进行通信连接 while(ros::ok() !current_state.connected){ ros::spinOnce();//非阻塞式处理所有回调函数 rate.sleep();//阻塞式控制循环频率 } std::cout机载pc与飞控建立了通信std::endl; //2.当机载pc与飞控建立通信后提前开始mavros数据的传输。然后才能切换offboard模式 //这个发布的期望位置时无人机即将起飞到的位置相对于无人机上电时刻作为起始点 geometry_msgs::PoseStamped pose; pose.pose.position.x0.0; pose.pose.position.y0.0; pose.pose.position.z2.0;//mavros位置都是ENU坐标系 //持续以20hz频率发送期望位置给飞控 for(int i100;ros::ok() i0;i--){ local_pos_pub.publish(pose); ros::spinOnce(); rate.sleep(); } //设置客户端请求无人机进入“offboard”模式 mavros_msgs::SetMode offb_set_mode; offb_set_mode.request.custom_mode OFFBOARD;//设置请求参数 //设置客户端请求无人机解锁 mavros_msgs::CommandBool arm_cmd; arm_cmd.request.valuetrue; //获取当前时间戳 ros::Time last_request ros::Time::now(); std::cout即将进进入while循环std::endl; //状态机逻辑未切换模式-(等待5s)-切换OFFBOARD-(等待5s)-解锁进入待机状态 while(ros::ok()){ //if语句循环请求进入OFFBOARD模式进入后则会进入else语句请求对无人机解锁 //double time_diff (ros::Time::now() - last_request).toSec(); //std::cout 当前模式: [ current_state.mode ], 时间差: time_diff 秒 std::endl; if(current_state.mode !OFFBOARD (ros::Time::now() -last_request ros::Duration(5.0))){ //调用服务请求参数模式。以及模式设置成功判断 std::cout请求进入OFFBOARD模式std::endl; if(set_mode_client.call(offb_set_mode) offb_set_mode.response.mode_sent){ //服务通信成功以及飞控进入offboard模式 ROS_INFO(offboard enabled); } last_request ros::Time::now(); }else{ if(!current_state.armed (ros::Time::now() -last_request ros::Duration(5.0))){ //调用服务请求进入待机状态 if(arming_client.call(arm_cmd) arm_cmd.response.success){ ROS_INFO(Vehicle armed); } last_request ros::Time::now(); } } //循环一次就发送一次期望位置以20hz频率发布 local_pos_pub.publish(pose); std::cout在while中发布期望位置std::endl; ros::spinOnce(); rate.sleep();//阻塞式使得循环以20hz } }这个代码是使用代码进入offboard模式然后进入待机状态解锁,然后起飞到高度为2m的地方。注意这里一开始老是切不进offboard档问题描述我已经关闭了QGC我查看了QGC中的COM_RCL_EXCEPT 设置为0找到问题了! COM_RCL_EXCEPT 0 是导致无法进入 OFFBOARD 模式的原因!问题解释COM_RCL_EXCEPT 参数控制在遥控器信号丢失时,哪些模式仍然被允许:0: 不允许任何特殊模式 → OFFBOARD 模式被禁止 ❌4: 允许 OFFBOARD 模式 → 可以进入 OFFBOARD ✅因为你在用机载计算机控制(没有遥控器),PX4 认为是遥控器丢失状态,所以拒绝进入 OFFBOARD 模式解决方法1打开QGC将COM_RCL_EXCEPT设置为4方法2通过 MAVROS 服务设置参数rosservice call /iris_0/mavros/param/set param_id: COM_RCL_EXCEPT value: integer: 4 real: 0.0然后运行代码就可以进入OFFBOARD模式并且解锁。当前模式: [OFFBOARD], 时间差: 10.392秒在while中发布期望位置当前模式: [OFFBOARD], 时间差: 10.444秒在while中发布期望位置2.1位置控制-Mavros教程-offboard模式下自主飞行用offboard模式无人机定高悬停和位置控制和速度控制走正方形https://zhuanlan.zhihu.com/p/4409960132.2 mavros发布姿态指令给无人机发布四元数和归一化的推力目前还不知道这个是干什么用的也不太看得懂这个视频2.3 mavros读取遥控器数据、读取无人机角速度和线速度数据、无人机从mavros读取的角速度和线速度数据是FLU系区别于从mavros读取的位置是ENU系。无论是点坐标位置还是线速度和角速度的坐标系下不同的表示坐标变换。都是在不改变其在实际物理世界中的时空信息目前都是空间信息的前提下在不同坐标系定义的不同刚体的姿态/朝向不同的坐标系的朝向中的表示。只是换一个坐标系表达。比如位置是绝对空间信息不变速度是绝对物理大小和方向都不变1.获取遥控器的数据代码实现部分2.订阅无人机的线速度和角速度代码实现部分3.修改mavros反馈传感器数据的频率2.4 offboard模式下的室内定位在mavros的文档中并没有包含所有的mavros可订阅/发布额话题名称室内定位系统。对px4飞控的配置就是飞控EKF2融合GPS气压计数据还是其他视觉定位数据融合定位。关键参数EKF2_HGT_MODE3启用外部定位系统的垂直方向数据EKF2_AID_MASK根据需求配置数据融合方式24视觉位置偏航角融合视觉坐标系朝向320/328视觉位置速度旋转融合正北朝向PX4坐标系Body系FRDX前Y右Z下World系NEDX北Y东Z下ROS坐标系Body系FLUX前Y左Z上通常命名为base_linkWorld系FLU或者ENUX东Y北Z上命名为odom或map频率最低要求官方建议位置数据频率2Hz实际测试SLAM数据频率10Hz时PX4无法进入位置模式优化建议适当提高频率可降低控制延时关于这里mavros订阅的外部定位数据话题的消息类型对应关系这里我有不同的理解。因为不论使用vins还是fast-lio,这两个定位系统直接输出的都是nav_msgs/Odometry类型但是在gazebo和实际飞行的offboard代码中都是将定位输出的nav_msgs/Odometry消息转换成geometry_msgs/PoseStamped类型的话题“mavros/vision_pose/pose,然后发布给mavros使用。