# 应用程åºæŽ¥å£ (API) 我们为Kerloud Flying Rover系列æ供用于开å‘çš„å¼€æºAPI,并有C++ã€Python或其他è¯è¨€çš„版本å¯é€‰ç”¨ã€‚è¯¦ç»†å†…å®¹ä¼šåœ¨æœ¬ç« èŠ‚æŒç»æ›´æ–°ã€‚ ## 1. ROS API(C++) ROS(Robot Operating System)ä¸çš„API是基于PX4社区的官方MAVROS包æ¥å®žçŽ°çš„。我们在维护的软件库链接为: * mavros (dev_flyingrover分支): <https://github.com/cloudkernel-tech/mavros> * mavlink (dev_flyingrover分支): <https://github.com/cloudkernel-tech/mavlink-gdp-release> * 基于ROS C++ APIçš„offboard控制案例 (dev_flyingrover分支): <https://github.com/cloudkernel-tech/offboard_demo> æ›´å¤šçš„ç¼–ç¨‹ç»†èŠ‚å°†åœ¨è¿™é‡Œçš„æ•™ç¨‹ç« èŠ‚è¿›è¡Œè¯´æ˜Žï¼Œè€Œæ¤å¤„介ç»ä¸Žæˆ‘们的飞车案例特别相关的è¯é¢˜å’ŒæœåŠ¡ã€‚ ### 1.1 Topics #### (1) ~mavros/extended_state 订阅该è¯é¢˜å¯èŽ·å–飞车的当å‰çŠ¶æ€ï¼Œæ¶ˆæ¯ç±»åž‹ä¸ºä»ŽåŽŸå§‹ç‰ˆæœ¬æ‰©å±•è€Œæ¥çš„mavros\_msgs/ExtendedState,æ供了用于指示飞车状æ€çš„flyingrover\_stateé¢å¤–å—段,具体如下文所示。本å—段的å–值是使用å‰ç¼€FLYINGROVER\_STATE\_*定义的那些常é‡ã€‚ # Extended autopilot state # # https://mavlink.io/en/messages/common.html#EXTENDED_SYS_STATE uint8 VTOL_STATE_UNDEFINED = 0 uint8 VTOL_STATE_TRANSITION_TO_FW = 1 uint8 VTOL_STATE_TRANSITION_TO_MC = 2 uint8 VTOL_STATE_MC = 3 uint8 VTOL_STATE_FW = 4 uint8 LANDED_STATE_UNDEFINED = 0 uint8 LANDED_STATE_ON_GROUND = 1 uint8 LANDED_STATE_IN_AIR = 2 uint8 LANDED_STATE_TAKEOFF = 3 uint8 LANDED_STATE_LANDING = 4 uint8 FLYINGROVER_STATE_UNDEFINED = 0 uint8 FLYINGROVER_STATE_ROVER = 1 uint8 FLYINGROVER_STATE_MC = 2 uint8 FLYINGROVER_STATE_TRANSITION_TO_MC = 3 uint8 FLYINGROVER_STATE_TRANSITION_TO_ROVER = 4 std_msgs/Header header uint8 vtol_state uint8 landed_state uint8 flyingrover_state 为清晰起è§ï¼Œåœ¨æ¤è¯´æ˜Žå…·ä½“å«ä¹‰ï¼š * flyingrover_state=0: 飞车尚未åˆå§‹åŒ–。 * flyingrover_state=1: 飞车è¿è¡Œåœ¨é™†åœ°è½¦æ¨¡å¼ä¸‹ã€‚ * flyingrover_state=2: 飞车è¿è¡Œåœ¨å¤šæ—‹ç¿¼æ¨¡å¼ä¸‹ã€‚ * flyingrover_state=3: 飞车æ£ä»Žé™†åœ°è½¦æ¨¡å¼å‘多旋翼模å¼è½¬æ¢ã€‚手动模å¼ä¸‹ï¼ŒçŠ¶æ€ä¼šç«‹å³åˆ‡ä¸ºå¤šæ—‹ç¿¼æ¨¡å¼ï¼›offboard或其他自动模å¼ä¸‹ï¼Œå½“è¿åŠ¨é€Ÿåº¦ä½ŽäºŽè‡ªé©¾ä»ªå›ºä»¶ä¸FR_V_TH_MCå‚æ•°çš„å–值(默认为0.2m/s)时会完æˆåˆ‡æ¢ã€‚ * flyingrover_state=4: 飞车æ£ä»Žå¤šæ—‹ç¿¼æ¨¡å¼å‘陆地车模å¼è½¬æ¢ï¼Œæœºå™¨å³å°†æ‰‹åŠ¨æˆ–自主ç€é™†ï¼Œç€é™†åŽçŠ¶æ€å°†è½¬ä¸ºé™†åœ°è½¦æ¨¡å¼ã€‚ #### (2) ~mavros/setpoint_position/local, ~mavros/setpoint_position/global 本è¯é¢˜ç”¨äºŽå‘布在本地或全局åæ ‡ç³»ä¸‹çš„èˆªç‚¹ä½ç½®ä¿¡æ¯ï¼Œé™†åœ°è½¦ã€å¤šæ—‹ç¿¼æ¨¡å¼ä¸‹é€šç”¨ã€‚需注æ„,ROS层使用的å‚考åæ ‡ç³»ä¸ºENU,而自驾仪使用的则是NED,消æ¯ç±»åž‹åˆ†åˆ«ä¸º[geometry_msgs/PoseStamped](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html)å’Œ[mavros_msgs/GlobalPositionTarget](http://docs.ros.org/en/api/mavros_msgs/html/msg/GlobalPositionTarget.html)。 #### (3) ~mavros/setpoint_velocity/cmd_vel_unstamped, ~mavros/setpoint_velocity/cmd_vel 这两个è¯é¢˜ç”¨äºŽå‘布飞车在本地åæ ‡ç³»ä¸çš„速度设定值,陆地车ã€å¤šæ—‹ç¿¼æ¨¡å¼ä¸‹é€šç”¨ï¼Œä¸¤ä¸ªè¯é¢˜çš„唯一区别是速度信æ¯æ˜¯å¦æºå¸¦æ—¶é—´æˆ³ã€‚消æ¯ç±»åž‹ä¸º[geometry_msgs/Twist](http://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html)。 #### (4) ~mavros/setpoint_attitude/attitude, ~mavros/setpoint_attitude/thrust 这两个è¯é¢˜å¯ç”¨äºŽåœ¨é™†åœ°è½¦ã€å¤šæ—‹ç¿¼æ¨¡å¼è®¾å®šå§¿æ€å€¼ï¼Œä½†å»ºè®®åªç”¨äºŽè½¦æ¨¡å¼ã€‚消æ¯ç±»åž‹åˆ†åˆ«ä¸º[geometry_msgs/PoseStamped](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html) å’Œ [mavros_msgs/Thrust](http://docs.ros.org/en/api/mavros_msgs/html/msg/Thrust.html)。姿æ€æŽ¨åŠ›ç›´æŽ¥è¾“入到主电机油门,通过å航角跟踪误差æ¥è®¡ç®—生æˆè½¬å‘伺æœèˆµæœºçš„控制输入。 ### 1.2 Services #### (1) ~mavros/cmd/command 本æœåŠ¡ç”¨äºŽoffboard控制模å¼ä¸‹é™†åœ°è½¦ã€å¤šæ—‹ç¿¼çš„状æ€åˆ‡æ¢ï¼Œæ¶ˆæ¯ç±»åž‹ä¸º[mavros_msgs/CommandLong](http://docs.ros.org/en/api/mavros_msgs/html/srv/CommandLong.html),对应于下文链接ä¸çš„一个定制化mavlinkæ¶ˆæ¯ ï¼ˆmavlink::common::MAV_CMD::DO_FLYINGROVER_TRANSITION),链接为<https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_flyingrover/message_definitions/v1.0/common.xml>。 例如,如果我们想切æ¢åˆ°å¤šæ—‹ç¿¼æ¨¡å¼ï¼Œåˆ™éœ€è¦é€šè¿‡å¦‚下设置调用该æœåŠ¡ï¼š mavros_msgs::CommandLong switch_to_mc_cmd;//command to switch to multicopter switch_to_mc_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::DO_FLYINGROVER_TRANSITION; switch_to_mc_cmd.request.confirmation = 0; switch_to_mc_cmd.request.param1 = (float)mavlink::common::MAV_FLYINGROVER_STATE::MC; 相å,若切æ¢åˆ°é™†åœ°è½¦æ¨¡å¼ï¼Œåˆ™ï¼š mavros_msgs::CommandLong switch_to_rover_cmd;//command to switch to rover switch_to_rover_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::DO_FLYINGROVER_TRANSITION; switch_to_rover_cmd.request.confirmation = 0; switch_to_rover_cmd.request.param1 = (float)mavlink::common::MAV_FLYINGROVER_STATE::ROVER; 请注æ„,mavlink::common::MAV_FLYINGROVER_STATE的枚举定义如下,å‚è§[链接](https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_flyingrover/message_definitions/v1.0/common.xml) typedef enum MAV_FLYINGROVER_STATE { MAV_FLYINGROVER_STATE_UNDEFINED=0, /* MAV is not configured as flyingrover | */ MAV_FLYINGROVER_STATE_ROVER=1, /* flyingrover is in rover state | */ MAV_FLYINGROVER_STATE_MC=2, /* flyingrover is in multicopter state | */ MAV_FLYINGROVER_STATE_TRANSITION_TO_MC=3,/* flyingrover is in transition from rover to multicopter | */ MAV_FLYINGROVER_STATE_TRANSITION_TO_ROVER=4,/* flyingrover is in transition from multicopter to rover | */ MAV_FLYINGROVER_STATE_ENUM_END=5, /* | */ } MAV_FLYINGROVER_STATE; ## 2. ROS API (python) 与C++版本ROS API类似,ROS python API也是基于我们维护的mavroså’Œ mavlink包实现,仅有的区别是上文æ到的所有è¯é¢˜å’ŒæœåŠ¡éœ€é€šè¿‡pythonæ¥ä½¿ç”¨ã€‚ * mavros (dev_flyingrover分支): <https://github.com/cloudkernel-tech/mavros> * mavlink (dev_flyingrover分支): <https://github.com/cloudkernel-tech/mavlink-gdp-release> * 基于ROS python APIçš„offboard控制案例 (dev_flyingrover分支): <https://github.com/cloudkernel-tech/offboard_demo_python> 代ç å°†åœ¨è¿™é‡Œçš„æ•™ç¨‹ç« èŠ‚æœ‰åšè®²è§£ã€‚为简æ´èµ·è§ï¼Œåº•å±‚消æ¯é€šä¿¡åœ¨Px4Controllerç±»ä¸è¿›è¡Œå¤„ç†ï¼Œè€Œé¢å‘用户编程用的å‹å¥½API接å£å°è£…于Commanderç±»ä¸ï¼Œéƒ¨åˆ†API列举如下: * move(x,y,z, BODY_FLU=False): 请求飞车移动到FLU或ENUåæ ‡ç³»ä¸‹çš„æŒ‡å®šä½ç½®ï¼Œé™†åœ°è½¦ã€å¤šæ—‹ç¿¼æ¨¡å¼ä¸‹é€šç”¨ã€‚ * turn(yaw_degree): 请求飞车å航指定角度,仅多旋翼模å¼å¯ç”¨ã€‚ * land(): 多旋翼模å¼ä¸‹ï¼Œè¯·æ±‚飞车ç€é™†ï¼› * hover(): 多旋翼模å¼ä¸‹ï¼Œè¯·æ±‚飞车悬åœåœ¨å½“å‰ä½ç½®ã€‚ * arm(): 请求解é”飞车。 * disarm(): 请求é”定地é¢çš„飞车。 * transit_to_rover(): 请求飞车切æ¢ä¸ºé™†åœ°è½¦æ¨¡å¼ã€‚ * transit_to_mc(): 请求飞车切æ¢ä¸ºå¤šæ—‹ç¿¼æ¨¡å¼ã€‚ * return_home(height): 请求飞车返航,仅多旋翼模å¼å¯ç”¨ã€‚