.. _tutorial_offboard_cplus_zh: 在 ROS ä¸ä½¿ç”¨ C++ 进行在线控制 =========================================== .. Hint:: 本教程仅供 ROS å¼€å‘人员使用,其他用户应å‚考快速入门指å—和用户手册。 Pursuit 自动驾驶仪为有兴趣自定义其应用程åºçš„å¼€å‘人员æä¾›äº†æžå¤§çš„çµæ´»æ€§ã€‚我们æŒç»ç»´æŠ¤ API æŽ¥å£ ï¼ˆ:ref:`section_api_zh`ï¼‰ä½¿ç”¨æ ‡å‡†æ¶ˆæ¯å’Œå议,以便具有最低 ROS ç»éªŒçš„用户å¯ä»¥å¿«é€Ÿä¸Šæ‰‹ï¼Œå¹¶åœ¨ä»¥åŽå—益于我们的高级功能。 1. 软件组件 ------------------------- 推è环境为 Ubuntu 18.04ã€ROS melodic å’Œ python 3.6.9。用户也å¯ä»¥å°è¯• Docker 方法,如 :ref:`tutorial_docker_env` 所示。软件组件如下: - mavros (dev_pursuit_agv 分支): https://gitee.com/cloudkernel-tech/mavros.git - mavlink(dev_pursuit_agv 分支): https://gitee.com/cloudkernel-tech/mavlink-gdp-release.git - offboard_demo (dev_pursuit_agv 分支): https://github.com/cloudkernel-tech/offboard_demo.git mavros 包是æ¥è‡ª ROS 社区 (http://wiki.ros.org/mavros) 的定制包,它实现了 :ref:`section_api_zh` 䏿‰€ç¤ºçš„å¼€å‘人员的所有 API 接å£ã€‚mavlink 包 是与自驾仪通信的消æ¯å议。offboard_demo 包是利用 API 进行车辆æ“纵的 offboard 控制演示。 请使用上述软件包æ£ç¡®çš„分支版本。 2. 创建和编译工作区 ------------------------------- 用户å¯ä»¥æ‰§è¡Œä»¥ä¸‹å‘½ä»¤æ¥åˆ›å»ºç”¨äºŽ offboard 控制演示的工作区: :: mkdir -p ~/src/catkinws_nav/src # initialize the workspace with catkin tool (https://catkin-tools.readthedocs.io/en/latest/installing.html) cd ~/src/catkinws_nav catkin init # clone all repos cd ~/src/catkinws_nav/src git clone --recursive https://gitee.com/cloudkernel-tech/mavros.git git clone --recursive https://gitee.com/cloudkernel-tech/mavlink-gdp-release.git ./mavlink git clone --recursive https://github.com/cloudkernel-tech/offboard_demo.git # checkout branches for pursuit cd ~/src/catkinws_nav/src/mavros && git checkout dev_pursuit_agv cd ~/src/catkinws_nav/src/mavlink && git checkout dev_pursuit_agv cd ~/src/catkinws_nav/src/offboard_demo && git checkout dev_pursuit_agv 用户必须为 mavros 包安装 GeographicLib æ•°æ®é›†ï¼š :: cd ~/src/catkinws_nav/ ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh 对于ä¸å›½å¤§é™†çš„ç”¨æˆ·ï¼Œæ¤æ¥éª¤å¯èƒ½ä¼šå‡ºçŽ°ç½‘ç»œé—®é¢˜ï¼Œè¯·å‚è€ƒæ–‡ç« èŽ·å–建议: https://blog.csdn.net/qq_35598561/article/details/131281485 è¦ç¼–译工作区,åªéœ€ä½¿ç”¨ catkin 构建工具å³å¯ï¼š :: cd ~/src/catkinws_nav/ catkin build 3. 代ç 说明 ----------------------------- offboard_demo包为用户æä¾›äº†ä¸€ä¸ªæ¨¡æ¿ï¼Œç”¨äºŽä½¿ç”¨è‡ªé©¾ä»ªçš„ API 接å£ã€‚代ç ç¤ºä¾‹é‡‡ç”¨æ ‡å‡†çš„ ROS 节点形å¼ï¼Œ 用户必须熟悉ROS官方教程编写publisherå’Œsubscriber (http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29)。 为了çªå‡ºæ˜¾ç¤ºï¼Œoffboard_demo 节点包å«å¤šä¸ªæ–‡ä»¶ï¼š - offboard_demo/launch/off_mission.launch:用于å¯åЍ offboard 控制节点的默认å¯åŠ¨æ–‡ä»¶ã€‚ - offboard_demo/launch/waypoints_xyzy.yaml:航路点任务定义文件,其ä¸åŒ…å« ENU åæ ‡å’Œç›¸åº”çš„å航值(在本例ä¸ï¼Œåªæœ‰ xã€y åæ ‡æœ‰æ•ˆï¼‰ã€‚ - offboard_demo/src/off_mission_node.cpp: 用于 offboard 控制的 ROS 节点文件 本例的任务定义为:机体将在ä½ç½®æŒ‡ä»¤æ¨¡å¼ä¸‹è¡Œé©¶ï¼Œé€šè¿‡å¤šä¸ªé¢„定义的航点,然åŽè¿›å…¥Twist速度控制模å¼ï¼ŒæŒç»6秒。 在ä½ç½®æŽ§åˆ¶æ¨¡å¼ä¸‹ï¼Œè‡ªåŠ¨é©¾é©¶ä»ªæŽ¥å—æ¥è‡ª ROS 节点的ä½ç½®è®¾å®šå€¼ï¼ŒåŒæ—¶åœ¨Twisté€Ÿåº¦æŽ§åˆ¶æ¨¡å¼æ¨¡å¼ä¸‹ç›´æŽ¥è¾“出线性和角速度命令。 为了清楚起è§ï¼Œæˆ‘们按顺åºè¯´æ˜Žäº† off_mission_node çš„ main() 函数。 3.1 è¯é¢˜è®¢é˜…ã€å‘布和æœåŠ¡çš„å£°æ˜Ž ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 我们通常在主程åºå¼€å§‹æ—¶å£°æ˜ŽROSè¯é¢˜è®¢é˜…ã€å‘布和æœåŠ¡ã€‚è¦èŽ·å–状æ€ä¿¡æ¯æˆ–å‘é€å‘½ä»¤ï¼Œå¯ä»¥å¾ˆå®¹æ˜“地利用mavros包ä¸çš„å„ç§è¯é¢˜å’ŒæœåŠ¡ã€‚ 这些API接å£åœ¨ :ref:`section_api_zh` ä¸å®šä¹‰ï¼Œä¾‹å¦‚ “mavros/vcu_command_velocity/from_nav†是我们å¯ä»¥å‘布以将ä½ç½®è®¾å®šå€¼å‘é€åˆ°è‡ªåŠ¨é©¾é©¶ä»ªçš„è¯é¢˜ã€‚ :: /*subscriptions, publications and services*/ ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State> ("mavros/state", 5, state_cb); //subscription for local position ros::Subscriber local_pose_sub = nh.subscribe<geometry_msgs::PoseStamped> ("mavros/local_position/pose", 5, local_pose_cb); ros::Subscriber vcu_base_status_sub = nh.subscribe<pursuit_msgs::VcuBaseStatus> ("mavros/vcu_base_status/output", 5, vcu_base_status_cb); //publication for local position setpoint ros::Publisher local_pos_sp_pub = nh.advertise<geometry_msgs::PoseStamped> ("mavros/setpoint_position/local", 5); ros::Publisher nav_vel_cmd_pub = nh.advertise<geometry_msgs::Twist> ("mavros/vcu_command_velocity/from_nav", 5); //service for arm/disarm ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool> ("mavros/cmd/arming"); //service for main mode setting ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode> ("mavros/set_mode"); 3.2 æœåŠ¡æŒ‡ä»¤ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ ç„¶åŽï¼Œæˆ‘们构建必è¦çš„命令æ¥è°ƒç”¨ä¸Šé¢å®šä¹‰çš„æœåŠ¡ï¼Œå¦‚ä¸‹æ‰€ç¤ºã€‚è‡ªåŠ¨é©¾é©¶ä»ªåªèƒ½åœ¨offboard模å¼ä¸‹æŽ¥å—ä½ç½®å’Œtwist速度命令, 而且在进行任何è¿åЍ之å‰ï¼Œåº”该首先解é”。 :: /*service commands*/ mavros_msgs::SetMode offboard_set_mode; offboard_set_mode.request.custom_mode = "OFFBOARD"; mavros_msgs::SetMode stabilized_set_mode; stabilized_set_mode.request.custom_mode = "STABILIZED"; mavros_msgs::CommandBool arm_cmd; arm_cmd.request.value = true; mavros_msgs::CommandBool disarm_cmd; disarm_cmd.request.value = false; 在模拟ä¸ï¼Œç¨‹åºå°†è‡ªåŠ¨è®¾ç½®ä¸ºoffboard模å¼å¹¶è§£é”ã€‚ç”¨æˆ·éœ€è¦æ³¨æ„æ¤è®¾ç½®æ‰èƒ½è¿›è¡Œå®žé™…æ“作。 :: if (current_wpindex == 0) { if (simulation_flag == 1) { //set offboard mode, then arm the vehicle if( current_state.mode != "OFFBOARD" && (ros::Time::now() - last_request > ros::Duration(1.0))){ if( set_mode_client.call(offboard_set_mode) && offboard_set_mode.response.mode_sent){ ROS_INFO("Offboard mode enabled"); } last_request = ros::Time::now(); } else { if( !current_state.armed && (ros::Time::now() - last_request > ros::Duration(1.0))){ if( arming_client.call(arm_cmd) && arm_cmd.response.success){ ROS_INFO("Vehicle armed"); } last_request = ros::Time::now(); } } } } 3.3 ä½ç½®æŽ§åˆ¶æ¨¡å¼ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 在ä½ç½®æŽ§åˆ¶æ¨¡å¼ä¸‹ï¼Œè‡ªåŠ¨é©¾é©¶ä»ªæŽ¥å—ROS节点å‘布的ä½ç½®è®¾å®šå€¼ï¼Œå¹¶è¯·æ±‚æ— äººæœºå‰å¾€æ‰€éœ€ä½ç½®ã€‚航点从yaml文件 (waypoints_xyzy.yaml) åŠ è½½ï¼Œ åæ ‡åœ¨ ENUç³»ä¸å®šä¹‰ã€‚请注æ„,除éžè‡ªåŠ¨é©¾é©¶ä»ªæ”¶åˆ°æ–°çš„ä½ç½®ç›®æ ‡ï¼Œå¦åˆ™å®ƒä¼šç»§ç»æ‰§è¡Œä½ç½®æŽ§åˆ¶ï¼Œå› æ¤ç”¨æˆ·éœ€è¦åˆ‡æ¢åˆ°è‡ªç¨³æ¨¡å¼æ‰èƒ½åœæ¢è½¦è¾†ï¼Œ 以é¿å…任何事故。 :: /* publish local position setpoint for rover maneuvering*/ case ROVER_MISSION_PHASE::POS_PHASE:{ ROS_INFO_ONCE("Starting position guidance phase"); geometry_msgs::PoseStamped pose; //pose to be passed to fcu pose = waypoints.at(current_wpindex); ROS_INFO_THROTTLE(2.0f, "Rover: go to position %5.3f, %5.3f, %5.3f \n",(double)pose.pose.position.x, (double)pose.pose.position.y, (double)pose.pose.position.z); local_pos_sp_pub.publish(pose); updateWaypointIndex(); break; } 3.4 Twisté€Ÿåº¦æŽ§åˆ¶æ¨¡å¼ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 在Twist速度控制模å¼ä¸‹ï¼Œè‡ªåŠ¨é©¾é©¶ä»ªæŽ¥å—线性和角速度命令以进行直接æ“çºµã€‚é€Ÿåº¦åœ¨è½¦è¾†ä½“åæ ‡ç³»ï¼ˆFLU) ä¸å®šä¹‰ã€‚请注æ„, ç”¨æˆ·å¿…é¡»åœ¨æ¤æ¨¡å¼ä¸‹æŒç»å‘布twist速度命令,å¦åˆ™æœºä½“å°†åœ¨åœæ¢å‘布命令2såŽæ€ 速。 :: /* publish twist command for rover maneuvering*/ case ROVER_MISSION_PHASE::TWIST_CONTROL_PHASE:{ ROS_INFO_ONCE("Starting twist control phase"); geometry_msgs::Twist twist_cmd; twist_cmd.linear.x = 1.0; twist_cmd.linear.y = 0.0; twist_cmd.linear.z = 0.0; twist_cmd.angular.x = 0.0; twist_cmd.angular.y = 0.0; twist_cmd.angular.z = 0.5; //about 30deg/s nav_vel_cmd_pub.publish(twist_cmd); //phase transition after a certain time if ( ros::Time::now() - _phase_entry_timestamp > ros::Duration(6.0)){ _flag_mission_completed = true; ROS_INFO("Mission completed"); } break; } 4. æ“作æç¤º ----------------------------- è¦åœ¨å®žé™…情况下æ“ä½œè½¦è¾†ï¼Œå»ºè®®å‡ ä¸ªæç¤ºï¼š - 在å¯åŠ¨æ–‡ä»¶ä¸æ£ç¡®è®¾ç½®æ¨¡æ‹Ÿæ ‡å¿—。请记ä½å°†simulation_flag设置为 0 以进行实际æ“作。 :: <arg name=“simulation_flag†default = “0â€/> - 请谨慎使用 waypoints_xyzy.yaml ä¸å®šä¹‰çš„ç›®æ ‡ç‚¹åæ ‡ã€‚ - 测试å‰è¯·ä½¿ç”¨æ¨¡æ‹ŸçŽ¯å¢ƒéªŒè¯ä½ 的代ç (:ref:`tutorial_sitl_sim`)。 - 需è¦ä¸€ä¸ªäººå¾…命æ“作地é¢ç«™è½¯ä»¶ï¼Œå¯¹äºŽæ„外行为,请切æ¢åˆ° stabilized 模å¼ã€‚