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
9 changes: 5 additions & 4 deletions demos/turtlebot3_integration/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,13 @@ RUN apt-get update && apt-get install -y \
curl \
&& rm -rf /var/lib/apt/lists/*

# Create workspace and clone ros2_medkit
# TODO: Replace with proper ROS 2 package dependency once ros2_medkit is released
# Clone ros2_medkit from GitHub
WORKDIR ${COLCON_WS}/src
RUN git clone https://github.com/selfpatch/ros2_medkit.git
RUN git clone --depth 1 https://github.com/selfpatch/ros2_medkit.git && \
mv ros2_medkit/src/ros2_medkit_gateway . && \
rm -rf ros2_medkit

# Copy demo package
# Copy demo package from local context (this repo)
COPY package.xml CMakeLists.txt ${COLCON_WS}/src/turtlebot3_medkit_demo/
COPY config/ ${COLCON_WS}/src/turtlebot3_medkit_demo/config/
COPY launch/ ${COLCON_WS}/src/turtlebot3_medkit_demo/launch/
Expand Down
23 changes: 20 additions & 3 deletions demos/turtlebot3_integration/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,18 @@ curl -X POST http://localhost:8080/api/v1/topics/publish ...

## What You'll See

When TurtleBot3 simulation starts with Nav2, ros2_medkit will discover nodes such as:
When TurtleBot3 simulation starts with Nav2, ros2_medkit will discover nodes organized into **areas** based on their ROS 2 namespaces:

### Areas (Namespaces)

| Area | Namespace | Description |
|------|-----------|-------------|
| `root` | `/` | TurtleBot3, Nav2, and Gazebo nodes |
| `diagnostics` | `/diagnostics` | ros2_medkit gateway |

### Components

**Root** (`/`) - Main robot system:

- `turtlebot3_node` - Main robot interface
- `robot_state_publisher` - TF tree publisher
Expand All @@ -157,9 +168,15 @@ When TurtleBot3 simulation starts with Nav2, ros2_medkit will discover nodes suc
- `bt_navigator` - Behavior Tree Navigator
- `controller_server` - Path following controller
- `planner_server` - Global path planner
- Various sensor and lifecycle nodes
- `velocity_smoother` - Velocity command smoother
- Various lifecycle and manager nodes

**Diagnostics** (`/diagnostics`):

- `ros2_medkit_gateway` - REST API gateway

These appear as **components** in the ros2_medkit REST API, organized into **areas** based on their ROS 2 namespaces.
This demonstrates ros2_medkit's ability to discover ROS 2 nodes and organize them into areas.
For a more hierarchical demo with multiple areas, see the [ros2_medkit demo nodes](https://github.com/selfpatch/ros2_medkit/tree/main/src/ros2_medkit_gateway#demo-nodes) which use namespaces like `/powertrain`, `/chassis`, and `/body`.

## Architecture

Expand Down
29 changes: 19 additions & 10 deletions demos/turtlebot3_integration/config/medkit_params.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,20 @@
# ros2_medkit gateway configuration for TurtleBot3 demo
ros2_medkit_gateway:
ros__parameters:
server.host: "0.0.0.0"
server.port: 8080
refresh_interval_ms: 2000
cors.allowed_origins: ["*"]
cors.allowed_methods: ["GET", "PUT", "POST", "OPTIONS"]
cors.allowed_headers: ["Content-Type", "Accept"]
cors.allow_credentials: false
cors.max_age_seconds: 86400
# Node runs under /diagnostics namespace, so we need to match that here
diagnostics:
ros2_medkit_gateway:
ros__parameters:
server:
# Bind to all interfaces for Docker networking
host: "0.0.0.0"
port: 8080

refresh_interval_ms: 2000

cors:
allowed_origins: ["*"]
allowed_methods: ["GET", "PUT", "POST", "OPTIONS"]
allowed_headers: ["Content-Type", "Accept"]
allow_credentials: false
max_age_seconds: 86400

max_parallel_topic_samples: 10
106 changes: 47 additions & 59 deletions demos/turtlebot3_integration/config/nav2_params.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,22 @@
# Nav2 parameters for TurtleBot3 + ros2_medkit demo
# Based on default nav2_bringup parameters for TurtleBot3 burger

# Lifecycle manager configuration - exclude docking_server which we don't use
lifecycle_manager_navigation:
ros__parameters:
use_sim_time: True
autostart: True
node_names:
- controller_server
- smoother_server
- planner_server
- behavior_server
- bt_navigator
- waypoint_follower
- velocity_smoother
- collision_monitor
# Note: docking_server and route_server removed - not configured for this demo

amcl:
ros__parameters:
use_sim_time: True
Expand Down Expand Up @@ -60,65 +76,15 @@ bt_navigator:
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
navigate_through_poses:
plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_are_error_codes_active_condition_bt_node
- nav2_would_a_controller_recovery_help_condition_bt_node
- nav2_would_a_planner_recovery_help_condition_bt_node
- nav2_would_a_smoother_recovery_help_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
# Note: plugin_lib_names is no longer needed in Jazzy - plugins are auto-loaded

controller_server:
ros__parameters:
use_sim_time: True
enable_stamped_cmd_vel: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
Expand Down Expand Up @@ -281,22 +247,23 @@ smoother_server:

behavior_server:
ros__parameters:
enable_stamped_cmd_vel: True
local_costmap_topic: local_costmap/costmap_raw
global_costmap_topic: global_costmap/costmap_raw
local_footprint_topic: local_costmap/published_footprint
global_footprint_topic: global_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
plugin: "nav2_behaviors/Spin"
plugin: "nav2_behaviors::Spin"
backup:
plugin: "nav2_behaviors/BackUp"
plugin: "nav2_behaviors::BackUp"
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
plugin: "nav2_behaviors::DriveOnHeading"
wait:
plugin: "nav2_behaviors/Wait"
plugin: "nav2_behaviors::Wait"
assisted_teleop:
plugin: "nav2_behaviors/AssistedTeleop"
plugin: "nav2_behaviors::AssistedTeleop"
local_frame: odom
global_frame: map
robot_base_frame: base_link
Expand All @@ -322,6 +289,7 @@ waypoint_follower:
velocity_smoother:
ros__parameters:
use_sim_time: True
enable_stamped_cmd_vel: True
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
Expand All @@ -337,6 +305,7 @@ velocity_smoother:
collision_monitor:
ros__parameters:
use_sim_time: True
enable_stamped_cmd_vel: True
base_frame_id: "base_link"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
Expand All @@ -363,3 +332,22 @@ collision_monitor:
min_height: 0.15
max_height: 2.0
enabled: True

# Docking server - minimal config to satisfy lifecycle manager
# We don't actually use docking in this demo
docking_server:
ros__parameters:
use_sim_time: True
enable_stamped_cmd_vel: True
dock_plugins: ["simple_charging_dock"]
simple_charging_dock:
plugin: "opennav_docking::SimpleChargingDock"
use_external_detection_pose: false
docking_threshold: 0.02
staging_x_offset: -0.5
staging_yaw_offset: 0.0

# Route server - minimal config
route_server:
ros__parameters:
use_sim_time: True
2 changes: 0 additions & 2 deletions demos/turtlebot3_integration/docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,6 @@ services:
ros2 launch turtlebot3_medkit_demo demo.launch.py"

sovd-web-ui:
# TODO: Replace with Docker Hub image once sovd_web_ui is published
# For now, we clone and build from GitHub
build:
context: https://github.com/selfpatch/sovd_web_ui.git
dockerfile: Dockerfile
Expand Down
116 changes: 65 additions & 51 deletions demos/turtlebot3_integration/launch/demo.launch.py
Original file line number Diff line number Diff line change
@@ -1,70 +1,84 @@
"""Launch TurtleBot3 simulation with Nav2 and ros2_medkit gateway for discovery demo."""
"""Launch TurtleBot3 simulation with Nav2 and ros2_medkit gateway for discovery demo.

This launch file demonstrates ros2_medkit's hierarchical discovery by:
- Running TurtleBot3 + Nav2 (in root namespace)
- Adding ros2_medkit gateway under /diagnostics namespace
- Showing how nodes are organized into Areas based on namespaces
"""

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
SetEnvironmentVariable,
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
# Get package directories
turtlebot3_gazebo_dir = get_package_share_directory('turtlebot3_gazebo')
nav2_bringup_dir = get_package_share_directory('nav2_bringup')
demo_pkg_dir = get_package_share_directory('turtlebot3_medkit_demo')
turtlebot3_gazebo_dir = get_package_share_directory("turtlebot3_gazebo")
nav2_bringup_dir = get_package_share_directory("nav2_bringup")
demo_pkg_dir = get_package_share_directory("turtlebot3_medkit_demo")

# Path to config files from installed package
medkit_params_file = os.path.join(demo_pkg_dir, 'config', 'medkit_params.yaml')
nav2_params_file = os.path.join(demo_pkg_dir, 'config', 'nav2_params.yaml')
map_file = os.path.join(demo_pkg_dir, 'config', 'turtlebot3_world.yaml')
medkit_params_file = os.path.join(demo_pkg_dir, "config", "medkit_params.yaml")
nav2_params_file = os.path.join(demo_pkg_dir, "config", "nav2_params.yaml")
map_file = os.path.join(demo_pkg_dir, "config", "turtlebot3_world.yaml")

# Launch configuration variables
use_sim_time = LaunchConfiguration('use_sim_time', default='True')

return LaunchDescription([
# Declare launch arguments
DeclareLaunchArgument(
'use_sim_time',
default_value='True',
description='Use simulation (Gazebo) clock if true'
),
use_sim_time = LaunchConfiguration("use_sim_time", default="True")

# Set TurtleBot3 model (can be overridden by environment variable)
SetEnvironmentVariable(
name='TURTLEBOT3_MODEL',
value=os.environ.get('TURTLEBOT3_MODEL', 'burger')
),

# Launch TurtleBot3 Gazebo simulation (turtlebot3_world)
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(turtlebot3_gazebo_dir, 'launch', 'turtlebot3_world.launch.py')
return LaunchDescription(
[
# Declare launch arguments
DeclareLaunchArgument(
"use_sim_time",
default_value="True",
description="Use simulation (Gazebo) clock if true",
),
launch_arguments={'use_sim_time': use_sim_time}.items()
),

# Launch Nav2 navigation stack
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(nav2_bringup_dir, 'launch', 'bringup_launch.py')
# Set TurtleBot3 model (can be overridden by environment variable)
SetEnvironmentVariable(
name="TURTLEBOT3_MODEL",
value=os.environ.get("TURTLEBOT3_MODEL", "burger"),
),
launch_arguments={
'map': map_file,
'params_file': nav2_params_file,
'use_sim_time': use_sim_time,
'autostart': 'True',
}.items()
),

# Launch ros2_medkit gateway
Node(
package='ros2_medkit_gateway',
executable='gateway_node',
name='ros2_medkit_gateway',
output='screen',
parameters=[medkit_params_file, {'use_sim_time': use_sim_time}],
),
])
# Launch TurtleBot3 Gazebo simulation (turtlebot3_world)
# Runs in root namespace to publish standard topics (/scan, /odom, /cmd_vel)
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(
turtlebot3_gazebo_dir, "launch", "turtlebot3_world.launch.py"
)
),
launch_arguments={"use_sim_time": use_sim_time}.items(),
),
# Launch Nav2 navigation stack
# Runs in root namespace to subscribe to robot topics
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(nav2_bringup_dir, "launch", "bringup_launch.py")
),
launch_arguments={
"map": map_file,
"params_file": nav2_params_file,
"use_sim_time": use_sim_time,
"autostart": "True",
}.items(),
),
# Launch ros2_medkit gateway under /diagnostics namespace
# This demonstrates namespace-based Area organization in discovery
Node(
package="ros2_medkit_gateway",
executable="gateway_node",
name="ros2_medkit_gateway",
namespace="diagnostics",
output="screen",
parameters=[medkit_params_file, {"use_sim_time": use_sim_time}],
),
]
)
Loading