m5p3nc3r 0174cb599f Manage sllidar_ros2 as a git subtree and apply QoS fix
- Add m5p3nc3r/sllidar_ros2 fork as a git subtree at lidar/sllidar_ros2/
- Dockerfile now COPYs source from the workspace instead of cloning at
  build time; git is no longer a build dependency
- Set /scan publisher QoS to BEST_EFFORT (depth 2) for Nav2/RViz2 compat
- Add lidar/README.md documenting the subtree workflow
- Remove lidar/sllidar_ros2/ from .gitignore (no longer needed)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-04-22 11:54:06 +00:00
2026-04-15 18:12:23 +01:00

raspbot_v2

ROS 2 package for the Yahboom Raspbot V2 platform — differential-drive motor control and pan/tilt camera orientation.


Architecture

Both nodes share the same I²C bus. The Linux kernel serialises individual transactions, so they can run as separate processes without additional locking.

Motor controller

                      ┌───────────────────────────────────┐
                      │      MotorControllerNode          │
                      │                                   │
 /cmd_vel  ──────────>│  Twist → differential kinematics  │
 (geometry_msgs/Twist)│  left  = linear  (angular × wb/2)│
                      │  right = linear + (angular × wb/2)│
                      │                                   │
 /wheel_speeds ──────>│  Direct per-wheel override        │
 (Float32MultiArray   │  [FL, FR, RL, RR]                 │
  4 × float32)        │                                   │
                      │         ▼                         │
                      │   raspbot_v2_interface            │
                      │   I²C bus 1, addr 0x2B            │
                      │         ▼                         │
                      │   /dev/i2c-1 ─────────> Motors    │
                      │                                   │
 /current_wheel_speeds│<─ telemetry @ 10 Hz               │
 (Float32MultiArray)  │   [FL, FR, RL, RR]                │
                      └───────────────────────────────────┘

Topics

Topic Direction Type Description
/cmd_vel Subscribed geometry_msgs/Twist Velocity command — linear.x (m/s) and angular.z (rad/s)
/wheel_speeds Subscribed std_msgs/Float32MultiArray Direct per-wheel speed override [FL, FR, RL, RR] in library units (0255)
/current_wheel_speeds Published std_msgs/Float32MultiArray Current wheel speeds read from hardware, published at 10 Hz

Parameters

Parameter Default Description
wheel_base 0.3 Distance between left and right wheels in metres
max_speed 1.0 Maximum motor speed in library units

Camera orientation controller

                         ┌──────────────────────────────────────┐
                         │      CameraOrientationNode           │
                         │                                      │
 /joint_command  ────────>│  JointState (names: pan, tilt)      │
 (sensor_msgs/           │  position in radians                 │
  JointState)            │                                      │
                         │  pan  → servo 1  (0°–180°)          │
                         │  tilt → servo 2  (0°–110°)          │
                         │                                      │
                         │         ▼                            │
                         │   raspbot_v2_interface               │
                         │   I²C bus 1, addr 0x2B               │
                         │         ▼                            │
                         │   /dev/i2c-1 ──────> Pan/tilt servos │
                         │                                      │
 /joint_states   <────────│  current angles @ 10 Hz             │
 (sensor_msgs/           │  position in radians                 │
  JointState)            │                                      │
                         └──────────────────────────────────────┘

Topics

Topic Direction Type Description
/joint_command Subscribed sensor_msgs/JointState Commanded pan/tilt angles. Joint names "pan" and "tilt", positions in radians. Unknown joint names are ignored.
/joint_states Published sensor_msgs/JointState Current angles reflected from the last command, published at 10 Hz

Parameters

Parameter Default Description
pan_servo_id 1 Raspbot servo channel for pan
tilt_servo_id 2 Raspbot servo channel for tilt
pan_min_deg 0.0 Pan lower limit (degrees)
pan_max_deg 180.0 Pan upper limit (degrees)
tilt_min_deg 0.0 Tilt lower limit (degrees)
tilt_max_deg 110.0 Tilt upper limit (degrees) — hardware cap
pan_center_deg 90.0 Startup and shutdown park position for pan
tilt_center_deg 60.0 Startup and shutdown park position for tilt
state_rate_hz 10.0 ~/joint_states publish rate

Hardware interface

The node drives the pan and tilt servos over I²C bus 1 (device address 0x2B). The same /dev/i2c-1 device used by the motor controller is sufficient — no additional device node is required.


Ultrasonic range sensor

                        ┌──────────────────────────────────────┐
                        │          UltrasonicNode              │
                        │                                      │
                        │  Sensor off when no subscribers      │
                        │  Sensor on  when subscribers > 0     │
                        │  1 s warm-up after power-on          │
                        │                                      │
                        │         ▼                            │
                        │   raspbot_v2_interface               │
                        │   I²C bus 1, addr 0x2B               │
                        │         ▼                            │
                        │   /dev/i2c-1 ──────> HC-SR04 sensor  │
                        │                                      │
 /ultrasonic/range <────│  Range @ configurable rate           │
 (sensor_msgs/Range)    │  radiation_type = ULTRASOUND         │
                        │  range in metres (REP-117)           │
                        └──────────────────────────────────────┘

Topics

Topic Direction Type Description
/ultrasonic/range Published sensor_msgs/Range Distance in metres. +inf when beyond max range, -inf when closer than min range (REP-117). Only published while subscribers are connected.

Parameters

Parameter Default Description
publish_rate_hz 10.0 Sensor poll and publish rate
frame_id 'ultrasonic' header.frame_id on published messages
min_range_m 0.02 Minimum valid range in metres
max_range_m 4.0 Maximum valid range in metres
field_of_view 0.2618 Sensor cone width in radians (~15°)
warmup_s 1.0 Seconds to wait after powering the sensor on before publishing

Verifying range readings

ros2 topic echo /ultrasonic/range

The sensor will activate automatically when this command runs and deactivate when it is stopped.


RPLIDAR A1

Runs in a separate container built from lidar/Dockerfile.

                        ┌──────────────────────────────────────┐
                        │  sllidar_ros2 (rplidar_node)         │
                        │                                      │
                        │  serial 115200 baud                  │
                        │  angle_compensate = true             │
                        │  scan_mode = Sensitivity             │
                        │         ▼                            │
                        │   /dev/ttyUSB0 ──────> RPLIDAR A1   │
                        │                                      │
 /scan          <───────│  LaserScan @ ~10 Hz                  │
 (sensor_msgs/          │  360° scan, range 0.1512 m          │
  LaserScan)            │                                      │
                        └──────────────────────────────────────┘

Topics

Topic Direction Type Description
/scan Published sensor_msgs/LaserScan 360° laser scan in the laser frame

Configuration

The LIDAR container is configured via environment variables in .env or docker-compose.yml. See the Launching section for details.

Verifying LIDAR data

ros2 topic echo /scan

Setting up the robot

1. Flash Raspberry Pi OS

Use the Raspberry Pi Imager to write Raspberry Pi OS (64-bit, Lite recommended) to a microSD card.

Before writing, open the imager's Advanced options (⚙) and configure:

Setting Value
Hostname raspbot-v2.local
SSH Enabled
Username / Password Your preferred credentials
Wi-Fi Your network SSID and password (if not using Ethernet)

Write the image, insert the card, and power on the Pi. Once it has booted and is reachable on the network (test with ping raspbot-v2.local), proceed to the next step.

2. Provision with Ansible

The ansible/ directory contains a playbook that handles the remaining setup (enabling SPI, installing Docker). See ansible/README.md for full instructions.


Building

Prerequisites

  • Docker (with BuildKit enabled)

  • For cross-compilation from an amd64 host, QEMU user-space emulation must be registered with the kernel. If you haven't done this before, run once:

    docker run --rm --privileged tonistiigi/binfmt --install arm64
    

Both images are defined in docker-compose.yml. Build them together:

docker compose build

Or build a single service:

docker compose build robot
docker compose build lidar

The builds are split into two stages each:

  1. builder — compiles the ROS package(s) with colcon; the lidar builder also clones sllidar_ros2 from GitHub
  2. runtime — copies only the install overlay into a clean ros:kilted-ros-core base; no build tools in the final image

Build images individually

# Robot controller
docker build --platform linux/arm64 -f robot/Dockerfile -t raspbot_v2:latest .

# LIDAR
docker build --platform linux/arm64 -f lidar/Dockerfile -t raspbot_v2_lidar:latest .

Deploying

Pipe both images directly to the target over SSH — no intermediate file or registry needed:

docker save raspbot_v2:latest raspbot_v2_lidar:latest \
  | ssh matt@raspbot-v2.local docker load

Then copy the compose file to the target:

scp docker-compose.yml matt@raspbot-v2.local:~/

Replace matt with the username configured in ansible/inventory.ini.


Launching

docker compose up

This starts both the robot controller and LIDAR containers. Logs from both are interleaved in the terminal, each line prefixed with the service name. To run in the background:

docker compose up -d
docker compose logs -f   # follow logs
docker compose down      # stop and remove containers

Environment variables

Create a .env file in the same directory as docker-compose.yml to override defaults:

ROS_DOMAIN_ID=0
LIDAR_PORT=/dev/ttyUSB0
LIDAR_FRAME_ID=laser
Variable Default Description
ROS_DOMAIN_ID 0 ROS 2 domain — must match on all nodes
LIDAR_PORT /dev/ttyUSB0 Host device node for the RPLIDAR
LIDAR_FRAME_ID laser frame_id in published LaserScan messages

Run containers individually

# Robot controller
docker run --rm \
  --network=host \
  --device /dev/i2c-1 \
  --env ROS_DOMAIN_ID=0 \
  raspbot_v2:latest

# LIDAR
docker run --rm \
  --network=host \
  --device /dev/ttyUSB0 \
  --env ROS_DOMAIN_ID=0 \
  raspbot_v2_lidar:latest

Overriding robot launch parameters

Launch arguments can be appended after the image name:

docker run --rm \
  --network=host \
  --device /dev/i2c-1 \
  --env ROS_DOMAIN_ID=0 \
  raspbot_v2:latest \
  ros2 launch raspbot_v2 robot.launch.py \
    wheel_base:=0.25 max_speed:=0.8 tilt_center_deg:=45.0

Available launch arguments:

Argument Default Description
wheel_base 0.3 Distance between left and right wheels (m)
max_speed 1.0 Maximum motor speed in library units
pan_center_deg 90.0 Pan angle at startup and shutdown (degrees)
tilt_center_deg 60.0 Tilt angle at startup and shutdown (degrees)
ultrasonic_rate_hz 10.0 Ultrasonic sensor publish rate (Hz)

LIDAR device permissions

The RPLIDAR connects as a USB serial device. If the user running Docker is not in the dialout group, add them and log back in:

sudo usermod -aG dialout $USER

Sending velocity commands from the host

With the container running, publish from another terminal (requires ROS 2 on the host or a second container on the same network):

# Drive forward at 0.2 m/s
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist \
  "{linear: {x: 0.02}, angular: {z: 0.0}}"

# Turn on the spot
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist \
  "{linear: {x: 0.0}, angular: {z: 0.5}}"

# Stop
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist \
  "{linear: {x: 0.0}, angular: {z: 0.0}}"

Commanding the camera from the host

Pan to centre (90°) and tilt to 30°:

ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
  "{name: ['pan', 'tilt'], position: [1.5708, 0.5236]}"

A single axis can be commanded by omitting the other joint name:

# Pan only
ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
  "{name: ['pan'], position: [0.0]}"

Verifying telemetry

# Wheel speeds
ros2 topic echo /current_wheel_speeds

# Camera orientation
ros2 topic echo /joint_states

Project layout

.
├── docker-compose.yml          # Launches robot and lidar containers together
├── docker-entrypoint.sh        # Sources ROS overlays before exec (shared by both images)
├── robot/
│   ├── Dockerfile              # Robot controller image (two-stage)
│   ├── src/
│   │   └── raspbot_v2/
│   │       ├── package.xml     # ROS package manifest
│   │       ├── setup.py        # ament_python build definition
│   │       ├── launch/
│   │       │   └── robot.launch.py           # Starts all robot nodes together
│   │       └── raspbot_v2/
│   │           ├── __init__.py
│   │           ├── motor_controller_node.py  # Differential-drive motor control
│   │           ├── camera_orientation_node.py # Pan/tilt servo control
│   │           └── ultrasonic_node.py        # HC-SR04 range sensor
│   └── raspbot_v2_interface/   # Vendored Yahboom hardware library
│       └── Raspbot_Lib/
│           └── Raspbot_Lib.py  # I²C driver (smbus, bus 1, addr 0x2B)
└── lidar/
    └── Dockerfile              # RPLIDAR A1 image (two-stage, clones sllidar_ros2)
S
Description
Ros2 nodes for Yahboom Raspbot v2
Readme 77 KiB
Languages
Python 94.8%
Dockerfile 5%
Shell 0.2%