Skip to main content

Launch System

Overview

PLEM uses an RT (Real-Time) thread separation architecture.

  1. RT Driver - RT threads within a single process (EtherCAT 1kHz, Controller, IPC Bridge)
  2. 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 FileRoleDependencies
plem_launch.pyMain integrated launch - Automatic combination of all componentsIncludes all sub-launches
rt_driver.launch.pyRT driver (built-in/user shared)None (can run independently)
ros2_control.launch.pyROS2 Control stack (hardware interface + controllers)Requires RT driver
moveit.launch.pyMoveIt motion plannerRequires ROS2 Control
moveit_only_launch.pySingle robot MoveIt + ROS2 Control (namespace isolation)Requires RT driver
multi_robot.launch.pyN robots simultaneous execution (each with independent namespace)Requires RT driver

Design principles:

  • Each launch file can run independently (when dependencies are met)
  • plem_launch.py combines sub-launches using IncludeLaunchDescription
  • 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

ArgumentTypeDefaultDescription
robot_idstringindyRobot instance ID (ROS2 namespace, IPC prefix)
description_packagestringwim_descriptionRobot URDF/xacro package name
robot_typestringindy7_v2Built-in robot type (only when wim_description)
eth_interfacestringeth0EtherCAT network interface
master_indexint0EtherCAT master index (0=eth0, 1=eth1, etc.)
recordbooltrueEnable rosbag2 recording
bag_dirstring~/bags/rt_monitoringrosbag2 save directory
retention_minutesint60bag file retention period (minutes)
disk_thresholdint70Disk cleanup threshold (%)
urdf_filestring''URDF path override (for external packages)
srdf_filestring''SRDF path override (for external packages)
robot_namestring''Robot name override (for external packages)
Using External Description 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:

ArgumentDefaultDescription
rt_packagebootstrapPackage containing RT driver executable
rt_executablebootstrap_nodeExecutable name
robot_idindyRobot ID for IPC namespace
eth_interfaceeth0EtherCAT network interface
master_index0EtherCAT master index
Advanced Parameters

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.py is a composable launch that automatically executes the above components sequentially.
  • Python bridge (plem_ai_server) is integrated into plem_launch.py and 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
Parameter Names by Launch File
  • plem_launch.py: Uses robot_id parameter
  • moveit_only_launch.py: Uses name parameter
  • multi_robot.launch.py: Uses robots parameter (comma-separated)

Namespace structure:

ResourceSingle RobotMulti-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_ERROR WebSocket message
  • Namespace configuration via PLEM_ROBOT_ID environment variable (automatically passed from plem_launch.py with robot_id argument)

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

ScenarioRT DriverExecution Method
Supported robot (Description Package only)PLEM built-in RT driverros2 launch plem_bringup plem_launch.py or scaffold bringup.launch.py
New manufacturer robot (C++ Extension)User application created with create_robotros2 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

NodeRoleLaunch FilePackageLocation
(RT Driver)RT EtherCAT driver (1kHz)rt_driver.launch.py or user application--
ros2_control_nodeHardware interface, controller managementros2_control.launch.pycontroller_managerROS2 Control standard
robot_state_publisherURDF-based TF publishing (500Hz)ros2_control.launch.pyrobot_state_publisherROS2 standard
joint_trajectory_controllerTrajectory execution action server (500Hz)ros2_control.launch.pyjoint_trajectory_controllerROS2 Control standard
mode_control_action_serverMode control action serverros2_control.launch.pyPLEM runtimeAuto-start
rt_monitoring_publisherRT metrics ROS2 publishing (10Hz)ros2_control.launch.pyPLEM runtimeAuto-start
move_groupMoveIt motion planningmoveit.launch.pyMoveIt2 standardAuto-start
plan_trajectory_action_serverMotion planning action servermoveit.launch.pyPLEM runtimeAuto-start
plem_ai_serverPython WebSocket/UDP bridgeplem_launch.pyPLEM runtimeAuto-start
Launch File Location

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).

Multi-Robot Support

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

TopicRateContent
/joint_states500HzJoint position, velocity, effort
/rt_raw1kHzRT loop jitter, execution time, timing metrics
/rt_eventsEventMode changes, faults, state transitions
/rt_monitor_stats10HzQueue statistics, overflow counts
/tf500HzRobot kinematics tree
Multi-Robot Namespace

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

Emergency Shutdown Procedure

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:

  1. RT thread separation: RT threads within RT driver (1kHz control) + multiple ROS2 nodes (planning/interface)
  2. Communication: RT↔ROS2 data exchange via POSIX shared memory
  3. Execution: ros2 launch plem_bringup plem_launch.py (automatic sequencing)
  4. Composable Launch structure:
    • plem_launch.py: Main integration (all components + Python bridge)
    • rt_driver.launch.py: RT driver only
    • ros2_control.launch.py: ROS2 Control stack
    • moveit.launch.py: MoveIt planner
    • moveit_only_launch.py: Single robot MoveIt (namespace isolation)
    • multi_robot.launch.py: Multi-robot simultaneous execution
  5. Modular design: Each component can be run and restarted independently
  6. Python Bridge: plem_ai_server integrated into main launch provides WebSocket/UDP communication
  7. Multi-robot support: robot_id parameter isolates namespace and IPC paths
  8. Monitoring: /{robot_id}/rt_raw (jitter), /{robot_id}/joint_states (state), /{robot_id}/rt_events (events)
  9. Recovery: ROS2 nodes can restart independently while maintaining RT driver
  10. Launch arguments:
  • robot_id: Robot instance ID (namespace, IPC prefix)
  • description_package: Specify external URDF/xacro package
  • robot_type: Select built-in robot type (only when wim_description)

Next steps: