Skip to main content

ROS API

warning

The ROS API in the beta version is subject to changes.

Subscribed topics

  • controller/cmd_ackermann (ackermann_msgs/msg/AckermannDrive)

    Steers the robot when operating in the Ackermann steering mode.

  • controller/cmd_turn_in_place (?) Not implemented yet

    Steers the robot when operating in the Turn-In-Place steering mode.

  • controller/cmd_vel (geometry_msgs/msg/Twist) Not implemented yet

    Steers the robot using Twist commands. More standardized way to control the robot.
    Useful for some navigation stacks. Not recommended for manual teleoperation.

  • controller/led_strip_state (rapha_interfaces/msg/LedStripState)

    Sets a new user state for all the LEDs in the LED strip.

  • controller/led_panel_state (rapha_interfaces/msg/LedPanelState) Not implemented yet

    Sets a new user state for all the LEDs in the specified LED panel.

Published Topics

Services

Parameters

controller

  • drivetrain.wheel_base (type: float, default: 0.378)

    Distance between front and rear wheels. [m][m]

  • drivetrain.track_width (type: float, default: 0.384)

    Distance between left and right wheels. [m][m]

  • drivetrain.wheel_radius (type: float, default: 0.08)

    Radius of the wheel. [m][m]

  • drivetrain.max_wheel_angular_velocity (type: float, default: 19.0)

    Maximum allowable wheel angular velocity. [rads][\frac{rad}{s}]

  • drivetrain.change_mode_acceleration (type: float, default: 2.0)

    Acceleration to use when changing steering mode. [ms2,rads2][\frac{m}{s^2}, \frac{rad}{s^2}]

  • drivetrain.change_mode_steering_angle_velocity (type: float, default: 4.0)

    Steering angle velocity to use when changing steering mode. [rads][\frac{rad}{s}]

  • drivetrain.max_steering_angle (type: float, default: 1.08)

    Maximum steering angle used in ackermann mode. [rad][rad]

  • drivetrain.input_timeout (type: float, default: 0.5)

    The duration from last received target, after which the controller will stop the robot. Set to 0 to disable. [s][s]

  • drivetrain.wheel_disable_timeout (type: float, default: 10.0)

    The duration from last received target, after which the controller will disable all motors. Set to 0 to disable. [s][s]

  • drivetrain.servo_left_position_offset (type: float, default: 0.0)

    Offset added to the left servo position. [rad][rad]

  • drivetrain.servo_right_position_offset (type: float, default: 0.0)

    Offset added to the right servo position. [rad][rad]

  • drivetrain.servo_calibration_power_threshold (type: float, default: 20.0)

    The minimal motor power after which we assume the servo is pressing against the bumper during calibration procedure. [W][W]

  • drivetrain.servo.acceleration_divider (type: int, default: 10)

    Raw acceleration divider value passed to servo motors.

  • drivetrain.servo.position_loop_speed (type: float, default: 5.0)

    Position loop speed value passed to servos motors. [rads][\frac{rad}{s}]

  • drivetrain.wheel.acceleration_divider (type: int, default: 2)

    Raw acceleration divider value passed to wheel motors.

Custom message types

  • rapha_interfaces/msg/SteeringMode
Represents the steering mode used by the drivetrain controller.
uint8 ACKERMANN=0
uint8 TURN_IN_PLACE=1

uint8 data
  • rapha_interfaces/msg/BatteryMode
Represents the target or actual battery power mode.
# Whether the battery is charging.
bool charging

# Whether the battery is used as a power source.
bool draining
  • rapha_interfaces/msg/BatteryState
Represents the state of a single battery.
# The current voltage in volts.
float64 voltage

# Estimated state of charge in percents.
float64 state_of_charge

# The target battery mode.
rapha_interfaces/BatteryMode target_mode

# The actual battery mode.
rapha_interfaces/BatteryMode current_mode
  • rapha_interfaces/msg/PowerSystemState
Represents the state of the Power System.
std_msgs/Header header

# Whether the charger is connected.
bool charger_connected

# Whether the batteries are connected.
bool bat1_connected
bool bat2_connected

# The states of the batteries, not valid for unconnected batteries.
rapha_interfaces/BatteryState bat1_state
rapha_interfaces/BatteryState bat2_state

# The current power output in watts.
float64 power

# The energy consumed in watt-hours since the robot was powered on.
float64 energy
  • rapha_interfaces/msg/LedColor
Represents the color of an LED.
# The intensity of each color (255 = 100%).
uint8 red
uint8 green
uint8 blue
uint8 white
  • rapha_interfaces/msg/LedPanel
Enumeration of robot's LED panels.
uint8 FRONT=0
uint8 BACK=1
uint8 LEFT=2
uint8 RIGHT=3

uint8 data
  • rapha_interfaces/msg/LedState
Represents the state of a single LED.
# The duration (in ms) the state should be active.
# Setting it to 0 will make the state active indefinitely.
uint16 duration

# The priority of the state.
# If the value is equal to 0 or is lower than the priority of the current user LED, the state is ignored.
# The value of -1 resets the user state of the LED.
int8 priority

# The color of the LED
rapha_interfaces/LedColor color
  • rapha_interfaces/msg/LedPanelState
Represents the state of the whole LED panel.
# Which LED panel does this state applies to.
rapha_interfaces/LedPanel panel

# State of each LED on the panel.
# For panels with less than 36 LEDs, the last array items are ignored.
rapha_interfaces/LedState[36] state
  • rapha_interfaces/msg/LedStripState
Represents the state of the whole LED strip.
uint8 LED_STRIP_SIZE=129
rapha_interfaces/LedState[129] state
  • rapha_interfaces/msg/Led
Represents the position and the state of the LED.
# The panel the LED is on.
rapha_interfaces/LedPanel panel

# The id of the LED on the panel.
uint8 id

# The state of the LED.
rapha_interfaces/LedState state
  • rapha_interfaces/msg/MotorDiagnostics
Diagnostic information about motors controlled by RaphaCore.
# The order of the motors is:
# - rear left wheel
# - rear right wheel
# - right servo
# - left servo
# - front left wheel
# - front right wheel

std_msgs/Header header

# The current temperature in degrees Celsius.
uint8[6] temperature

# The current power output in watts.
float64[6] power

# The energy consumed in watt-hours since the robot was powered on.
float64[6] energy

uint8 FAULT_BIT_SENSOR_FAULT=1
uint8 FAULT_BIT_BUS_OVERCURRENT=2
uint8 FAULT_BIT_PHASE_OVERCURRENT=4
uint8 FAULT_BIT_STALL=8
uint8 FAULT_BIT_OVERHEAT=16

# The current fault mask reported by the motor.
uint8[6] fault_mask_active

# Mask of all fault that occurred since the robot was powered on.
uint8[6] fault_mask_occurred
  • rapha_interfaces/msg/ImuDiagnostics
Diagnostic information about IMU sensor running on RaphaCore.
std_msgs/Header header

# The current temperature of the sensor in degrees Celsius.
float64 temperature

# The current gyroscope biases.
float64 gyro_bias_x
float64 gyro_bias_y
float64 gyro_bias_z

Custom service types

  • rapha_interfaces/srv/SetSteeringMode
rapha_interfaces/SteeringMode steering_mode
---
bool success
string status_message
  • rapha_interfaces/srv/SetBatteryModes
rapha_interfaces/BatteryMode bat1_mode
rapha_interfaces/BatteryMode bat2_mode
---
bool success
string status_message
  • rapha_interfaces/srv/SetLeds
rapha_interfaces/Led[<=129] leds
---
bool success
string status_message