Skip to main content

Raph Rover ROS 2 API Reference

Subscribed topics​

  • controller/cmd_ackermann (ackermann_msgs/msg/AckermannDrive)

    Steers the robot when operating in the Ackermann steering mode.

  • controller/cmd_led_panel (raph_interfaces/msg/LedStripState)

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

  • controller/cmd_led_strip (raph_interfaces/msg/LedPanelState)

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

  • controller/cmd_turn_in_place (raph_interfaces/msg/TurnInPlaceDrive)

    Sets the target angular velocity when operating in the turn-in-place steering mode. [rad][rad]

  • controller/cmd_vel (geometry_msgs/msg/Twist)

    Steers the robot using Twist commands. More standardized way to control the robot. Useful for some navigation stacks. Not recommended for manual teleoperation. Only uses linear.x and angular.z components.

Published Topics​

Services​

Parameters​

controller​

  • drivetrain.ackermann_deceleration (type: float, default: 5.0)

    Deceleration to use when operating in ackermann mode. [ms2][\frac{m}{s^2}]

  • drivetrain.turn_in_place_deceleration (type: float, default: 8.0)

    Deceleration to use when operating in turn-in-place mode. [rads2][\frac{rad}{s^2}]

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

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

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

    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.cmd_vel_acceleration (type: float, default: 2.0)

    Acceleration to use when sending cmd_vel commands. [ms2,rads2][\frac{m}{s^2}, \frac{rad}{s^2}]

  • drivetrain.cmd_vel_steering_angle_velocity (type: float, default: 5.0)

    Steering angle velocity to use when sending cmd_vel commands. [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_speed (type: float, default: 2.0)

    Speed of servos during calibration. [rads][\frac{rad}{s}]

  • drivetrain.servo_calibration_timeout (type: float, default: 6.0)

    Timeout for servo calibration procedure. [s][s]

  • drivetrain.servo_calibration_torque_samples (type: int, default: 5)

    Number of consecutive servo torque readings over the threshold required during calibration.

  • drivetrain.servo_calibration_torque_threshold (type: float, default: 1.0)

    Minimal motor torque that indicates the servo presses against the bumper during calibration. [Nm][Nm]

  • 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.

  • power_manager.output_12v_enabled (type: bool, default: true)

    Whether the 12V output is enabled.

  • power_manager.output_5v_enabled (type: bool, default: true)

    Whether the 5V output is enabled.

  • power_manager.output_bat_enabled (type: bool, default: true)

    Whether the BAT output is enabled.

Custom message types​

  • raph_interfaces/msg/DrivetrainState
Represents the state of the drivetrain

# Current steering mode.
raph_interfaces/SteeringMode steering_mode

uint8 OPERATING_STATE_DISABLED=0
uint8 OPERATING_STATE_ENABLED=1
uint8 OPERATING_STATE_CALIBRATING_SERVOS=2
uint8 OPERATING_STATE_CHANGING_STEERING_MODE=3

# Current operating state.
uint8 operating_state

# Indicates if the servos are calibrated.
bool is_servos_calibrated
  • raph_interfaces/msg/SteeringMode
Represents the steering mode used by the drivetrain controller.
uint8 ACKERMANN=0
uint8 TURN_IN_PLACE=1

uint8 data
  • raph_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
  • raph_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.
raph_interfaces/BatteryMode target_mode

# The actual battery mode.
raph_interfaces/BatteryMode current_mode
  • raph_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.
raph_interfaces/BatteryState bat1_state
raph_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
  • raph_interfaces/msg/LedColor
Represents the color of an LED.
# The intensity of each color (255 = 100%).
uint8 red
uint8 green
uint8 blue
uint8 white
  • raph_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
raph_interfaces/LedColor color
  • raph_interfaces/msg/LedPanelState
Represents the state of the whole LED panel.
uint8 PANEL_FRONT=0
uint8 PANEL_REAR=1
uint8 PANEL_LEFT=2
uint8 PANEL_RIGHT=3

# Which LED panel does this state applies to.
uint8 panel

# State of each LED on the panel.
# The largest panel has 40 LEDs. If the length of the array is smaller than the number of LEDs on
# the panel, the remaining LEDs are not changed. If the length is greater than the number of LEDs
# on the panel, the extra states are ignored.
raph_interfaces/LedState[<=40] state
  • raph_interfaces/msg/LedStripState
Represents the state of the whole LED strip.
uint8 LED_STRIP_SIZE=143

raph_interfaces/LedState[143] state
  • raph_interfaces/msg/Led
Represents the position and the state of the LED.
uint8 PANEL_FRONT=0
uint8 PANEL_REAR=1
uint8 PANEL_LEFT=2
uint8 PANEL_RIGHT=3

# The panel the LED is on.
uint8 panel

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

# The state of the LED.
raph_interfaces/LedState state
  • raph_interfaces/msg/MotorDiagnostics
Diagnostic information about motors controlled by RaphCore.
# 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
  • raph_interfaces/msg/ImuDiagnostics
Diagnostic information about IMU sensor running on RaphCore.
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
  • raph_interfaces/msg/TurnInPlaceDrive
A command to turn the robot in place.

float64 angular_velocity
float64 acceleration

Custom service types​

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