Application Programming Interface (API)
We provide open source API for development with the Kerloud VTOL series, and the current supported language is C++. Details will be updated continuously in this part.
ROS API (C++)
The API in ROS (Robot Operating System) is implemented based on the official MAVROS package from the PX4 community.
Our maintained repositories are:
Note that users have to switch to the dev_kerloudvtol branch for above repositories.
We also provide an offboard control example for customers, and they will be invited to join our hosted repository in https://gitee.com/cloudkernel-tech/offboard_kerloudvtol. We present here topics and services that are specifically related with the Kerloud VTOL case. More general information on the mavros package can be referred in the official link. Illustrations on how to utilize these APIs can be found in the tutorial (Offboard Control in a Companion Computer)
Topics
(1) /mavros/extended_state
This topic can be subscribed to obtain current vehicle state. The message type is mavros_msgs/ExtendedState, with details given below.
# 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
For clarity, we illustrate the meanings here:
vtol_state=0: VTOL state is not defined for this vehicle.
vtol_state=1: The vehicle is in the forward transition phase to transit to the fixed-wing mode.
vtol_state=2: The vehicle is in the backward transition phase to transit to the multicopter mode.
vtol_state=3: The vehicle is in the multicopter mode.
vtol_state=4: The vehicle is in the fixed-wing mode.
The field flyingrover_state is related with our Kerloud flying rover series, hence not used here.
(2) /mavros/setpoint_position/local, /mavros/setpoint_position/global
These two topic are used to publish the position setpoint in the local or global frame for both multicopter and fixed-wing modes. Note that the reference frame in the ROS level is the ENU frame, while that for the autopilot is the NED frame. The message type is geometry_msgs/PoseStamped or mavros_msgs/GlobalPositionTarget respectively.
(3) mavros/setpoint_raw/local, /mavros/setpoint_raw/global
These two topics can be utilized to construct more sophisticated position and velocity setpoints in the local or global frame for both multicopter and fixed-wing modes. The Kerloud VTOL supports several guidance modes: (i) traditional position guidance mode: the UAV will fly to the target position with a L1 guidance law, and then loiter around the position target afterwards. (ii) fixed-vector position guidance mode: the UAV will fly to the target position with a L1 guidance law, and then fix its heading after reaching the position target. (iii) velocity guidance mode: the UAV will follow the forward velocity and banking angle references, which is a low-level control interface for application development.
Services
mavros/cmd/command
This service is utilized for mode switching between the multicopter and fixed-wing modes in the offboard operation. The message type is mavros_msgs/CommandLong. It corresponds to a mavlink message (mavlink::common::MAV_CMD::DO_VTOL_TRANSITION) defined in the link.
To illustrate, if we’d like to switch to the fixed-wing mode, then the service has to be called with settings below:
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;
To switch to the multicopter mode reversely,
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;