Application Programming Interface

We provide open source API for development with the Kerloud Flying Rover series, and candidate API interfaces will support C++, python and other languages. Details will be updated continuously in this part.

1. 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:

More programming details will be illustrated in the tutorial section here. We present here topics and services that are specifically related with our flying rover case.

1.1 Topics

(1) ~mavros/extended_state

This topic can be subscribed to obtain current flying rover state. The message type is mavros_msgs/ExtendedState, which is extended from the original version. An extra field, namely flyingrover_state, is provided to indicate the flying rover state, shown as follows. The candidate values for this field are those constants defined with the prefix 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

For clarity, we illustrate the meanings here:

  • flyingrover_state=0: the flying rover is not initialized yet;

  • flyingrover_state=1: the flying rover is operating in the rover mode;

  • flyingrover_state=2: the flying rover is operating in the multicopter mode;

  • flyingrover_state=3: the flying rover is in transition from the rover to the multicopter mode. The state will turn to the multicopter in manual mode instantaneously, or when the speed is lower than the param FR_V_TH_MC value (0.2m/s by default) in autopilot firmware in the offboard or other auto modes;

  • flyingrover_state=4: the flying rover is in transition from the multicopter to the rover mode, and it will tend to land manually or autonomously. The state will turn to the rover mode after landing;

(2) ~mavros/setpoint_position/local, ~mavros/setpoint_position/global

This topic is used to publish the position setpoint in the local or global frame for both rover and multicopter 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_velocity/cmd_vel_unstamped, ~mavros/setpoint_velocity/cmd_vel

These two topics are used to publish the velocity setpoint in the local frame for both rover and multicopter modes. The only difference between them is whether the velocity information is with a timestamp or not. The message type is geometry_msgs/Twist.

(4) ~mavros/setpoint_attitude/attitude, ~mavros/setpoint_attitude/thrust

These two topics can be utilized to set the attitude setpoint for both rover and multicopter modes, although it's recommended to use in the rover mode only. The message types are geometry_msgs/PoseStamped and mavros_msgs/Thrust respectively. The attitude thrust is directly fed into the main rotor throttle for the rover, and the yaw angle tracking error will be computed to generate the servo control input for steering.

1.2 Services

(1) ~mavros/cmd/command

This service is utilized for mode switching between the rover and multicopter modes in the offboard operation. The message type is mavros_msgs/CommandLong. It corresponds to a customized mavlink message (mavlink::common::MAV_CMD::DO_FLYINGROVER_TRANSITION) in https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_flyingrover/message_definitions/v1.0/common.xml.

To illustrate, if we'd like to switch to the multicopter mode, then the service has to be called with settings below:

    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;

To switch to the rover mode reversely,

    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;

Note that the mavlink::common::MAV_FLYINGROVER_STATE enumeration is defined here and presented below:

    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)

Similar with the ROS API in C++, ROS python API is implemented on basis of our maintained mavros and mavlink packages as well. The only difference is that all those topics and services mentioned above should be utilized with python.

Our maintained repositories are:

The code is explained in the tutorial section here. For brevity, the low level message communication is handled within the Px4Controller class, and the friendly API for user programming is wrapped within the Commander class, partially listed below:

  • move(x,y,z, BODY_FLU=False): request the vehicle to move to a desired position defined in either FLU frame or ENU frame, applicable in both rover and multicopter modes.

  • turn(yaw_degree): request the vehicle to turn to a desired yaw angle, applicable in multicopter mode only.

  • land(): request the vehicle to land in multicopter mode.

  • hover(): request the vehicle to hover at current position in multicopter mode.

  • arm(): request to arm the vehicle.

  • disarm(): request to disarm the vehicle on ground.

  • transit_to_rover(): request the vehicle to transit to rover mode.

  • transit_to_mc(): request the vehicle to transit to multicopter mode.

  • return_home(height): request the vehicle to return home, applicable in multicopter mode only.

Last updated