Skip to content

Output Topics

Introduction

These topics are used by Avular Programming Interface to expose the data from the Vertex One to the user, so that it can be used e.g. to control the Vertex One.

Coordinate System Info

Topic: /robot/estimate/coordinate_system_info

Description: Flight Controller state estimate coordinate frame info. The flight controller will initialize with a local relative coordinate frame until the GNSS quality is good enough to initialize a local tangent plane. This leads to the change of coordinate system and will provide the origin of the local tangent plane in the latitude, longitude and altitude fields according to the WGS84 standard.

Data Frequency: 1 hz

ROS Message Type: Custom (See below):

uint8 LOCAL_RELATIVE=0
uint8 LOCAL_TANGENT_PLANE=1
uint8 UTM=2
uint8 UNKNOWN=3

# Type of coordinate system used, default value is UNKNOWN
uint8 type 3

# Local relative only
string map_name

# Local tangent plane only
float64 latitude
float64 longitude
float64 altitude

# UTM only
# Zone can be 0 to 60 (-1 is default/unknown)
int8 zone -1
bool north true
float64 x_offset
float64 y_offset
float64 z_offset

Example: ros2 topic echo --once /robot/estimate/coordinate_system_info

Flight Controller State

Topic: /robot/estimate/state

Description: Flight Controller State Estimation. The position and velocity is with respect to the origin defined in the coordinate_system_info message. The angular velocity is provided in the body frame.

Data Frequency: 50 hz

ROS Message Type: nav_msgs::msg::Odometry (External Link) (See below):

Field Name Data Type Unit ROS Message Type
position float[3] m geometry_msgs::msg::PoseWithCovariance
orientation float[4] quaterions geometry_msgs::msg::PoseWithCovariance
pose_covariance float[21] - geometry_msgs::msg::PoseWithCovariance
linear_velocity float[3] m/s geometry_msgs::msg::TwistWithCovariance
angular_velocity float[3] rad/s geometry_msgs::msg::TwistWithCovariance
twist_covariance float[21] - geometry_msgs::msg::TwistWithCovariance

Note

Sensible data won't be available before the automatic sensor calibration is completed. For that, the remote controller needs to be connected and the drone needs to stand still until it is "ready for arming". When the drone is ready, the mode_supervisor field of the /robot/supervisor_mode message will be 4.

Example: ros2 topic echo --once /robot/estimate/state

Supervisor Mode

Topic: /robot/supervisor_mode

Description: Vertex One Supervisor mode. All fields refer to an enum below. Documented in message type.

Data Frequency: 1 hz

ROS Message Type: SupervisorMode.msg (See below):

Field Name Data Type
mode_supervisor uint8
mode_armed uint8
mode_of_operation uint8
mode_of_flight uint8
mode_external_control uint8

# Vertex Supervisor Mode

# Header containing a timestamp
std_msgs/Header header

#Main mode of the supervisor
uint8 SUPERVISOR_MODE_NONE       = 0
uint8 SUPERVISOR_INIT            = 1     # Flight Controller initializing
uint8 SUPERVISOR_BOOT_OK         = 2     # Flight Controller booted up succesfully
uint8 SUPERVISOR_CALIBRATING     = 3     # Flight Controller calibrating sensors
uint8 SUPERVISOR_E_STOP          = 5     # Flight Controller in emergency stop state, reboot required

uint8   mode_supervisor  

# Armed mode of the supervisor 
# Supervisor mode inside the flight mode 'ARMED' otherwise value is 'ARMED_MODE_NONE'
uint8   ARMED_MODE_NONE         = 10
uint8   ARMED_MODE_IDLE         = 11     # Flight Controller in idle mode
uint8   ARMED_MODE_TAKE_OFF     = 12     # Flight Controller in take-off mode
uint8   ARMED_MODE_IN_FLIGHT    = 13     # Take-off completed, in flight
uint8   ARMED_MODE_LANDING      = 14     # Flight Controller in landing mode 
uint8   ARMED_MODE_FAIL_SAFE    = 15     # Flight Controller in emergency landing

uint8   mode_armed 

# Supervisor mode of operation
# Mode of operation when main mode is 'READY' otherwise value is 'MODE_N0NE'
uint8   OPERATION_MODE_NONE                 = 20
uint8   OPERATION_MODE_ATTITUDE_MANUAL      = 21     # Manual RC control over attitude angles, altitude velocity and yaw velocity
uint8   OPERATION_MODE_POSITION_MANUAL      = 22     # Manual RC control over horizontal velocity in body frame, altitude velocity and yaw velocity
uint8   OPERATION_MODE_POSITION_EXTERNAL    = 23     # External control while following waypoints or commands.

uint8   mode_of_operation

# Supervisor flight mode
# Supervisor mode inside the main 'READY' mode  otherwise value is 'MODE_N0NE'
uint8   FLIGHT_MODE_NONE                = 30
uint8   FLIGHT_MODE_PRE_FLIGHT_CHECK    = 31     # Basic sensor and RC checks
uint8   FLIGHT_MODE_DISARMED            = 32     # Flight Controller ready, motors disarmed
uint8   FLIGHT_MODE_ARMED               = 33     # Flight Controller ready, motors armed
uint8   FLIGHT_MODE_EMERGENCY_STOP      = 34     # Flight Controller in emergency stop mode, motors stopped

uint8   mode_of_flight

# External supervisor mode
uint8   EXTERNAL_MODE_NONE              = 40
uint8   EXTERNAL_MODE_UNDEFINED         = 41     # Undefined external control
uint8   EXTERNAL_MODE_POSITION          = 42     # External control over position
uint8   EXTERNAL_MODE_VELOCITY          = 43     # External control over velocity
uint8   EXTERNAL_MODE_ACCELERATION      = 44     # External control over acceleration
uint8   EXTERNAL_MODE_ATTITUDE_THRUST   = 45     # External control over attitude and thrust
uint8   EXTERNAL_MODE_WAYPOINT          = 46     # External control over waypoints

uint8   mode_external_control
Example: ros2 topic echo --once /robot/supervisor_mode

Remote Controller

Topic: /robot/sensor/remote_controller/data

Description: The state of the remote controller buttons and sticks are published on this topic. The data is published as a Joy message. The button values represent a short press (1) detected upon release or a long press (2) when held for more than 500ms.

Data Frequency: 100 hz

ROS Message Type: sensor_msgs::msg::Joy (External Link) (See below):

The fields of the Joy message are as follows:

Field Name Index Data Type Description
axes 0 float32 x-axis right stick
axes 1 float32 y-axis richt stick
axes 2 float32 x-axis left stick
axes 3 float32 y-axis left stick
buttons 0 int32 button a
buttons 1 int32 button b
buttons 2 int32 button c
buttons 3 int32 button d
buttons 4 int32 trigger button
buttons 5 int32 home button
buttons 6 int32 wheel

Timestamping

Topic: /robot/timestamping/offset

Description: Timestamping used for converting Real-Time MCU timestamping to Onboard Computing Module's UTC (ROS Default).

  • nanoseconds_since_boot_prime refers to the time of the Real-Time MCU
  • nanoseconds_since_boot_jetson refers to the time of the Onboard Computing Module
  • timestamp_offset refers to time offset between the two
  • offset_utc_boot_time refers to time offset between boot time and UTC

Data Frequency: 10 hz

ROS Message Type: Timestamping.msg (See below):

Field Name Data Type Unit
nanoseconds_since_boot_prime uint64 -
nanoseconds_since_boot_jetson uint64 -
timestamp_offset int64 -
offset_utc_boot_time uint64 -
# Timestamping message
std_msgs/Header header

uint64 nanoseconds_since_boot_prime
uint64 nanoseconds_since_boot_jetson

int64 timestamp_offset  # Offset from Flight Controller to Onboard Computing Unit
uint64 offset_utc_boot_time # Used for conversion from boot time to UTC

Example: ros2 topic echo --once /robot/timestamping/offset