.. _section_api_zh: 应用程序设计接口(API) ========================================= 我们提供开源API用于Kerloud VTOL系列的开发,当前支持的语言为C++。 该部分的细节会持续更新。 ROS API (C++) ------------------ ROS(Robot Operating System)中的API是基于PX4社区的官方 `MAVROS `_ 包来实现的。 我们在维护的软件库链接为: * mavros: https://github.com/cloudkernel-tech/mavros * mavlink: https://github.com/cloudkernel-tech/mavlink-gdp-release 请注意:对于上述软件库,用户必须切换到 *dev_kerloudvtol* 分支。 我们还为用户提供了一个offboard控制例程,用户可受邀请加入我们在 https://gitee.com/cloudkernel-tech/offboard_kerloudvtol 下托管的软件包。 在此我们将介绍与Kerloud VTOL案例特别相关的主题、服务,更多关于mavros软件包的常用信息可参考官方 `链接 `_ 。关于如何使用API的说明可查阅使用教程章节(:ref:`tutorial_offboard_zh`)。 主题 ^^^^^^^^^^ **(1) /mavros/extended_state** 订阅该主题可获取机体当前状态,消息类型为 `mavros_msgs/ExtendedState `_ ,,细节描述如下: :: # 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 为清晰起见,在此说明具体含义: * vtol_state=0: 此飞机未定义VTOL状态; * vtol_state=1: 飞机处于向固定翼模式转换阶段; * vtol_state=2: 飞机处于向多旋翼模式转换阶段; * vtol_state=3: 飞机处于多旋翼模式。 * vtol_state=4: 飞机处于固定翼模式。 flyingrover_state字段与我们的 `Kerloud飞车 `_ 系列相关,此处不使用。 **(2) /mavros/setpoint_position/local, /mavros/setpoint_position/global** 本主题用于发布在本地或全局坐标系下的航点位置信息,多旋翼、固定翼模式下通用。需注意,ROS层使用的参考坐标系为ENU,而自驾仪使用的则是NED, 消息类型分别为 `geometry_msgs/PoseStamped `_ 和 `mavros_msgs/GlobalPositionTarget `_ **(3) mavros/setpoint_raw/local, /mavros/setpoint_raw/global** 这两个主题可用于在本地或全局坐标系中为飞机发布更精密的位置和速度设定值。Kerloud VTOL支持多种引导模式:(i) 传统位置引导模式: 无人机会按照L1制导律飞到目标位置,然后在目标位置周围徘徊;(ii) 固定矢量位置引导模式:无人机将按照L1制导律飞行到目标位置,到达位置目标后固定航向; (iii) 速度引导模式:无人机将依据前进速度、参考倾斜角,是一种用于应用程序开发的低级控制接口。 服务 ^^^^^^^^^^^^^^^ **mavros/cmd/command** 该服务用于在offboard操作时多旋翼、固定翼模式间切换。消息类型为 mavros_msgs/CommandLong,对应于 `此链接 `_ 中所定义的一条 mavlink 消息(mavlink::common::MAV_CMD::DO_VTOL_TRANSITION)。 例如,如果我们想切换到固定翼模式,则必须使用以下设置来调用该服务: :: mavros_msgs::CommandLong switch_to_fw_cmd;//command to switch to fixed-wing switch_to_fw_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::DO_VTOL_TRANSITION; switch_to_fw_cmd.request.confirmation = 0; switch_to_fw_cmd.request.param1 = (float)mavlink::common::MAV_VTOL_STATE::FW; 要切换到多旋翼模式则为: :: 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_VTOL_TRANSITION; switch_to_mc_cmd.request.confirmation = 0; switch_to_mc_cmd.request.param1 = (float)mavlink::common::MAV_VTOL_STATE::MC;