Skip to main content

Configuration Reference

Configuration Priority

When multiple configuration sources are available, the following priority applies (highest first):

  1. Programmatic Configuration (set directly in code)
  2. Launch File Parameters (command-line overrides)
  3. Environment Variables (system-wide defaults)
  4. Robot Profiles (instance-specific calibration)
  5. Model Defaults (compile-time constants)

SerialArmConfig Struct

SerialArmConfig<DOF> is the base template for all serial manipulator configurations. It provides a runtime configuration interface.

Complete Struct

template <size_t DOF>
struct SerialArmConfig {
static constexpr size_t dof = DOF;

// =====================================================================
// Fieldbus Configuration
// =====================================================================

/// EtherCAT network interface (e.g., "eth0", "enp3s0")
std::string network_interface = "eth0";

/// EtherCAT master index (0-based)
unsigned int master_index = 0;

/// Control loop cycle time (typically 1000µs for 1kHz)
std::chrono::microseconds cycle_time{1000};

/// Real-time thread priority (SCHED_FIFO, typically 98)
int rt_priority = 98;

// =====================================================================
// Robot Profile Parameters
// =====================================================================

/// Robot serial number for profile lookup
/// If set, joint_offsets are loaded from ~/.plem/profiles/<serial>.json
std::optional<std::string> robot_serial;

/// Joint encoder offsets (robot-specific calibration values)
/// Populated from robot_serial profile or set directly
std::array<int32_t, DOF> joint_offsets{};

// =====================================================================
// Dependency Injection
// =====================================================================

// =====================================================================
// Instance Identification
// =====================================================================

/// Robot instance identifier (for multi-robot support)
/// Empty string (default) for single-robot backward compatibility
std::string robot_id;

// =====================================================================
// Dependency Injection
// =====================================================================

/// Custom fieldbus implementation (nullptr = use default EtherCAT)
/// Use for testing with MockBus or alternative protocols
std::shared_ptr<fieldbus::IBus> custom_bus;
};

Member Descriptions

network_interface

Type: std::string Default: "eth0" Description: Network interface name for EtherCAT communication.

Valid values:

  • Physical interfaces: "eth0", "eth1", "enp3s0", "enp2s0"
  • Invalid: Wireless interfaces ("wlan0"), loopback ("lo")

How to find interfaces:

# List all network interfaces
ip link show

# Check EtherCAT master configuration
cat /opt/etherlab/etc/ethercat.conf | grep MASTER0_DEVICE

Common scenarios:

  • Desktop with single Ethernet port: "eth0" or "enp3s0"
  • W-RC/embedded: "eth0"
  • Multi-NIC systems: Use dedicated RT network interface

master_index

Type: unsigned int Default: 0 Description: EtherCAT master index for multi-master systems.

Common usage:

  • Single robot: 0 (default)
  • Multiple robots on one host: 0, 1, 2, etc.
  • Check available masters: ls /dev/EtherCAT*

Multi-robot setup example:

config_a.network_interface = "eth0";
config_a.master_index = 0;

config_b.network_interface = "eth1";
config_b.master_index = 1;

Use with_robot_id("arm_left") in Builder to isolate IPC/ROS2 namespaces. See Robot Integration Guide for details.

cycle_time

Type: std::chrono::microseconds Default: 1000 (1ms = 1kHz) Description: Control loop cycle time.

Valid range:

  • Minimum: 250µs (4kHz, experimental)
  • Typical: 1000µs (1kHz, recommended)
  • Maximum: 2000µs (500Hz)

Performance considerations:

  • Higher frequency = better control, higher CPU load
  • Must match EtherCAT cycle time in /opt/etherlab/etc/ethercat.conf
  • Below 1000µs requires RT kernel

rt_priority

Type: int Default: 98 Description: SCHED_FIFO real-time thread priority.

Valid range:

  • Minimum: 1 (lowest RT priority)
  • Recommended: 98 (high priority, below kernel threads)
  • Maximum: 99 (highest, reserved for critical kernel tasks)
RT Priority Warning

Never use rt_priority=99. This value is reserved for critical kernel watchdogs and interrupt handlers. Using rt_priority=99 can cause system instability, deadlocks, or complete system freezes.

Safe values:

  • Development/testing: 50-80
  • Production RT control: 95-98

robot_serial

Type: std::optional<std::string> Default: std::nullopt Description: Unique serial number for profile-based configuration.

Format: Manufacturer-specific (e.g., "PE07I7E0E001" for Neuromeka)

Behavior:

  • If set: joint_offsets are loaded from ~/.plem/profiles/<serial>.json
  • If not set: Use joint_offsets array directly

Example workflow:

// Option 1: Use robot serial (auto-load profile)
config.robot_serial = "PE07I7E0E001";

// Option 2: Set offsets directly
config.joint_offsets = {-535768, 195386, 191634, 34542, 24035, 21232};

joint_offsets

Type: std::array<int32_t, DOF> Default: All zeros Description: Per-joint encoder offset calibration values (raw encoder counts).

Units: Raw encoder counts (not radians)

Source priority:

  1. Loaded from profile if robot_serial is set
  2. Set directly in code
  3. Defaults to 0 (uncalibrated)

Calibration process:

  1. Move robot to known zero position (home)
  2. Read raw encoder values
  3. Negate values to obtain offsets
  4. Save in profile or set in configuration

custom_bus

Type: std::shared_ptr<fieldbus::IBus> Default: nullptr Description: Dependency injection for custom fieldbus implementations.

Usage scenarios:

  • Testing with MockBus: config.custom_bus = std::make_shared<MockBus>(6);
  • Alternative protocols: Implement IBus interface
  • Hardware-in-the-loop: Custom bridge implementation

Default behavior: When nullptr, factory automatically creates EtherCAT bus.

YAML Configuration Files

YAML files provide external configuration for ROS2 integration and MoveIt parameters. PLEM core library uses ConfigLoader for YAML file loading.

Using ConfigLoader

#include <plem/core/config/config_loader.hpp>

using namespace plem::core;

// Load scalar values
auto interface = load_config<std::string>("config.yaml", "network_interface");
auto priority = load_config<int>("config.yaml", "rt_priority");

// Load arrays
auto offsets = load_config<std::vector<int32_t>>("config.yaml", "joint_offsets");

// Load nested values (dot notation)
auto timeout = load_config<int>("config.yaml", "robot.control.timeout");

// Load safely with optional
auto opt_value = load_config_optional<double>("config.yaml", "optional_param");
if (opt_value) {
// Use *opt_value
}

// Load with default fallback
auto retry_count = ConfigLoader::get_instance()
.load_or_default<int>("config.yaml", 5, "retry_count");

YAML File Locations

ROS2 package resources:

wim_description/urdf/config/<robot_type>/
├── joint_limits.yaml # MoveIt joint limits
├── kinematics.yaml # Kinematics solver configuration
├── physical_parameters.yaml # Mass, inertia
└── visual_parameters.yaml # Mesh paths, colors

Launch configuration:

plem_bringup/config/
└── controllers.yaml # ros2_control controllers

Example: joint_limits.yaml

# Joint limits for indy7_v2
# Units: radians, rad/s, rad/s², Nm
# Note: Joint names as defined in URDF (Indy7: joint0-joint5, scaffold-generated: joint1-joint6)
joint_limits:
joint0:
has_velocity_limits: true
has_acceleration_limits: true
has_position_limits: true
max_velocity: 2.618 # 150 deg/s
max_acceleration: 5.0
max_effort: 431.97 # Nm
max_position: 3.054 # 175 deg
min_position: -3.054 # -175 deg
joint1:
has_velocity_limits: true
has_acceleration_limits: true
has_position_limits: true
max_velocity: 2.618
max_acceleration: 5.0
max_effort: 431.97
max_position: 3.054
min_position: -3.054
# ... joints 2-5

Example: controllers.yaml

controller_manager:
ros__parameters:
update_rate: 500 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

free_drive_controller:
type: wim_controller/FreeDriveController

joint_state_broadcaster:
ros__parameters:
joints:
- joint0
- joint1
- joint2
- joint3
- joint4
- joint5

joint_trajectory_controller:
ros__parameters:
joints:
- joint0
- joint1
- joint2
- joint3
- joint4
- joint5

command_interfaces:
- position
- velocity
- acceleration

state_interfaces:
- position
- velocity

Path Resolution

ConfigLoader supports multiple path formats:

Absolute paths:

load_config<int>("/etc/plem/config.yaml", "value");

Relative paths:

load_config<int>("config/robot.yaml", "value");  // From current directory

ROS2 package resources:

// Format: package_name/relative/path
load_config<int>("wim_description/urdf/config/indy7_v2/joint_limits.yaml",
"joint_limits.joint0.max_velocity");

Robot Profiles

Robot profiles store instance-specific calibration data in JSON format. This separates per-robot parameters from model-wide constants.

Profile Structure

Location: ~/.plem/profiles/<robot_serial>.json

Format:

{
"robot_serial": "PE07I7E0E001",
"joint_offsets": [-535768, 195386, 191634, 34542, 24035, 21232],
"profile_date": "2026-01-22T10:30:00Z"
}

Fields:

  • robot_serial: Unique identifier (required)
  • joint_offsets: Array of 6 int32 encoder offsets (required)
  • profile_date: ISO 8601 timestamp of creation/update (optional)

Creating Profiles

Programmatically:

#include <plem/robot/robot_profile.hpp>

using namespace plem::robot;

// Create profile
RobotProfile profile;
profile.robot_serial = "PE07I7E0E001";
profile.joint_offsets = {-535768, 195386, 191634, 34542, 24035, 21232};
profile.profile_date = "2026-02-02T12:00:00Z";

// Validate
if (!profile.is_valid()) {
throw std::runtime_error("Invalid profile");
}

// Save to default location (~/.plem/profiles/PE07I7E0E001.json)
std::filesystem::create_directories(RobotProfile::default_directory());
profile.save(RobotProfile::default_path(profile.robot_serial));

Manually:

# Create profile directory
mkdir -p ~/.plem/profiles

# Create profile file
cat > ~/.plem/profiles/PE07I7E0E001.json <<EOF
{
"robot_serial": "PE07I7E0E001",
"joint_offsets": [-535768, 195386, 191634, 34542, 24035, 21232],
"profile_date": "2026-02-02T12:00:00Z"
}
EOF

Loading Profiles

Automatic loading (recommended):

// Set robot serial in config
config.robot_serial = "PE07I7E0E001";

// Factory automatically loads profile
auto robot = RobotFactory<Indy7>::create(config, bus);
// joint_offsets are populated from ~/.plem/profiles/PE07I7E0E001.json

Manual loading:

// Load from default location
auto profile = RobotProfile::load_from_serial("PE07I7E0E001");

// Or load from custom path
auto profile = RobotProfile::load("/custom/path/robot.json");

// Apply to config
config.joint_offsets = profile.joint_offsets;

Profile Migration

Backward compatibility: Old profiles using "calibration_date" are automatically migrated to "profile_date":

// Old format (still supported)
{
"robot_serial": "OLD001",
"joint_offsets": [1, 2, 3, 4, 5, 6],
"calibration_date": "2025-01-01T00:00:00Z"
}

// Loads as:
profile.profile_date == "2025-01-01T00:00:00Z" // Automatically migrated

Environment Variables

Environment variables provide system-wide configuration defaults.

ROS_DOMAIN_ID

Purpose: ROS2 DDS domain isolation Default: 0 Valid range: 0-101 (avoid 215, reserved) Usage:

export ROS_DOMAIN_ID=42

When to use:

  • Multiple robots on same network
  • Development/production isolation
  • Multi-user environments

Note: All ROS2 nodes must use the same domain ID to communicate.

RMW_IMPLEMENTATION

Purpose: ROS2 middleware selection Default: rmw_cyclonedds_cpp (PLEM project default) Alternative: rmw_fastrtps_cpp Usage:

export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp

Performance notes:

  • CycloneDDS: Better real-time performance, lower latency
  • FastRTPS: More features, wider adoption

LD_LIBRARY_PATH

Purpose: Shared library search path Required when: Development builds outside install prefix Usage:

export LD_LIBRARY_PATH=/workspace/install/plem_core/lib:$LD_LIBRARY_PATH

Launch files set this automatically: build_plem_library_env() in launch_utils.py automatically discovers all installed plem_* packages and constructs LD_LIBRARY_PATH. Manual configuration is unnecessary.

RT Kernel Variables

PREEMPT_RT verification:

# Check kernel type
uname -a | grep PREEMPT_RT

# If RT kernel is installed, verify
cat /sys/kernel/realtime
# Output: 1 (RT kernel active)

CPU isolation (kernel parameter):

# Add to /etc/default/grub:
GRUB_CMDLINE_LINUX="isolcpus=7"

# Update grub and reboot
sudo update-grub
sudo reboot

Launch File Parameters

Launch files provide the primary interface for system configuration. PLEM uses Python launch files with declarative arguments.

Unified Launch Parameters (For Quick Testing)

File: plem_bringup/launch/plem_launch.py

Purpose: Prototyping, full-stack validation (starts all PLEM components) Production: Scaffold launcher recommended (generated with launch files via ros2 run plem_bringup create_description, disable with --no-launch)

eth_interface

Type: String Default: "eth0" Description: EtherCAT network interface

Usage:

ros2 launch plem_bringup plem_launch.py eth_interface:=enp3s0

robot_type

Type: String Default: "indy7_v2" Valid values: "indy7", "indy7_v2", "indy12", "indy12_v2", "indyrp2", etc. Description: Robot model selection (only used when description_package is wim_description)

Usage:

ros2 launch plem_bringup plem_launch.py robot_type:=indy12_v2

Effects:

  • Loads corresponding URDF from wim_description
  • Selects joint limit configuration
  • Configures MoveIt planning groups

description_package

Type: String Default: "wim_description" Description: ROS2 package containing URDF/SRDF/config

Usage:

# Use external robot (quick testing)
ros2 launch plem_bringup plem_launch.py description_package:=my_robot_description

# Use built-in robot (default)
ros2 launch plem_bringup plem_launch.py description_package:=wim_description robot_type:=indy7_v2

# Production: Use scaffold launcher (component selection available)
ros2 launch my_robot_description bringup.launch.py

Effects:

  • wim_description: Type-based selection (uses robot_type parameter)
  • Other packages: Convention-based auto-discovery (robot_type ignored)

urdf_file

Type: String Default: "" (auto-discovery) Description: Override auto-discovered URDF (path relative to description_package share)

Usage:

ros2 launch plem_bringup plem_launch.py \
description_package:=my_robot_description \
urdf_file:=urdf/my_robot_custom.urdf.xacro

When to use:

  • Package with multiple URDFs
  • Testing/debugging

srdf_file

Type: String Default: "" (auto-discovery) Description: Override auto-discovered SRDF (path relative to description_package share)

Usage:

ros2 launch plem_bringup plem_launch.py \
description_package:=my_robot_description \
srdf_file:=srdf/my_robot_custom.srdf.xacro

Note: If no SRDF, MoveIt is disabled and only ROS2 Control starts

robot_name

Type: String Default: "" (extracted from URDF) Description: Override robot name (used as MoveIt planning group prefix)

Usage:

ros2 launch plem_bringup plem_launch.py \
description_package:=my_robot_description \
robot_name:=my_custom_robot

Effects:

  • MoveIt planning group: {robot_name}_manipulator
  • Default: Extracted from URDF <robot name="..."> attribute

record

Type: Boolean Default: true Description: Enable rosbag2 recording of RT monitoring topics

Usage:

# Disable recording
ros2 launch plem_bringup plem_launch.py record:=false

Recorded topics:

  • /rt_raw (1kHz): Raw RT loop data
  • /rt_events: RT events (faults, state changes)
  • /rt_monitor_stats (10Hz): Queue statistics

bag_dir

Type: String Default: ~/bags/rt_monitoring Description: Directory for rosbag files

Usage:

ros2 launch plem_bringup plem_launch.py bag_dir:=/data/bags

retention_minutes

Type: Integer Default: 60 Description: How long to keep bag files (circular buffer)

Usage:

# Keep 2 hours of data
ros2 launch plem_bringup plem_launch.py retention_minutes:=120

disk_threshold

Type: Integer (percentage) Default: 70 Description: Delete oldest files when disk usage exceeds threshold

Usage:

ros2 launch plem_bringup plem_launch.py disk_threshold:=80

robot_id

Type: String Default: "indy" Description: Robot instance identifier. All ROS2 topics, actions, and IPC paths are prefixed with /{robot_id}/ namespace.

Usage:

# Single robot (default)
ros2 launch plem_bringup plem_launch.py robot_id:=indy

# Multi-robot (each with unique ID)
ros2 launch plem_bringup multi_robot.launch.py

Effects:

  • IPC shared memory path: /{robot_id}_joint_actual_values
  • ROS2 topics: /{robot_id}/joint_states, /{robot_id}/rt_raw
  • ROS2 actions: /{robot_id}/wim_rt_driver/set_mode
  • Python bridge: Sets namespace via PLEM_ROBOT_ID environment variable (automatically passed from robot_id argument in plem_launch.py)

Multi-robot scenario:

// C++ Builder API
auto left = Robot::builder<Indy7>(config_a).with_robot_id("arm_left").build();
auto right = Robot::builder<Indy7>(config_b).with_robot_id("arm_right").build();
Backward Compatibility

When robot_id is not specified, it defaults to "indy" for backward compatibility with existing single-robot setups. The C++ SerialArmConfig robot_id defaults to empty string, while the launch parameter default is "indy". plem_launch.py automatically passes the robot_id argument to the Python bridge as the PLEM_ROBOT_ID environment variable.

Launch File Declaration Pattern

from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration

def generate_launch_description():
# Declare argument
robot_type_arg = DeclareLaunchArgument(
'robot_type',
default_value='indy7_v2',
description='Robot type (indy7_v2, indy12_v2, etc.)'
)

# Use argument
robot_type = LaunchConfiguration('robot_type')

return LaunchDescription([
robot_type_arg,
# ... nodes that use robot_type
])

Configuration Examples

Development Setup (MockBus)

Unit testing without hardware:

#include <plem/robot/models/indy7.hpp>
#include <plem/robot/specs/robot_factory.hpp>
#include <plem/fieldbus/mock_bus.hpp>

using namespace plem::robot;
using namespace plem::fieldbus;

// Create config
models::Indy7 config;
config.rt_priority = 50; // Lower priority for testing

// Inject MockBus
auto mock_bus = std::make_shared<MockBus>(6);
config.custom_bus = mock_bus;

// Create robot (no EtherCAT needed, use Builder pattern)
auto result = Robot::builder<models::Indy7>(config).build();

Production Setup (EtherCAT)

Physical robot with profile-based calibration:

#include <plem/robot/robot_builder.hpp>
#include <plem/robot/models/indy7.hpp>

using namespace plem::robot;

// Create config
models::Indy7 config;
config.network_interface = "eth0";
config.master_index = 0;
config.cycle_time = std::chrono::microseconds(1000); // 1kHz
config.rt_priority = 98;
config.robot_serial = "PE07I7E0E001"; // Auto-loads profile

// Create robot (use Builder pattern)
auto result = Robot::builder<models::Indy7>(config).build();
if (!result.is_ok()) { /* Handle error */ }
auto robot = std::move(result).value();

Launch equivalent:

ros2 launch plem_bringup plem_launch.py \
eth_interface:=eth0 \
robot_type:=indy7_v2 \
robot_id:=indy

Common Configuration Errors

Configuration Troubleshooting

Here are common errors encountered when configuring PLEM and how to resolve them.

Error: "Failed to open profile file"

Cause: Profile file not found Solution:

# Check file exists
ls ~/.plem/profiles/PE07I7E0E001.json

# Create if missing
mkdir -p ~/.plem/profiles
# ... create profile file

Error: "EtherCAT master not found"

Cause: EtherCAT service not running or incorrect interface Solution:

# Check service
sudo systemctl status ethercat

# Restart if needed
sudo systemctl restart ethercat

# Check devices
ls /dev/EtherCAT*

Error: "joint_offsets must have exactly 6 elements"

Cause: Invalid array size in profile Solution: Edit profile file, ensure 6 elements:

{
"robot_serial": "PE07I7E0E001",
"joint_offsets": [-535768, 195386, 191634, 34542, 24035, 21232],
"profile_date": "2026-02-02T12:00:00Z"
}

Error: "rt_priority out of range"

Cause: Invalid RT priority value Solution: Use range 1-99, avoid 99:

config.rt_priority = 98;  // Recommended production value

Error: "Network interface does not exist"

Cause: Configured interface not available Solution:

# Check available interfaces
ip link show

# Check EtherCAT configuration
cat /opt/etherlab/etc/ethercat.conf | grep MASTER0_DEVICE

Additional Resources

For runtime configuration of new robot models, see Robot Integration Guide.

For more configuration examples, refer to: