TurtleBot 4 Robot

Source code is available here.

Installation

The turtlebot4_robot metapackage is pre-installed on the TurtleBot 4 Raspberry Pi image.

Source installation

To manually install this metapackage from source, clone the git repository:

  • Clone the repository into your workspace:

    cd ~/turtlebot4_ws/src
    git clone https://github.com/turtlebot/turtlebot4_robot.git -b galactic
    

    Install dependencies:

    cd ~/turtlebot4_ws
    rosdep install --from-path src -yi
    

    Build the packages:

    source /opt/ros/galactic/setup.bash
    colcon build --symlink-install
    
  • Clone the repository into your workspace:

    cd ~/turtlebot4_ws/src
    git clone https://github.com/turtlebot/turtlebot4_robot.git  -b humble
    

    Install dependencies:

    cd ~/turtlebot4_ws
    rosdep install --from-path src -yi
    

    Build the packages:

    source /opt/ros/humble/setup.bash
    colcon build --symlink-install
    

Base

The turtlebot4_base package contains the source code for the rclcpp node turtlebot4_base_node which runs on the physical robot. This node interfaces with the GPIO lines of the Raspberry Pi which allows it to read the state of the buttons, as well as write to the LEDs and display.

Note

This node is only used on the standard TurtleBot 4 model.

Publishers:

Topic Message Type Description
hmi/buttons turtlebot4_msgs/msg/UserButton Button states of the TurtleBot 4 HMI

Subscribers:

Topic Message Type Description
hmi/display turtlebot4_msgs/msg/UserDisplay The current information that is to be displayed
hmi/led/_[led] std_msgs/msg/Int32 Hidden topics indicating the state of each LED

GPIO Interface

The TurtleBot 4 uses libgpiod to interface with the GPIO lines of the Raspberry Pi. The gpiochip0 device represents the 40-pin header of the Raspberry Pi and is used for reading and writing to these pins.

I2C Interface

The linux I2C drivers are used to read and write data on the I2C buses of the Raspberry Pi. The display's SSD1306 driver is connected to the i2c-3 device by default, but other buses are available too.

SSD1306

The SSD1306 is a driver for OLED displays. It receives commands over a communication bus (I2C for the TurtleBot 4) and controls how the physical display behaves. The TurtleBot 4 uses a modified version of this STM32 SSD1306 driver to write pixels, shapes and characters to the display.

Configuration

Warning

Do NOT change pin definitions if you are using the standard PCBA or do not know what you are doing.

The turtlebot4_base_node pin definitions can be set with ROS parameters. The default configuration is:

turtlebot4_base_node:
  ros__parameters:
    # GPIO definition for HMI. Do NOT change if you are using the standard PCBA.
    gpio:
      user_button_1: 13
      user_button_2: 19
      user_button_3: 16
      user_button_4: 26

      led_green_power: 17
      led_green_motors: 18
      led_green_comms: 27
      led_green_wifi: 24
      led_green_battery: 22
      led_red_battery: 23
      led_green_user_1: 25
      led_green_user_2: 6
      led_red_user_2: 12

      display_reset: 2
Note

The value for each GPIO device is the GPIO number, NOT the pin number.

Bringup

The turtlebot4_bringup package contains the launch and configuration files to run the robots software.

Launch files:

  • Joy Teleop: Launches nodes to enable the bluetooth controller.
  • OAKD: Launches the OAK-D nodes.
  • RPLIDAR: Launches the RPLIDAR node.
  • Robot: Launches the TurtleBot 4 nodes.
  • Lite: Launches all necessary nodes for the TurtleBot 4 Lite.
  • Standard: Launches all necessary nodes for the TurtleBot 4.

Config files:

Robot Upstart

The robot uses the robot_upstart package to install the bringup launch files as a background service that launches when the robot starts. The launch files are located under the turtlebot4_bringup package.

  • Robot upstart commands:

    Command Bash Description
    Stop sudo systemctl stop turtlebot4 Kill all nodes launched by the service.
    The service will start again on reboot if it is not uninstalled.
    Start sudo systemctl start turtlebot4 Launch all nodes if the service is inactive
    Restart sudo systemctl restart turtlebot4 Kill all nodes launched by the service, then launch again
    Install install.py model [ROS_DOMAIN_ID] (v0.1.2)
    install.py model --domain [ROS_DOMAIN_ID] (v0.1.3)
    Install the service. Optionally, set the ROS_DOMAIN_ID.
    Uninstall uninstall.py Uninstall the service. The nodes will no longer be launched on boot.
    Status sudo systemctl status turtlebot4 View the current status of the service, and recent logs.
    View Logs sudo journalctl -u turtlebot4 -r View the latest logs from the service.
  • Use the TurtleBot 4 setup tool to manage robot_upstart:

    turtlebot4-setup
    

    Navigate to ‘ROS Setup', then ‘Robot Upstart'. Use the various menu options to start, stop, uninstall, or reinstall the upstart job.

    robot_upstart
    Manage robot_upstart with the TurtleBot 4 setup tool

    The setup tool will automatically reinstall the robot_upstart job when certain settings are changed.

Diagnostics

The turtlebot4_diagnostics packages contains the source code and launch files for the TurtleBot 4 diagnostics updater.

Launch files:

  • Diagnostics: Launches the turtlebot4 diagnostics updater and the diagnostic aggregator node.

Diagnostics Updater

The diagnostics updater is a Python3 node that runs on the robot. It subscribes to diagnostic topics and records statistics specific to each topic. The diagnostic data is viewable with rqt_robot_monitor.

  • Diagnostic topics:

    Topic Message Type Description
    battery_state sensor_msgs/msg/BatteryState Battery voltage and percentage
    color/preview/image sensor_msgs/msg/Image OAK-D color camera data
    dock irobot_create_msgs/msg/Dock Dock status
    hazard_detection irobot_create_msgs/msg/HazardDetectionVector Create® 3 Hazards
    imu sensor_msgs/msg/Imu IMU data
    mouse irobot_create_msgs/msg/Mouse Mouse sensor data
    scan sensor_msgs/msg/LaserScan RPLIDAR laser scan data
    wheel_status irobot_create_msgs/msg/WheelStatus Wheels enabled status
  • Diagnostic topics:

    Topic Message Type Description
    battery_state sensor_msgs/msg/BatteryState Battery voltage and percentage
    color/preview/image sensor_msgs/msg/Image OAK-D color camera data
    dock irobot_create_msgs/msg/DockStatus Dock status
    hazard_detection irobot_create_msgs/msg/HazardDetectionVector Create® 3 Hazards
    imu sensor_msgs/msg/Imu IMU data
    mouse irobot_create_msgs/msg/Mouse Mouse sensor data
    scan sensor_msgs/msg/LaserScan RPLIDAR laser scan data
    wheel_status irobot_create_msgs/msg/WheelStatus Wheels enabled status

Viewing diagnostics:

ros2 launch turtlebot4_viz view_diagnostics.launch.py
rqt_robot_monitor
Diagnostics data captured with rqt_robot_monitor

Tests

The turtlebot4_tests packages contains the source code for the TurtleBot 4 system test scripts. These scripts test basic functionality of the robot and are useful for troubleshooting issues.

ROS Tests

The ROS tests use ROS topics and actions to test various system functionality. Test results are saved to ~/turtlebot4_test_results/Y_m_d-H_M_S where Y_m_d-H_M_S is the date and time of the test. A rosbag is also recorded for the duration of the test and saved to the same location.

Currently supported tests:

  • Light Ring: Test the Create® 3 light ring
  • Create® 3 Button: Test the Create® 3 buttons
  • User LED: Test the HMI LEDs (TurtleBot 4 model only)
  • User Button: Test the HMI buttons (TurtleBot 4 model only)
  • Display: Test the HMI display (TurtleBot 4 model only)
  • Dock: Test the robots ability to undock and dock.

Running the tests:

ros2 run turtlebot4_tests ros_tests

This will launch a CLI menu where the different tests can be run.

Enter the index of the test and hit enter to start the test. Some tests will run automatically while others require user input.

ROS tests
Running the Light Ring test