Application Programming Interface (API)

We provide open source API for development with the Kerloud Autocar 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:

1.1 Topics

(1) ~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.

(2) ~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.

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

These two topics are utilized to set the attitude and thrust setpoint. The message type is geometry_msgs/PoseStamped and mavros_msgs/Thrust. 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.

(4) ~mavros/actuator_control

The topic can be used to directly control the low level actuators including the steering servo and main motor. The message type is mavros_msgs/ActuatorControl. The channel indexes for the steering servo and main motor are 2 and 3 respectively.

1.2 Services

(1) ~mavros/cmd/command

This service is utilized for mode switching between forward and backward driving in the offboard mode. The message type is mavros_msgs/CommandLong. It corresponds to a customized mavlink message (mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING) in https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_rover/message_definitions/v1.0/common.xml.

To illustrate, if we’d like to switch to forward driving, then the service has to be called with settings below:

    mavros_msgs::CommandLong set_forward_driving_cmd;
    set_forward_driving_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING;
    set_forward_driving_cmd.request.confirmation = 0;
    set_forward_driving_cmd.request.param1 = 1.0f;

Reversely for the backward driving,

    mavros_msgs::CommandLong set_backward_driving_cmd;
    set_backward_driving_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING;
    set_backward_driving_cmd.request.confirmation = 0;
    set_backward_driving_cmd.request.param1 = 0.0f;

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 will be explained in the tutorial section. 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_position(x,y,z, BODY_FLU=False): request the vehicle to move to a desired position defined in either FLU frame or ENU frame, the z channel is neglected.

  • move_velocity(vx,vy,vz, BODY_FLU=False): request the vehicle to move with a velocity defined in either FLU frame or ENU frame, the z channel is neglected.

  • set_forward_driving(): request the vehicle to move forward, which is applicable only in attitude and actuator control command modes.

  • set_backward_driving(): request the vehicle to move backward, which is applicable only in attitude and actuator control command modes.

  • set_yaw_and_throttle(): set desired yaw angle and throttle for the vehicle.

  • set_steering_servo_and_throttle(): set direct actuator control for the vehicle, including steering servo and throttle inputs.

  • arm(): request to arm the vehicle.

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

  • return_home(): request the vehicle to return home, which is the origin of the ENU frame.