• MAVROS外部控制例程
    • 代码
    • 代码解释

    MAVROS外部控制例程

    官网英文原文地址:http://dev.px4.io/ros-mavros-offboard.html

    注意: 外部控制是危险的。如果在真机上操作,确保可以在出错的时候切换回手动控制。

    下面的教程是基本的外部控制,通过MAVROS应用在Gazebo模拟的Iris四旋翼上。在教程最后,应该会得到与下面视频相同的结果,即缓慢起飞到高度2米。

    代码

    在ROS包中创建offb_node.cpp文件,并粘贴下面内容:

    1. /**
    2. * @file offb_node.cpp
    3. * @brief offboard example node, written with mavros version 0.14.2, px4 flight
    4. * stack and tested in Gazebo SITL
    5. */
    6. #include <ros/ros.h>
    7. #include <geometry_msgs/PoseStamped.h>
    8. #include <mavros_msgs/CommandBool.h>
    9. #include <mavros_msgs/SetMode.h>
    10. #include <mavros_msgs/State.h>
    11. mavros_msgs::State current_state;
    12. void state_cb(const mavros_msgs::State::ConstPtr& msg){
    13. current_state = *msg;
    14. }
    15. int main(int argc, char **argv)
    16. {
    17. ros::init(argc, argv, "offb_node");
    18. ros::NodeHandle nh;
    19. ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>
    20. ("mavros/state", 10, state_cb);
    21. ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>
    22. ("mavros/setpoint_position/local", 10);
    23. ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>
    24. ("mavros/cmd/arming");
    25. ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
    26. ("mavros/set_mode");
    27. //the setpoint publishing rate MUST be faster than 2Hz
    28. ros::Rate rate(20.0);
    29. // wait for FCU connection
    30. while(ros::ok() && current_state.connected){
    31. ros::spinOnce();
    32. rate.sleep();
    33. }
    34. geometry_msgs::PoseStamped pose;
    35. pose.pose.position.x = 0;
    36. pose.pose.position.y = 0;
    37. pose.pose.position.z = 2;
    38. //send a few setpoints before starting
    39. for(int i = 100; ros::ok() && i > 0; --i){
    40. local_pos_pub.publish(pose);
    41. ros::spinOnce();
    42. rate.sleep();
    43. }
    44. mavros_msgs::SetMode offb_set_mode;
    45. offb_set_mode.request.custom_mode = "OFFBOARD";
    46. mavros_msgs::CommandBool arm_cmd;
    47. arm_cmd.request.value = true;
    48. ros::Time last_request = ros::Time::now();
    49. while(ros::ok()){
    50. if( current_state.mode != "OFFBOARD" &&
    51. (ros::Time::now() - last_request > ros::Duration(5.0))){
    52. if( set_mode_client.call(offb_set_mode) &&
    53. offb_set_mode.response.success){
    54. ROS_INFO("Offboard enabled");
    55. }
    56. last_request = ros::Time::now();
    57. } else {
    58. if( !current_state.armed &&
    59. (ros::Time::now() - last_request > ros::Duration(5.0))){
    60. if( arming_client.call(arm_cmd) &&
    61. arm_cmd.response.success){
    62. ROS_INFO("Vehicle armed");
    63. }
    64. last_request = ros::Time::now();
    65. }
    66. }
    67. local_pos_pub.publish(pose);
    68. ros::spinOnce();
    69. rate.sleep();
    70. }
    71. return 0;
    72. }

    提示: 本过程需要对ROS有一定的了解。
    创建工作空间后需要source devel/setup.bash,否则会出现找不到package的情况,要想保证工作空间已配置正确需确保ROS_PACKAGE_PATH环境变量包含你的工作空间目录,采用echo $ROS_PACKAGE_PATH命令查看是否包含了你创建的package的路径,此操作也可以通过直接在.bashrc文件最后添加路径的方式解决。

    代码解释

    1. #include <ros/ros.h>
    2. #include <geometry_msgs/PoseStamped.h>
    3. #include <mavros_msgs/CommandBool.h>
    4. #include <mavros_msgs/SetMode.h>
    5. #include <mavros_msgs/State.h>

    mavros_msgs包含有所有用于MAVROS服务和主题的自定义消息。所有服务和主题以及它们所对应的消息类型参照文档mavros wiki。

    1. mavros_msgs::State current_state;
    2. void state_cb(const mavros_msgs::State::ConstPtr& msg){
    3. current_state = *msg;
    4. }

    创建一个简单的回调函数,它可以保存飞控的当前状态。我们可以用它检查连接状态,解锁状态以及外部控制标志。

    1. ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>("mavros/state", 10, state_cb);
    2. ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_position/local", 10);
    3. ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");
    4. ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");

    我们实例化一个用来发布指令位置的发布器,一个请求解锁的客户端和一个请求改变模式的客户端。注意,对你自己的系统,根据启动文件中节点名字的不同,”mavros”前面的部分会有所不同。

    1. //the setpoint publishing rate MUST be faster than 2Hz
    2. ros::Rate rate(20.0);

    px4飞行栈在外部控制指令之间有500ms的时限,如果超过了时限,那么飞控将会切换回进入外部控制模式之前的模式。这正是考虑可能的延迟,发布频率必须高于2Hz的原因。这同样也是推荐从位置控制模式进入外部控制模式的原因,如果外部控制模式发生故障,飞行器将会停止动作并处于盘旋状态。

    1. // wait for FCU connection
    2. while(ros::ok() && current_state.connected){
    3. ros::spinOnce();
    4. rate.sleep();
    5. }

    在发布之前,需要等待MAVROS和飞控建立连接。一旦接收到心跳包,该循环就会立即退出。

    1. geometry_msgs::PoseStamped pose;
    2. pose.pose.position.x = 0;
    3. pose.pose.position.y = 0;
    4. pose.pose.position.z = 2;

    即使px4飞行栈工作在航空常用的NED坐标系,MAVROS仍然会将这些坐标转换到标准的ENU坐标系,反之亦然。这是我们将Z设置为+2的原因。

    1. //send a few setpoints before starting
    2. for(int i = 100; ros::ok() && i > 0; --i){
    3. local_pos_pub.publish(pose);
    4. ros::spinOnce();
    5. rate.sleep();
    6. }

    在进入外部控制模式之前,就必须开始发布指令,否则模式切换会被拒绝。这里,100是个随意选取的值。

    1. mavros_msgs::SetMode offb_set_mode;
    2. offb_set_mode.request.custom_mode = "OFFBOARD";

    设置自定义模式为OFFBOARD,参考支持的模式列表

    1. mavros_msgs::CommandBool arm_cmd;
    2. arm_cmd.request.value = true;
    3. ros::Time last_request = ros::Time::now();
    4. while(ros::ok()){
    5. if( current_state.mode != "OFFBOARD" &&
    6. (ros::Time::now() - last_request > ros::Duration(5.0))){
    7. if( set_mode_client.call(offb_set_mode) &&
    8. offb_set_mode.response.success){
    9. ROS_INFO("Offboard enabled");
    10. }
    11. last_request = ros::Time::now();
    12. } else {
    13. if( !current_state.armed &&
    14. (ros::Time::now() - last_request > ros::Duration(5.0))){
    15. if( arming_client.call(arm_cmd) &&
    16. arm_cmd.response.success){
    17. ROS_INFO("Vehicle armed");
    18. }
    19. last_request = ros::Time::now();
    20. }
    21. }
    22. local_pos_pub.publish(pose);
    23. ros::spinOnce();
    24. rate.sleep();
    25. }

    剩下的代码比较好理解。在解锁并起飞后,不断地请求切换至外部控制模式。在请求之间间隔5秒,不至于让飞控响应不过来。在同样的循环里,以合适的频率持续发送位姿指令。

    提示: 出于解释的目的,这份代码经过了简化。在更大的系统中,创建一个新的负责周期性发送目标指令的线程往往更加有用。