Launch System
Overview
PLEM uses an RT (Real-Time) thread separation architecture.
- RT Driver - RT threads within a single process (EtherCAT 1kHz, Controller, IPC Bridge)
- ROS2 Nodes - Multiple independent nodes running composably (ros2_control, MoveIt, bridge, etc.)
Communication between RT threads and ROS2 nodes occurs through POSIX shared memory.
Launch file location: All launch files are located in the plem_bringup/launch/ directory and are designed with a modular (composable) structure, enabling individual execution and combination.
Composable Launch Structure
| Launch File | Role | Dependencies |
|---|---|---|
plem_launch.py | Main integrated launch - Automatic combination of all components | Includes all sub-launches |
rt_driver.launch.py | RT driver (built-in/user shared) | None (can run independently) |
ros2_control.launch.py | ROS2 Control stack (hardware interface + controllers) | Requires RT driver |
moveit.launch.py | MoveIt motion planner | Requires ROS2 Control |
moveit_only_launch.py | Single robot MoveIt + ROS2 Control (namespace isolation) | Requires RT driver |
multi_robot.launch.py | N robots simultaneous execution (each with independent namespace) | Requires RT driver |
Design principles:
- Each launch file can run independently (when dependencies are met)
plem_launch.pycombines sub-launches usingIncludeLaunchDescription- Individual components can be restarted during development
System Execution
Full System Execution
# Production launch (RT driver + ROS2 stack + Python bridge auto-start)
ros2 launch plem_bringup plem_launch.py
# Specify robot ID (namespace isolation)
ros2 launch plem_bringup plem_launch.py robot_id:=indy
# Enable recording
ros2 launch plem_bringup plem_launch.py record:=true
# Use external description package
ros2 launch plem_bringup plem_launch.py description_package:=ur_description
# Select built-in robot type (when using wim_description)
ros2 launch plem_bringup plem_launch.py robot_type:=indy7
Key Launch Arguments
| Argument | Type | Default | Description |
|---|---|---|---|
robot_id | string | indy | Robot instance ID (ROS2 namespace, IPC prefix) |
description_package | string | wim_description | Robot URDF/xacro package name |
robot_type | string | indy7_v2 | Built-in robot type (only when wim_description) |
eth_interface | string | eth0 | EtherCAT network interface |
master_index | int | 0 | EtherCAT master index (0=eth0, 1=eth1, etc.) |
record | bool | true | Enable rosbag2 recording |
bag_dir | string | ~/bags/rt_monitoring | rosbag2 save directory |
retention_minutes | int | 60 | bag file retention period (minutes) |
disk_threshold | int | 70 | Disk cleanup threshold (%) |
urdf_file | string | '' | URDF path override (for external packages) |
srdf_file | string | '' | SRDF path override (for external packages) |
robot_name | string | '' | Robot name override (for external packages) |
Packages must follow convention-based structure (details: Description Protocol Reference). config/, urdf/, meshes/ directory structure is required, with automatic validation and fallback support.
Individual Component Execution (Development)
# Terminal 1: RT driver only (built-in driver)
ros2 launch plem_bringup rt_driver.launch.py
# Terminal 1: RT driver only (custom driver)
ros2 launch plem_bringup rt_driver.launch.py rt_package:=my_robot rt_executable:=my_robot_node
# Terminal 2: ROS2 Control only (after 2 second wait)
ros2 launch plem_bringup ros2_control.launch.py
# Terminal 3: MoveIt only (after additional 4 second wait)
ros2 launch plem_bringup moveit.launch.py
Additional arguments for rt_driver.launch.py:
| Argument | Default | Description |
|---|---|---|
rt_package | bootstrap | Package containing RT driver executable |
rt_executable | bootstrap_node | Executable name |
robot_id | indy | Robot ID for IPC namespace |
eth_interface | eth0 | EtherCAT network interface |
master_index | 0 | EtherCAT master index |
Advanced parameters like rt_priority (default 98), cycle_time_us (default 1000) are also supported. Check the complete list with ros2 launch plem_bringup rt_driver.launch.py --show-args.
Important:
- The RT driver creates shared memory, so it must be started first.
plem_launch.pyis a composable launch that automatically executes the above components sequentially.- Python bridge (
plem_ai_server) is integrated intoplem_launch.pyand starts automatically.
Multi-Robot Execution
PLEM controls multiple robots simultaneously through namespace isolation.
Multi-robot integrated launch:
# Default configuration
ros2 launch plem_bringup multi_robot.launch.py
# Specify custom interfaces
ros2 launch plem_bringup multi_robot.launch.py \
interface_a:=eth0 interface_b:=eth1
Single robot MoveIt launch (namespace isolation):
# Place all nodes in /{name}/ namespace with name parameter
ros2 launch plem_bringup moveit_only_launch.py name:=arm_left
plem_launch.py: Usesrobot_idparametermoveit_only_launch.py: Usesnameparametermulti_robot.launch.py: Usesrobotsparameter (comma-separated)
Namespace structure:
| Resource | Single Robot | Multi-Robot (arm_left) |
|---|---|---|
| Topic | /indy/joint_states | /arm_left/joint_states |
| Action | /indy/wim_rt_driver/set_mode | /arm_left/wim_rt_driver/set_mode |
| IPC | /indy_joint_actual_values | /arm_left_joint_actual_values |
Python Bridge (plem_ai_server)
plem_ai_server is a Python bridge that communicates with external applications (Android apps, etc.) via WebSocket/UDP.
Key features:
- Stream robot status and receive commands via WebSocket
- Automatic robot discovery via UDP
- Automatic brake lock on connection loss (safety feature)
- Error reset with
RESET_ERRORWebSocket message - Namespace configuration via
PLEM_ROBOT_IDenvironment variable (automatically passed fromplem_launch.pywithrobot_idargument)
Integrated in plem_launch.py: The bridge starts automatically from the main launch without a separate launch file.
RT Driver
Role
- EtherCAT communication (1kHz)
- Torque calculation (PID + dynamics)
- Safety monitoring
- Shared memory owner (creation and writing)
Execution Method
| Scenario | RT Driver | Execution Method |
|---|---|---|
| Supported robot (Description Package only) | PLEM built-in RT driver | ros2 launch plem_bringup plem_launch.py or scaffold bringup.launch.py |
| New manufacturer robot (C++ Extension) | User application created with create_robot | ros2 launch <package_name> bringup.launch.py (details: Robot Integration) |
Status Check
# Check RT driver alive (1kHz topic publishing)
ros2 topic hz /rt_raw
# Monitor loop jitter
ros2 topic echo /rt_raw --field loop_jitter_us
ROS2 Nodes
Main Nodes
| Node | Role | Launch File | Package | Location |
|---|---|---|---|---|
| (RT Driver) | RT EtherCAT driver (1kHz) | rt_driver.launch.py or user application | - | - |
| ros2_control_node | Hardware interface, controller management | ros2_control.launch.py | controller_manager | ROS2 Control standard |
| robot_state_publisher | URDF-based TF publishing (500Hz) | ros2_control.launch.py | robot_state_publisher | ROS2 standard |
| joint_trajectory_controller | Trajectory execution action server (500Hz) | ros2_control.launch.py | joint_trajectory_controller | ROS2 Control standard |
| mode_control_action_server | Mode control action server | ros2_control.launch.py | PLEM runtime | Auto-start |
| rt_monitoring_publisher | RT metrics ROS2 publishing (10Hz) | ros2_control.launch.py | PLEM runtime | Auto-start |
| move_group | MoveIt motion planning | moveit.launch.py | MoveIt2 standard | Auto-start |
| plan_trajectory_action_server | Motion planning action server | moveit.launch.py | PLEM runtime | Auto-start |
| plem_ai_server | Python WebSocket/UDP bridge | plem_launch.py | PLEM runtime | Auto-start |
All launch files are located in the plem_bringup/launch/ directory.
Check Running Nodes
# List all ROS2 nodes
ros2 node list
# Controller status
ros2 control list_controllers
# Hardware interface status
ros2 control list_hardware_interfaces
IPC Communication
The RT driver and ROS2 processes communicate via POSIX shared memory. Users do not need to handle IPC channels directly; data is accessed through ROS2 topics (/joint_states, /rt_raw).
When robot_id is set, a prefix is automatically applied to IPC paths.
Shared Memory Cleanup (Troubleshooting)
# Check shared memory regions (prefix varies by robot_id)
ls -lh /dev/shm/*joint_actual_values /dev/shm/*joint_target_values /dev/shm/*control_* 2>/dev/null
# Clean shared memory (after RT driver shutdown)
# Default (robot_id=indy): /dev/shm/indy_joint_actual_values, etc.
sudo rm -f /dev/shm/indy_* /dev/shm/joint_* 2>/dev/null
ROS2 Topics
Monitoring Topics
| Topic | Rate | Content |
|---|---|---|
/joint_states | 500Hz | Joint position, velocity, effort |
/rt_raw | 1kHz | RT loop jitter, execution time, timing metrics |
/rt_events | Event | Mode changes, faults, state transitions |
/rt_monitor_stats | 10Hz | Queue statistics, overflow counts |
/tf | 500Hz | Robot kinematics tree |
All topics have a /{robot_id}/ namespace prefix applied. Example: /{robot_id}/joint_states, /{robot_id}/rt_raw.
Topic Monitoring
# Joint states
ros2 topic echo /joint_states
# RT jitter
ros2 topic echo /rt_raw --field loop_jitter_us
# Mode change events
ros2 topic echo /rt_events
# Check topic frequency
ros2 topic hz /joint_states
System Shutdown
Emergency Shutdown
In emergency situations during robot operation, follow this procedure.
# 1. Recommended: Ctrl+C in launch terminal (SIGINT → graceful shutdown)
# 2. If forced shutdown is needed:
sudo pkill -f plem_launch # Terminate launch process
sudo pkill -f bootstrap_node # Terminate RT driver (built-in driver)
# Clean shared memory
sudo rm -f /dev/shm/indy_* /dev/shm/joint_* 2>/dev/null
Troubleshooting
RT Driver Crash
Symptoms:
- EtherCAT communication stopped
- Servos enter SAFE-OP (brakes engaged)
- ROS2 nodes fail IPC reading
Recovery:
# Restart entire system
ros2 launch plem_bringup plem_launch.py
ROS2 Node Crash
Symptoms:
- RT driver continues running
- IPC write succeeds but no reader
- Protective stop after 100ms (command freshness timeout)
Recovery:
# Restart ROS2 nodes only (keep RT driver)
ros2 launch plem_bringup ros2_control.launch.py
# Automatically reconnects to existing shared memory
EtherCAT Communication Loss
Diagnosis:
# EtherCAT status
sudo ethercat slaves
sudo ethercat master
Common causes:
- Cable disconnected
- Servo power loss
- Network interface configuration issues
Shared Memory Corruption
Symptoms:
- NaN/inf values in joint states
- Persistent IPC read failures
Recovery:
# Terminate processes (Ctrl+C recommended, or commands below)
sudo pkill -f plem_launch
sudo pkill -f bootstrap_node
# Clean shared memory then restart
sudo rm -f /dev/shm/indy_* /dev/shm/joint_* 2>/dev/null
ros2 launch plem_bringup plem_launch.py
Summary
Key points:
- RT thread separation: RT threads within RT driver (1kHz control) + multiple ROS2 nodes (planning/interface)
- Communication: RT↔ROS2 data exchange via POSIX shared memory
- Execution:
ros2 launch plem_bringup plem_launch.py(automatic sequencing) - Composable Launch structure:
plem_launch.py: Main integration (all components + Python bridge)rt_driver.launch.py: RT driver onlyros2_control.launch.py: ROS2 Control stackmoveit.launch.py: MoveIt plannermoveit_only_launch.py: Single robot MoveIt (namespace isolation)multi_robot.launch.py: Multi-robot simultaneous execution
- Modular design: Each component can be run and restarted independently
- Python Bridge:
plem_ai_serverintegrated into main launch provides WebSocket/UDP communication - Multi-robot support:
robot_idparameter isolates namespace and IPC paths - Monitoring:
/{robot_id}/rt_raw(jitter),/{robot_id}/joint_states(state),/{robot_id}/rt_events(events) - Recovery: ROS2 nodes can restart independently while maintaining RT driver
- Launch arguments:
robot_id: Robot instance ID (namespace, IPC prefix)description_package: Specify external URDF/xacro packagerobot_type: Select built-in robot type (only when wim_description)
Next steps:
- Action Servers - Handling long-running tasks