Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
99 changes: 99 additions & 0 deletions examples/9_turtlebot3/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
# Example - Turtlebot3 (Real)

![Static Badge](https://img.shields.io/badge/ROS2-Available-green)

This example demonstrates the use of a real TurtleBot3 Burger robot with ROS2.
The TurtleBot3 is a compact, customizable mobile robot designed for education and research. It supports applications such as SLAM, navigation, and autonomous control, and comes in various hardware configurations.


## Prerequisites

For this example, the TurtleBot3 Burger version with Ubuntu 22.04 and ROS2 Humble is used. Depending on your TurtleBot3 model and installed hardware (e.g., LDS-01 LiDAR), make sure to install the corresponding packages required for your specific configuration.

### Turtlebot3

For more details, please refer to the [TurtleBot3 Documentation](https://emanual.robotis.com/docs/en/platform/turtlebot3/overview/).

<img src="images/turtlebot3_image.png" width="300">

- **Specification**
- **OS** : Ubuntu 22.04
- **ROS** : ROS2 Humble
- **TurtleBot3 Model** : Burger
- **LiDAR** : LDS-01
- **Computer** : Raspberry Pi 3 Model B+ (1GB RAM)
- **Motor Controller** : OpenCR 1.0 (Firmware v0.2.1)

## Quick Start

### 1. Network Setup

Since the TurtleBot3 is controlled via ROS-MCP from the user PC, it is important to connect both the user PC and the TurtleBot3 to the same network.
> **Note:** You can check your network IP address with the `ifconfig` command.

**Ping Test**

After connecting them to the same network, perform a ping test from the user PC to TurtleBot3 to verify that the connection is established correctly:
**[User's PC]**
```bash
ping <TURTLEBOT3_IP> # e.g., ping 192.168.101.166
```

**ROS2 Network Setup**

In ROS2, environment variables are used to configure Domain ID and ROS middleware behavior.
On both the user PC and TurtleBot3, export:
**[User's PC]** **[Turtlebot3 SBC]**
```bash
echo "export ROS_DOMAIN_ID=30" >> ~/.bashrc
echo "export RMW_IMPLEMENTATION=rmw_fastrtps_cpp" >> ~/.bashrc
source ~/.bashrc
```

### 2. Bringup Turtlebot3

Open a new terminal on the user PC and connect to the Raspberry Pi via SSH using its IP address. Enter your Ubuntu OS password for the Raspberry Pi.

**[User's PC]**
```bash
ssh ubuntu@{IP_ADDRESS_OF_RASPBERRY_PI}
```

Bring up basic packages to start essential TurtleBot3 applications. You will need to specify your TurtleBot3 model.

**[Turtlebot3 SBC]**
```bash
export TURTLEBOT3_MODEL=burger
ros2 launch turtlebot3_bringup robot.launch.py
```

### 3. Launch Node on Your Turtlebot3 SBC and Open claude-desktop on Your PC

**[Turtlebot3 SBC]**
```bash
ros2 launch rosbridge_server rosbridge_websocket_launch.xml
```

**[User's PC]**
```bash
claude-desktop
```

## **Example Walkthrough**
You're now ready to interact with the TurtleBot3 via the ROS MCP server. Follow these examples step-by-step:

### **Example 1**: Connect to Robot

<img src="images/turtlebot3_connect.png" width="500">

### **Example 2**: Check Available Topics

<img src="images/turtlebot3_gettopics_1.png" width="500">
<img src="images/turtlebot3_gettopics_2.png" width="500">

### **Example 3**: Move the Robot Back and Forth
<img src="images/turtlebot3_example3.gif" width="500">


## **Next Steps**
If your TurtleBot3 is equipped with a Raspberry Pi camera, you can now start streaming visual data. Try integrating camera feeds into your pipeline for more advanced robot control demos.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
86 changes: 86 additions & 0 deletions examples/9_turtlebot3/ros2_mcp_turtlebot3.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
#!/usr/bin/env python3

"""
ROS2 Launch file for ROS-MCP Server with TurtleBot3
This launch file starts:
- rosbridge_websocket server
- TurtleBot3 robot
- Provides proper process management and cleanup
"""

import os

from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, LogInfo
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

from launch import LaunchDescription


def generate_launch_description():
"""Generate the launch description for ROS-MCP Server with TurtleBot3."""

# Declare launch arguments
rosbridge_port_arg = DeclareLaunchArgument(
"port", default_value="9090", description="Port for rosbridge websocket server"
)

rosbridge_address_arg = DeclareLaunchArgument(
"address",
default_value="",
description="Address for rosbridge websocket server (empty for all interfaces)",
)

# Rosbridge websocket server node
rosbridge_node = Node(
package="rosbridge_server",
executable="rosbridge_websocket",
name="rosbridge_websocket",
output="screen",
parameters=[
{
"port": LaunchConfiguration("port"),
"address": LaunchConfiguration("address"),
"use_compression": False,
"max_message_size": 10000000,
"send_action_goals_in_new_thread": True,
"call_services_in_new_thread": True,
}
],
arguments=["--ros-args", "--log-level", "info"],
)

# Include TurtleBot3 bringup launch file
turtlebot3_bringup_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
os.path.join(
FindPackageShare("turtlebot3_bringup").find("turtlebot3_bringup"),
"launch",
"robot.launch.py",
)
]
)
)

# Log info about what's being launched
log_info = LogInfo(
msg=[
"Starting ROS-MCP Server with:",
" - Rosbridge WebSocket on port: ",
LaunchConfiguration("port"),
" - TurtleBot3 robot bringup",
]
)

return LaunchDescription(
[
rosbridge_port_arg,
rosbridge_address_arg,
log_info,
rosbridge_node,
turtlebot3_bringup_launch,
]
)