robomaster_msgs

package robomaster_msgs

This package implements all Robomaster specific interfaces used by the driver node RoboMasterROS. Most interfaces maps the arguments of SDK methods (e.g., robomaster_msgs/action/Move maps to arguments of rm:robomaster.chassis.Chassis.move() or the information provided by SDK subscribers (e.g., robomaster_msgs/msg/ChassisStatus maps to the callback arguments in rm:robomaster.chassis.Chassis.sub_status()).

Interfaces

Messages

message robomaster_msgs/msg/ArmorHit

A hit event detected by one of the sensors placed behind the LEDs. The Robomaster detects two kind of hits: collision using microphones, and infrared beams using infrared receivers.

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp of the hit

  • type (uint8) – type of hit; one of COLLISION or IR

  • location (uint8) – a bit mask for which sensors have detected the hit

  • level (uint16) – the hit impact strength as measured by the sensor microphone. Only applies to events of COLLISION type

Constants:
  • BOTTOM_BACK (uint8) = 1 – sensor location: on back of the chassis

  • BOTTOM_FRONT (uint8) = 2 – sensor location: on front of the chassis

  • BOTTOM_LEFT (uint8) = 4 – sensor location: on left of the chassis

  • BOTTOM_RIGHT (uint8) = 8 – sensor location: on right of the chassis

  • TOP_LEFT (uint8) = 16 – sensor location: on left of the gimbal

  • TOP_RIGHT (uint8) = 32 – sensor location: on right of the gimbal

  • COLLISION (uint8) = 0 – type: detected by a microphone

  • IR (uint8) = 1 – type: detected by the IR sensor

message robomaster_msgs/msg/AudioData

Raw audio samples .. note:: Unlike ROS1, ROS2 has no audio_common_msgs, so for now we define our own format to publish the raw 16-bit 48Khz audio stream from the camera mono microphone

Fields:
  • header (std_msgs/msg/Header) – the timestamp and frame of the microphone recording

  • data (int16[]) – an array of 16-bit audio samples

message robomaster_msgs/msg/AudioLevel

Sound level .. note:: Unlike ROS1, ROS2 has no audio_common_msgs, so we define our own format for sound level in dBFS

Fields:
message robomaster_msgs/msg/AudioOpus

Encapsulate a packet from an OPUS encoded audio stream

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp and origin of the packet

  • seq (uint64) – sequential number of the packet

  • buffer (uint8[]) – Opus data

message robomaster_msgs/msg/BlasterLED

Command to control the blaster LED

Fields:

brightness (float32) – relative intensity of the LED: 0.0: off, 1.0: full brightness

message robomaster_msgs/msg/CameraConfig

Command to configure the camera

Fields:

zoom (float32) – relative zoom

message robomaster_msgs/msg/ChassisStatus

High-level chassis state provided by the robot through robomaster.chassis.Chassis.sub_status(). TODO(Jerome): check

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp of the update

  • is_static (bool) – whenever the robot is still

  • up_hill (bool) – whenever the robot is facing uphill

  • down_hill (bool) – whenever the robot is facing downhill

  • on_slope (bool) – whenever the robot is on a lateral slope

  • is_pick_up (bool) – whenever the robot has been picked up

  • slip (bool) – whenever wheels are slipping

  • impact_x (bool) – whenever the accelerometer has registered a collision longitudinally

  • impact_y (bool) – whenever the accelerometer has registered a collision laterally

  • impact_z (bool) – whenever the accelerometer has registered a collision vertically

  • roll_over (bool) – whenever the robot is capsized

  • hill (bool) – whenever the robot is facing uphill and is still.

message robomaster_msgs/msg/DetectedGesture

Information about an gesture detected using vision

Fields:
message robomaster_msgs/msg/DetectedLine

Information about a line detected in the camera frame

Fields:
  • x (float32) – relative horizontal position of the line in the image (between 0 and 1)

  • y (float32) – relative vertical position of the line in the image (between 0 and 1)

  • angle (float32) – slope

  • curvature (float32) – curvature

message robomaster_msgs/msg/DetectedMarker

Information about a marker detected using vision

Fields:
message robomaster_msgs/msg/DetectedPerson

Information about a person detected using vision

Fields:

roi (robomaster_msgs/msg/RegionOfInterest) – bounding box

message robomaster_msgs/msg/DetectedRobot

Information about a robot detected using vision

Fields:

roi (robomaster_msgs/msg/RegionOfInterest) – bounding box

message robomaster_msgs/msg/Detection

Summary of vision detections

Fields:
message robomaster_msgs/msg/GimbalCommand

Command to control the gripper in speed

Fields:
  • yaw_speed (float32) = 0.0 – target yaw angular speed in rad/m

  • pitch_speed (float32) = 0.0 – target pitch angular speed in rad/m

message robomaster_msgs/msg/GripperState

State of the gripper

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp of the update

  • state (uint8) – one of PAUSE. OPEN. or CLOSE

Constants:
  • PAUSE (uint8) = 0 – Gripper inactive

  • OPEN (uint8) = 1 – Gripper open

  • CLOSE (uint8) = 2 – Gripper closed

message robomaster_msgs/msg/H264Packet

Encapsulate a packet from a H264 encoded video stream

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp and origin of the packet

  • seq (uint64) – sequential number of the packet

  • data (uint8[]) – H264 data

message robomaster_msgs/msg/LEDEffect

Control commands for all LEDs

Fields:
  • mask (uint8) = 63 – bitmask mask to select which LEDs to control

  • submask (uint8) = 255 – bitmask to select which portions of the gimbal LED to control. The 7 sub LEDs are enumerate clockwise

  • effect (uint8) = 1 – One of the effect enums

  • color (std_msgs/msg/ColorRGBA) – The desired LED color (not relevant for effect=OFF)

  • t1 (float32) = 1.0 – On interval duration, only relevant for effects PULSE and FLASH.

  • t2 (float32) = 1.0 – Off interval duration, only relevant for effects PULSE and FLASH.

Constants:
  • BOTTOM_BACK (uint8) = 1 – mask: chassis rear LED

  • BOTTOM_FRONT (uint8) = 2 – mask: chassis front LED

  • BOTTOM_LEFT (uint8) = 4 – mask: chassis left LED

  • BOTTOM_RIGHT (uint8) = 8 – mask: chassis right LED

  • BOTTOM (uint8) = 15 – mask: all chassis LEDs

  • TOP_LEFT (uint8) = 16 – mask: gimbal left LED

  • TOP_RIGHT (uint8) = 32 – mask: gimbal right LED

  • TOP (uint8) = 48 – mask: all gimbal LEDs

  • ALL (uint8) = 63 – mask: all LEDs

  • OFF (uint8) = 0 – effect: switch off LED

  • ON (uint8) = 1 – effect: switch LED to solid color

  • BREATH (uint8) = 2 – effect: breath

  • FLASH (uint8) = 3 – effect: flash LED

  • SCROLLING (uint8) = 4 – effect: scrolling

  • PULSE (uint8) = 5 – effect: pulse LED

message robomaster_msgs/msg/Mode

Coupling control model between gimbal and chassis.

Fields:

mode (uint8) – coupling mode, one of FREE, GIMBAL_LEAD, CHASSIS_LEAD

Constants:
  • FREE (uint8) = 0 – mode: gimbal and chassis are decoupled

  • GIMBAL_LEAD (uint8) = 1 – mode: chassis follows gimbal movements to maintain the same relative orientation

  • CHASSIS_LEAD (uint8) = 2 – mode: gimbal follows gimbal movements to maintain the same relative orientation

message robomaster_msgs/msg/PWM

Commands to control the 6 PWM interfaces

Fields:

fraction_of_duty_cycle (float32[6]) = [-1.0, -1.0, -1.0, -1.0, -1.0, -1.0] – Fraction of duty cycle in [0, 1]. Negative value signal to ignore the interface.

message robomaster_msgs/msg/RegionOfInterest

A region of interest (ROS) in an image. All values are in [0, 1] and are relative to image width and height

Fields:
  • x_offset (float32) – leftmost pixel of the ROI (0 if the ROI includes the left edge of the image)

  • y_offset (float32) – topmost pixel of the ROI (0 if the ROI includes the top edge of the image)

  • height (float32) – height of ROI

  • width (float32) – width of ROI

message robomaster_msgs/msg/SBus

Values recevied by the SBUS interface

Fields:
message robomaster_msgs/msg/SensorAdapter

Summarizes the state of up to 6 sensor adapters (each with 2 interfaces)

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp of the update

  • io (uint8[12]) – input pin state (0 or 1)

  • adc (int16[12]) – adc state

  • port (uint8[12]) = [1, 2, 1, 2, 1, 2, 1, 2, 1, 2, 1, 2] – interface intentifier

  • id (uint8[12]) = [1, 1, 2, 2, 3, 3, 4, 4, 5, 5, 6, 6] – sensor adapter identifier

message robomaster_msgs/msg/Serial

Encapsulates serial communication received or to be sent through UART

Fields:
message robomaster_msgs/msg/ServoCommand

Command to control a servo in speed

Fields:
  • index (uint8) – ID of the servo (between 0 and 2)

  • enable (bool) = True – whenever to engage or disengage the servo

  • angular_speed (float32) = 0.0 – target angular speed in rad/m

message robomaster_msgs/msg/ServoRawState

Raw state from the servos on ports {0, 1, 2, 3}

Fields:
  • header (std_msgs/msg/Header) – header with the time stamp of the update

  • valid (bool[4]) – whenever a servo in connected to a port

  • value (int32[4]) – the angle of the servos (1024 corresponds to 180 degrees)

  • speed (int32[4]) – the speed of the servos (1024 corresponds to about 36 degrees per seconds)

message robomaster_msgs/msg/SpeakerCommand

An command to stop or play a predefined sound or an audio file from the speaker.

Fields:
  • sound_id (int32) = 1 – ID of the sound to play

  • times (uint8) = 1 – how many times to play the same sound (0: infinite loop)

  • control (uint8) – Control command: one of CONTROL_STOP, CONTROL_PLAY, CONTROL_ADD

  • file (string) – if not empry, the local file to be played.

Constants:
  • CONTROL_STOP (uint8) = 0 – Stop playing sound

  • CONTROL_PLAY (uint8) = 1 – Start playing sound after stopping currently played sounds

  • CONTROL_ADD (uint8) = 2 – Start playing sound, without stopping currently played sounds

message robomaster_msgs/msg/WheelSpeeds

A Command to set linear speeds for each wheel of the robot.

Fields:
  • front_left (float32) – front left wheel tangential speed in m/s

  • front_right (float32) – front right wheel tangential speed in m/s

  • rear_left (float32) – rear left wheel tangential speed in m/s

  • rear_right (float32) – rear right wheel tangential speed in m/s

Services

service robomaster_msgs/srv/GetADC

Command to read on the Analog to Digital Converter (ADC) interface of one of the sensor adapters.

Request fields:
  • id (uint8) – 0 or 1: ID of one of two interfaces of a sensor adapter

  • port (uint8) – 0, 1, 2, or 3: ID of one of the 4 sensor adapter that can be connected to the robot

Response fields:
  • valid (bool) – whenever the sensor adapter is enabled

  • value (uint16) – the raw value read by the ADC

service robomaster_msgs/srv/GetIO

Command to read an IO pin state of sensor adapters.

Request fields:
  • id (uint8) – 0 or 1: ID of one of two interfaces of a sensor adapter

  • port (uint8) – 0, 1, 2, or 3: ID of one of the 4 sensor adapter that can be connected to the robot

Response fields:
  • valid (bool) – whenever the sensor adapter is enabled

  • value (uint8) – the pin state (0 or 1)

service robomaster_msgs/srv/GetPulse

Command to read the pulse duration measured by one of the sensor adapters.

Request fields:
  • id (uint8) – 0 or 1: ID of one of two interfaces of a sensor adapter

  • port (uint8) – 0, 1, 2, or 3: ID of one of the 4 sensor adapter that can be connected to the robot

Response fields:
  • valid (bool) – whenever the sensor adapter is enabled

  • time_ms (uint32) – the pulse duration in milliseconds

service robomaster_msgs/srv/GetServoAngle

Command to read the servo angle.

Request fields:

index (uint8) – ID of the servo (between 0 and 2)

Response fields:

angle (float32) – absolute angle in rad

Actions

action robomaster_msgs/action/GripperControl

The gripper goal to open, close, or pause, by applying some power.

The action succeeds when the gripper reaches the the target state.

Goal fields:
  • target_state (uint8) – the target gripper state: one of PAUSE, OPEN, or CLOSE

  • power (float32) = 0.5 – the relative amount of power in [0, 1]

Goal constants:
  • PAUSE (uint8) = 0 – the gripper state when manually stopped

  • OPEN (uint8) = 1 – the open gripper state

  • CLOSE (uint8) = 2 – the closed gripper state

Result fields:

duration (builtin_interfaces/msg/Duration) – the duration of the action

Feedback fields:

current_state (uint8) – the current gripper state: one of PAUSE, OPEN, or CLOSE

action robomaster_msgs/action/Move

An action to move the robot relative to its current pose, at desired angular and linear speeds using the onboard control.

The action succeeds when the robot arrives near the goal pose.

Goal fields:
  • x (float32) – target relative position (longitudinal component with positive towards front)

  • y (float32) –

  • theta (float32) – target relative angle in rad

  • linear_speed (float32) = 0.5 – maximal linear speed in m/s

  • angular_speed (float32) = 0.5236 – maximal angular speed in rad/s (default is 30 deg/s)

Feedback fields:

progress (float32) – the relative progress towards goal from 0 to 1

action robomaster_msgs/action/MoveArm

An action to move the arm end effector using the onboard control. Coodinates may be relative to the current end effector position or absolute with respect to arm_base_link.

The action succeeds when the end effector come closest to the target point as possible .. note:: it may not be able to reach the target point

Goal fields:
  • x (float32) – target x-coordinate in meter (x-axis points forwards)

  • z (float32) – target z-coordinate in meter (z-axis points upwards)

  • relative (bool) – whenever the coordinates are relative or absolute.

Feedback fields:

progress (float32) – the relative progress towards goal from 0 to 1

action robomaster_msgs/action/MoveGimbal

An action to rotate the gimbal using the onboard control. Attitute can be specified in four different frames.

The action succeeds when the gimbal reaches the target orientation.

Goal fields:
  • yaw (float32) – target yaw in rad

  • pitch (float32) – target pitch in rad

  • yaw_speed (float32) = 0.52 – maximal yaw rotation speed in rad/s

  • pitch_speed (float32) = 0.52 – maximal pitch rotation speed in rad/s

  • frame (uint8) = 3 – the frame in which target orientation is specified. One of FIXED, GIMBAL, CHASSIS_GIMBAL_PITCH, or CHASSIS_FIXED_PITCH

Goal constants:
  • FIXED (uint8) = 0 – Frame: gravity aligned, origin set at boot (same frame as chassis odometry and imu)

  • GIMBAL (uint8) = 1 – Frame: attached to gimbal, useful to send relative movements.

  • CHASSIS_GIMBAL_PITCH (uint8) = 2 – Frame: yaw aligned to chassis, pitch as in GIMBAL

  • CHASSIS_FIXED_PITCH (uint8) = 3 – Frame: yaw aligned to chassis, pitch as in FIXED

Feedback fields:

progress (float32) – the relative progress towards goal from 0 to 1

action robomaster_msgs/action/MoveServo

An action to rotate a servo using the onboard control.

The action succeeds when the servo reaches the target angle.

Goal fields:
  • index (uint8) – ID of the servo (between 0 and 2)

  • angle (float32) – absolute target angle in rad

Feedback fields:

progress (float32) – the relative progress towards goal from 0 to 1

action robomaster_msgs/action/PlaySound

An action to play a predefined sound or an audio file from the speaker.

The action succeeds when the speaker finishes to play.

Goal fields:
  • sound_id (int32) = 1 – ID of the sound to play

  • times (uint8) = 1 – how many times to play the same sound

  • file (string) – if not empry, the local file to be played.

Feedback fields:
  • time (uint8) – the current count of sound repetitions

  • progress (float32) – the relative progress towards goal from 0 to 1

action robomaster_msgs/action/RecenterGimbal

An action to recenter the gimbal using the onboard control distict from robomaster_msgs/action/MoveGimbal to trigger a specific onboard action.

The action succeeds when the gimbal reaches the neutral orientation.

Goal fields:
  • yaw_speed (float32) = 1.04 – maximal yaw rotation speed in rad/s

  • pitch_speed (float32) = 1.04 – maximal pitch rotation speed in rad/s

Feedback fields:

progress (float32) – the relative progress towards goal from 0 to 1