Skip to content

Sensor Topics

Introduction

Vertex One contains series of sensors onboard that can be read out using the commands of Avular Programming Interface.

IMU

Topic: /robot/sensor/imu/data

Description: Vertex One contains 4 IMUs. These are fused and filtered to output reliable and stable IMU data that is published on ROS network.

Data Frequency: 500 hz

ROS Message Type: sensor_msgs::msg::Imu (See below):

Field Name Data Type Unit
accelerometer float[3] m/s2
gyroscope float[3] rad/s
accelerometer_covariance (diagonal) float[3] -
gyroscope_covariance (diagonal) float[3] -

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/sensor/imu/data

Barometers

Vertex One has two barometers on board. Both are published on ROS network.

Topic: /robot/sensor/barometer_1

Topic: /robot/sensor/barometer_2

Description: Barometer 1/2 state and info.

Data Frequency: 50 hz

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

Field Name Data Type Unit
pressure float hPa
variance float -
temperature float °C

# Barometer sensor message
# If uninitialized, values are set to -1.

std_msgs/Header header   

float32     pressure        # hPa 
float32     variance        # variance of pressure measurement
float32     temperature     # degree celcius
Example: ros2 topic echo --once /robot/barometer/one/data

GNSS

Topic: /robot/sensor/gnss/data

Description: Vertex One's GNSS status/location data.

Data Frequency: 50 hz

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

Field Name Data Type Unit
status int8 -
latitude double -
longitude double -
altitude float -
position_covariance float[2] -
num_sats_visible int8 -
num_sats_used int8 -

Note

In case you need to access the GNSS data without the use of ROS, you can connect to the GNSS module directly via UART.

Example: ros2 topic echo --once /robot/sensor/gnss/data

GNSS Status

Topic: /robot/sensor/gnss/status

Description: Vertex One's GNSS sensor status and info.

Data Frequency: 50 hz

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

Field Name Data Type Unit
satellites_visible uint8 -
satellites_used uint8 -
# GNSS status, a supplement to sensor_msgs/NavSatFix.
std_msgs/Header header

# GNSS fix type
int8 STATUS_NO_FIX=-1    # Unable to fix position
int8 STATUS_2D_FIX=0     # 2D fix
int8 STATUS_3D_FIX=1     # 3D fix
int8 STATUS_RTK_FLOAT=2  # RTK with floating solution, the RTK algorithm hasn’t found an acceptable fix solution (yet)
int8 STATUS_RTK_FIX=3    # RTK with fixed solution
int8 status

# Uncertainty of measurement, 1-sigma confidence
# float32 horizontal_position_accuracy  # Horizontal position uncertainty (meters) expressed as a bivariate normal distribution, 1-sigma then corresponds to 39.4% confidence
# float32 vertical_position_accuracy    # Vertical position uncertainty (meters) expressed as a univariate normal distribution, 1-sigma then corresponds to 68% confidence

# Satellites visible
# Max reported is 30, more might be used internally in the GNSS module.
uint8 satellites_visible # Number of satellites visible
uint8 satellites_used    # Number of satellites used

Example: ros2 topic echo --once /robot/sensor/gnss/status

Downward-Facing LiDAR

Topic: /robot/sensor/lidar/downwards/data

Description: Vertex One's downward-facing 1D LiDAR sensor data.

Data Frequency: 50 hz

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

Field Name Data Type Unit
range uint16 cm
min_range uint16 cm
max_range uint16 cm
field_of_view uint8 deg

Example: ros2 topic echo --once /robot/sensor/lidar/downwards/data

Magnetometer

Topic: /robot/sensor/magnetometer/data

Description: Vertex One's calibrated and rotated magnetometer sensor data in the body frame. The covariance is currently not supported.

Data Frequency: 50 hz

ROS Message Type: sensor_msgs::msg::MagneticField (External Link)

Field Name Data Type Unit
magnetic_field float[3] mG
covariance float[3] -

Example: ros2 topic echo --once /robot/sensor/magnetometer/data

Remote Controller Data

Topic: /robot/sensor/remote_controller/data

Description: Raw channel data from the remote controller. Not all fields are occupied due to the number of supported RC channels. Only the four axis and first four buttons are used.

Data Frequency: 50 hz

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

Field Name Data Type Unit
axes float[4] -
buttons float[12] -
header_stamp_sec uint32 s
header_stamp_nsec uint32 ns

Example: ros2 topic echo --once /robot/sensor/remote_controller/data

1st generation

# Button/switch value range value description
0 Button SB -1 - 1 -1 = back, 1 = front
1 Button SA -1 - 1 -1 = back, 0 = middle, 1 = front
2 Button SF -1 - 1 -1 = back, 1 = front
3 Button SE -1 - 1 -1 = back, 0 = middle, 1 = front

2nd generation

# Button/switch value range value description
0 Button A 0 - 2 0 = not pressed, 1 = short press, 2 = long press
1 Button B 0 - 2 0 = not pressed, 1 = short press, 2 = long press
2 Button C 0 - 2 0 = not pressed, 1 = short press, 2 = long press
3 Button D 0 - 2 0 = not pressed, 1 = short press, 2 = long press
4 Button Trigger 0 - 2 0 = not pressed, 1 = short press, 2 = long press
5 Button Home 0 - 2 0 = not pressed, 1 = short press, 2 = long press
6 Wheel 0 - 255 0 = left, 127 = middle, 255 = right

PowerPack Data

Topic: /robot/sensor/battery

Description: PowerPack state and info.

Data Frequency: 1 hz

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

Field Name Data Type Unit
voltage uint32 mV
current int32 mA
temperature int16 °C
state_of_charge uint8 %
time_remaining uint16 s
state_of_health uint8 %
alert uint32 -
state uint8 -

# Battery information message
# For all field holds, if the field is unavailable the max value will be provided (i.e. UINT32_MAX)

# Battery alert constants
uint32 BATTERY_ALERT_CELL_UNDERVOLTAGE = 1
uint32 BATTERY_ALERT_CELL_OVERVOLTAGE  = 2
uint32 BATTERY_ALERT_OVERCURRENT_CHARGE = 4
uint32 BATTERY_ALERT_OVERCURRENT_DISCHARGE = 8
uint32 BATTERY_ALERT_OVERLOAD_DISCHARGE = 16
uint32 BATTERY_ALERT_OVERLOAD_DISCHARGE_LATH = 32
uint32 BATTERY_ALERT_SHORT_CIRCUIT_DISCHARGE = 64
uint32 BATTERY_ALERT_SHORT_CIRCUIT_DISCHARGE_LATCH = 128
uint32 BATTERY_ALERT_OVERTEMPERATURE_CHARGE = 256
uint32 BATTERY_ALERT_OVERTEMPERATURE_DISCHARGE = 512
uint32 BATTERY_ALERT_UNDERTEMPERATURE_CHARGE = 1024
uint32 BATTERY_ALERT_UNDERTEMPERATURE_DISCHARGE = 2048
uint32 BATTERY_ALERT_AFE_ALERT = 4096
uint32 BATTERY_ALERT_RESERVED_1 = 32768
uint32 BATTERY_ALERT_PRECHARGE_TIMEOUT_SUSPEND = 262144
uint32 BATTERY_ALERT_RESERVED_2 = 131072
uint32 BATTERY_ALERT_CHARGE_TIMEOUT_SUSPEND = 262144
uint32 BATTERY_ALERT_RESERVED_3 = 524288
uint32 BATTERY_ALERT_OVERCHARGE = 1048576

# Battery state constants
uint8 BATTERY_STATE_READY = 0
uint8 BATTERY_STATE_PREDISCHARGING = 1
uint8 BATTERY_STATE_BALANCING = 2
uint8 BATTERY_STATE_ONE_MODULE_FAILED = 3
uint8 BATTERY_STATE_COMMUNICATION_ERROR = 4

std_msgs/Header header      

uint32      voltage             # mV
uint32      current             # positive on discharge (mA)
int16       temperature         # degree celcius
uint8       state_of_charge     # 0-100%
uint16      time_remaining      # Estimated time remaining until emergency behavior (s)
uint8       state_of_health     # 0-100%
uint32      alert               # Battery alert status
uint8       state               # Battery state
Example: ros2 topic echo --once /robot/sensor/battery/data