These docs are public and open source.Edit on GitHub
API REFERENCE / ROS 2
ROS 2 TOPICS.
The whole stack is sensors publishing and actuators subscribing. You read four sensor topics, you publish one drive topic, and the nodes in between do the arbitration and scaling. Below is the exact list the default launch brings up, with the message type on each.
Publish /driveRead /scan · /imu · /cameraackermann_msgs
THE FULL LIST
THE TOPIC LIST.
| Topic | Message type | Your role | What it carries |
|---|---|---|---|
| /scan | sensor_msgs/LaserScan | Read it | One planar sweep from the Lakibeam LiDAR over UDP, frame_id lidar_link. The depth source for wall follow, gap follow, and mapping. |
| /imu | sensor_msgs/Imu | Read it | Linear acceleration (m/s²) and angular velocity (rad/s), frame_id imu_link. Published by the controller node from the QMI8658A on the OSCORE board. |
| /mag | sensor_msgs/MagneticField | Read it | The magnetometer vector in teslas, frame_id imu_link. A rough compass, on the physical car only. |
| /odom | nav_msgs/Odometry | Read it | Wheel odometry integrated by the controller node from the encoder counts on the ESP32. Useful for short-horizon dead reckoning between LiDAR scans. |
| /camera | sensor_msgs/Image | Read it | A JPEG-compressed colour frame from the camera node (USB webcam in MJPG). The bytes are raw JPEG with encoding="jpeg", decode with cv2.imdecode before display. |
| /camera/decoded | sensor_msgs/Image | Optional | A plain RViz-friendly image, published only when the decode_camera node is enabled in the launch file. |
| /drive | ackermann_msgs/AckermannDriveStamped | Publish it | The autonomy channel. This is the one topic your own node writes to. The mux only forwards it while autonomy mode is armed. |
| /joy | sensor_msgs/Joy | Teleop | Flysky RC stick and switch state, published by the controller node from the receiver on the ESP32. The gamepad and mux nodes read it; you rarely need to. |
| /gamepad_drive | ackermann_msgs/AckermannDriveStamped | Teleop | The drive command gamepad_node builds from the sticks. Gated by the mux the same way /drive is. |
| /mux_out | ackermann_msgs/AckermannDriveStamped | Internal | Whichever command won arbitration, teleop or autonomy. You read this to see what the car was actually told. |
| /motor | ackermann_msgs/AckermannDriveStamped | Internal | The throttle-scaled command the controller node turns into the ESP32 serial command. The last hop before hardware. |
| /led_matrix/command | std_msgs/String | Publish it | Write text or simple commands to the 8x8 dot-matrix display on the back of the car. Handled by the led_matrix node over USB-UART. |
THE DRIVE PIPELINE
THE DRIVE PIPELINE.
Your message does not go straight to the motor. It passes through an arbiter that decides whether or autonomy is in control, then a throttle stage that scales speed down to a safe range before the node ever touches the hardware. That is why a raw set_speed_angle(1.0, 0) does not launch the car at full speed.
// the drive pipeline
/drive(yours)→mux_node→/mux_out→throttle_node→/motor→controller→ESP32 → ESC + steering servo
/gamepad_drive(teleop)→mux_node joins the same arbiter. LB arms teleop, RB arms autonomy.
//Reading and writing from your own node
pythonimport rclpy from rclpy.node import Node from sensor_msgs.msg import LaserScan from ackermann_msgs.msg import AckermannDriveStamped class GapFollower(Node): def __init__(self): super().__init__("gap_follower") # Read the LiDAR. self.create_subscription(LaserScan, "/scan", self.on_scan, 10) # Publish to the autonomy channel. The mux forwards it when RB is held. self.drive = self.create_publisher(AckermannDriveStamped, "/drive", 10) def on_scan(self, scan): msg = AckermannDriveStamped() msg.drive.speed = 0.25 msg.drive.steering_angle = 0.0 self.drive.publish(msg) def main(): rclpy.init() rclpy.spin(GapFollower()) if __name__ == "__main__": main()
