Application Programming Interface (API)

We provide open source API for development with Pursuit autopilot, and candidate API interfaces will support C++, python and other languages. Details will be updated continuously in this part. Note that we assume users are familiar with basic concepts about ROS, and those who don’t meet the prerequisite are recommended to go through official tutorials in http://wiki.ros.org/ROS/Tutorials.

Caution

📌 The officially supported development environment is Ubuntu 18.04 with ROS Melodic only. Users can attempt the Docker method in other host environment.

ROS API (C++)

The ROS API for Pursuit autopilot is implemented in ROS packages, and we maintain several packages as follows:

1. pursuit_driver node

(1) Subscribed topics

The following topics are used in product release only, and shall not be used by developers

  • /pursuit_outdoor_avoidance/trajectory/generated (mavros_msgs::Trajectory):

    The generated trajectory from the navigation module to be sent to the Pursuit autopilot.

  • /pursuit_outdoor_avoidance/avoidance_status (pursuit_msgs::AvoidanceStatus):

    The avoidance status for obstacle detection with the onboard laser scanner.

  • /pursuit_nav/smooth_cmd_vel (geometry_msgs::Twist):

    The smooth command velocity from the navigation module to be sent to the Pursuit autopilot.

(2) Published topics

  • ~pursuit_driver/ackermann_drive_cmd ( ackermann_msgs::AckermannDriveStamped ):

    The drive command sent to the VCU AGV chassis by the autopilot, applicable for Ackermann vehicles only.

  • ~pursuit_driver/vehicle_gps_position ( mavros_msgs::GPSRAW):

    The GPS position of the vehicle, which is the output from the onboard RTK device.

  • ~pursuit_driver/vehicle_local_pose ( geometry_msgs::PoseStamped):

    The local position and attitude of the vehicle expressed in ENU (East-North_Up) frame when the vehicle localization is ready after GPS lock.

  • ~pursuit_driver/vehicle_local_velocity (geometry_msgs::TwistStamped):

    The local velocity of the vehicle expressed in ENU frame.

  • ~pursuit_driver/trajectory/desired (mavros_msgs::Trajectory):

    The desired waypoint setpoint requested by the autopilot.

  • ~pursuit_driver/vehicle_ctrl_state (pursuit_msgs::VehicleCtrlState):

    The control state defined by the autopilot, including arming state, navigation state, etc.

  • ~pursuit_driver/vcu_base_status (pursuit_msgs::VcuBaseStatus):

    The state of VCU base in the ground vehicle.

  • ~pursuit_driver/vcu_cmd_vel (geometry_msgs::Twist):

    The velocity command sent to the VCU base by the Pursuit autopilot.

  • ~pursuit_driver/vehicle_angular_velocity (std_msgs::Float32MultiArray):

    The attitude rate of the vehicle expressed in the ENU frame.

2. pursuit_msgs package

The customized messages can be referred in https://gitee.com/cloudkernel-tech/pursuit_msgs/tree/main/msg, and they are self-explanatory in corresponding definitions. For instance, the content of VcuBaseStatus message is shown below, which contains the VCU status of the AGV chassis such as steering angle, forward speed, heading rate, etc. The valid fields are dependent on the vehicle type.

# Base type definitions
uint8 VCU_BASE_TYPE_UNDEFINED = 0
uint8 VCU_BASE_TYPE_ACKERMANN = 1
uint8 VCU_BASE_TYPE_DDRIVE_4WHEELS = 2

# Gear position definitions
uint8 VCU_GEAR_POSITION_UNDEFINED = 0   # undefined
uint8 VCU_GEAR_POSITION_P = 1   # pause/stop
uint8 VCU_GEAR_POSITION_R = 2   # recede
uint8 VCU_GEAR_POSITION_N = 3   # null
uint8 VCU_GEAR_POSITION_D = 4   # forward

# Operating mode definitions
uint8 VCU_OPERATING_MODE_AUTO = 0
uint8 VCU_OPERATING_MODE_REMOTE = 1
uint8 VCU_OPERATING_MODE_STOP = 2

std_msgs/Header         header

uint8       vcu_base_type         # vcu base type
uint8       gear_position         # current gear position
float32     speed                 # current moving speed, unit: m/s, positive value only
bool        steering_angle_valid    # valid flag for steering angle
float32     steering_angle          # steering angle in radians
bool        twist_valid
float32[3]  vel                     # velocity along body axes (m/s)
bool        heading_rate_valid
float32     heading_rate            # heading rate (rad/s)

uint8       operating_mode          # current operating mode

3. mavros package

The mavros package originates from the PX4 community (http://wiki.ros.org/mavros). We add customized messages for the Pursuit autopilot. Most messages can be referred in the official mavros wiki page, and we only list those that are commonly used in our case.

(1) Subscribed topics

  • ~mavros/setpoint_position/local (geometry_msgs/PoseStamped)

    The position setpoint expressed in the ENU frame that is sent to the autopilot (enabled in offboard mode only)

  • ~mavros/setpoint_velocity/cmd_vel (geometry_msgs::TwistStamped)

    The velocity setpoint expressed in the ENU frame that is sent to the autopilot (enabled in offboard mode only)

  • ~mavros/vcu_command_velocity/from_nav (geometry_msgs::Twist)

    The command velocity (linear and angular velocities in the body frame) to be sent to the autopilot (enabled in offboard mode only)

(2) Published topics

  • ~mavros/state (mavros_msgs/State)

    The state of the autopilot, including arming status, mode, connection state, etc.

  • ~mavros/global_position/global (sensor_msgs/NavSatFix)

    GPS global position and satellite status for the vehicle.

  • ~mavros/local_position/pose ( geometry_msgs::PoseStamped):

    The local position and attitude of the vehicle expressed in ENU (East-North_Up) frame when the vehicle localization is ready after GPS lock.

  • ~mavros/local_position/velocity (geometry_msgs/TwistStamped)

    Velocity data from the autopilot.

  • ~mavros/imu/data_raw (sensor_msgs/Imu)

    Raw IMU data without orientation, including accelerometer and gyroscope data.

  • ~mavros/vcu_base_status/output (pursuit_msgs::VcuBaseStatus):

    The state of VCU base in the ground vehicle.

  • ~mavros/vcu_command_velocity/output (geometry_msgs::Twist):

    The velocity command sent to the VCU base by the Pursuit autopilot.

(3) Services

  • ~mavros/set_mode (mavros_msgs/SetMode)

    Set the operation mode for the autopilot, including offboard, mission and stabilized modes.

  • ~mavros/cmd/arming (mavros_msgs/CommandBool)

    Change arming status from the companion computer, e.g. armed/disarmed switching.