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_servo_l, controller/cmd_servo_r (raph_interfaces/msg/ServoCommand)

    Direct commands for the left and right steering servos that bypass the higher-level Ackermann or turn-in-place interfaces.

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

  • controller/cmd_wheel_fl, controller/cmd_wheel_fr, controller/cmd_wheel_rl, controller/cmd_wheel_rr (raph_interfaces/msg/WheelCommand)

    Per-wheel commands for directly driving each wheel motor (front-left, front-right, rear-left, rear-right). Can be used for testing or custom control strategies.

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: 4.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.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.

  • imu_filter.gain_acc (type: float, default: 0.01)

    Gain for the accelerometer in the complementary filter for IMU data fusion (0.0-1.0, higher is more trust in the accelerometer).

  • imu_filter.bias_alpha (type: float, default: 0.01)

    The factor at which the gyroscope bias is updated when the IMU is determined to be in steady state (>=0.0, higher is faster bias compensation).

  • imu_filter.steady_state_angular_velocity_threshold (type: float, default: 0.05)

    Threshold for the angular velocity to determine whether the IMU is in steady state. [rads][\frac{rad}{s}]

  • imu_filter.steady_state_acceleration_threshold (type: float, default: 0.1)

    Threshold for the magnitude of the linear acceleration (after subtracting gravity) to determine whether the IMU is in steady state. [ms2][\frac{m}{s^2}]

  • imu_filter.steady_state_delta_angular_velocity_threshold (type: float, default: 0.01)

    Threshold for the change in angular velocity, between two consecutive measurements, to determine whether the IMU is in steady state. [rads][\frac{rad}{s}]

  • imu_filter.steady_state_required_steady_time (type: float, default: 1.0)

    How long should the IMU reading meet the steady thresholds before it's determined to be in steady state. [s][s]

  • imu_filter.orientation_variance (type: float, default: 0.001)

    Values on the diagonal of the orientation covariance matrix in the published IMU data.

oak​

  • device.mx_id (type: string, read-only, default: "")

    Device MX ID to connect to.

  • device.usb_port_id (type: string, read-only, default: "")

    USB port ID to connect to (e.g. 1.1.2).

  • device.ir_laser_dot_projector_intensity (type: float, default: 0.3)

    IR laser dot projector intensity (0.0-1.0, higher is stronger intensity).

  • device.ir_laser_dot_projector_lazy (type: bool, default: true)

    If true, the IR laser dot projector will only be turned on when the depth stream is active. If false, the IR laser dot projector will be always on.

  • device.ir_flood_light_intensity (type: float, default: 0.0)

    IR flood light intensity (0.0-1.0, higher is stronger intensity).

  • depth.confidence_threshold (type: int, default: 110)

    Depth images will only contain pixels where depth confidence is below the confidence threshold (lower the confidence value means better depth accuracy).

  • depth.lr_check_enabled (type: bool, default: true)

    Computes and combines disparities in both L-R and R-L directions.

  • depth.lr_check_threshold (type: int, default: 5)

    Disparity is considered for the output when the difference between LR and RL disparities is smaller than the LR check threshold.

  • depth.subpixel_enabled (type: bool, default: true)

    Computes disparity with sub-pixel interpolation.

  • depth.subpixel_fractional_bits (type: int, default: 3)

    Number of fractional bits for subpixel mode.

  • depth.min_distance (type: float, default: 0.0)

    Minimal distance in meters.

  • depth.max_distance (type: float, default: 10.0)

    Maximal distance in meters.

  • mono.width (type: int, read-only, default: 1280)

    Mono camera image width.

  • mono.height (type: int, read-only, default: 800)

    Mono camera image height.

  • mono.isp_scale_num (type: int, read-only, default: 1)

    ISP scale numerator for mono cameras.

  • mono.isp_scale_den (type: int, read-only, default: 1)

    ISP scale denominator for mono cameras.

  • mono.fps (type: float, read-only, default: 10.0)

    Mono camera frames per second.

  • mono_compressed.jpeg_quality (type: int, read-only, default: 80)

    JPEG quality for mono compressed images (0-100, higher is better quality and bigger size).

  • rgb.width (type: int, read-only, default: 1344)

    RGB camera image width.

  • rgb.height (type: int, read-only, default: 1008)

    RGB camera image height.

  • rgb.isp_scale_num (type: int, read-only, default: 1)

    ISP scale numerator for RGB camera.

  • rgb.isp_scale_den (type: int, read-only, default: 3)

    ISP scale denominator for RGB camera.

  • rgb.fps (type: float, read-only, default: 15.0)

    RGB camera frames per second.

  • rgb_compressed.jpeg_quality (type: int, read-only, default: 80)

    JPEG quality for RGB compressed images (0-100, higher is better quality and bigger size).