TurtleBot3 Home Service Challenge (ROS 2 Humble)
Overview
The TurtleBot3 Home Service Challenge simulates real-world robotics tasks involving navigation, manipulation, and interaction with objects. Designed to test autonomous task completion, the challenge utilizes the TurtleBot3 with the OpenMANIPULATOR-X arm, operating in a Gazebo-based virtual environment or on actual hardware.
Prerequisites
Before running the challenge:
- ROS 2 Humble must be installed.
- Complete TurtleBot3 setup on both the Remote PC and SBC.
- Install TB3&OpenMANIPULATOR-Xpackages.
Installation (Remote PC)
cd ~/turtlebot3_ws/src/
git clone -b humble https://github.com/ROBOTIS-GIT/turtlebot3_home_service_challenge.git
cd ~/turtlebot3_ws && colcon build --symlink-install
Gazebo Simulation
Launch Environment
Launch Navigation in RViz
Launch Core Node (Scenario Control)
The core node manages: - ArUco marker detection - Parking logic - Manipulator control
Real Robot Operation
Bringup Hardware
Launch Camera Node
Launch Navigation with Custom Map
ros2 launch turtlebot3_home_service_challenge_tools navigation2.launch.py map_yaml_file:=$HOME/map.yaml
Run Core Node with Parameters
ros2 launch turtlebot3_home_service_challenge_core core_node.launch.py launch_mode:='actual' marker_size:=0.04
Mission Execution
Individual Actions
- Park in front of marker (IDs 0–7):
- Control Manipulator:
ros2 topic pub -1 /manipulator_control std_msgs/msg/String "{data: 'pick_target'}"
ros2 topic pub -1 /manipulator_control std_msgs/msg/String "{data: 'place_target'}"
Run Full Scenario
Configuration
- Scenario YAML File
Defines marker IDs, goals, and return poses:
scenario:
  room1:
    target_marker_id: 0
    goal_pose: [0.9, 0.5, 0.0, 0.0, 0.0, 0.7071, 0.7071]
    goal_marker_id: 4
    end_pose: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]
- Manipulator Pose File (srdf)
<group_state name="target" group="arm">
  <joint name="joint1" value="0"/>
  <joint name="joint2" value="0.9076"/>
  <joint name="joint3" value="-0.9425"/>
  <joint name="joint4" value="0.0873"/>
</group_state>
Mission Workflow Summary
- Approach object using AR marker.
- Pick object with manipulator.
- Navigate to placement location.
- Place object using gripper.
- Return to home base.