Skip to content

ESOGU-SRLAB/FMU-Based-Trajectory-Validation

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

6 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

FMU-Based Multi-Criteria Trajectory Validation of Industrial Robots

ROS2 Humble FMI 2.0 License: BSD-3 UR10e IEEE Access

A modular, FMI 2.0-compliant validation framework that evaluates industrial robot trajectories against dynamics, safety, and smoothness criteria in real time within a ROS 2 / MoveIt 2 / Gazebo digital twin pipeline.

Framework Architecture


Overview

This repository contains the ROS 2 package fmu_validation accompanying the under-peer review IEEE Access paper:

S. Kahraman, C. S. Yilmaz, M. Yilmaz, and U. Yayan, "FMU-Based Multi-Criteria Trajectory Validation of Industrial Robots," IEEE Access, 2026.

The framework intercepts planned trajectories from MoveIt 2, resamples them to a fixed time step, and dispatches them to two parallel FMU-based validation modules before execution. This enables pre-execution assessment of trajectory quality, catching safety-critical deficiencies that are invisible to goal-position verification alone.

Key Findings (450-Test Evaluation)

Metric Rapid Sprint Chassis Inspection
PASS rate 96.4% 0%
Hard-fail ratio 0.00 -- 0.40 0.53 -- 1.00
Score paradox --- 96% soft-pass, 100% hard-fail

The same planner and velocity configurations yield vastly different outcomes across scenarios, demonstrating the framework's discriminant power.


Architecture

MoveIt 2 Planner ──► /display_planned_path ──► FMUValidatorNode
                                                     │
                                           resample (Δt = 0.01 s)
                                                     │
                                    ┌────────────────┼────────────────┐
                                    ▼                                 ▼
                        DynamicsSmoothnessFMU                   SafetyFMU
                        ┌──────────┬──────────┐        ┌────────────┬──────────┐
                        │ RNEA     │ Jerk     │        │ Joint      │ Velocity │
                        │ Solver   │ Analysis │        │ Margin     │ Ratio    │
                        │ (C++ FMU)│ (Python) │        │            │          │
                        └────┬─────┴────┬─────┘        └─────┬──────┴────┬─────┘
                             ▼          ▼                     ▼           ▼
                          S_dyn      S_smo                  S_saf (two-tier)
                                                      Hard Gate + Soft Score
                            │                                          │
                            └───────────────────────┬──────────────────┘
                                                    ▼
                                        Weighted Score Aggregation
                                   S = w_d·S_dyn + w_s·S_saf + w_m·S_smo
                                                     │
                                            ┌────────┼────────┐
                                            ▼        ▼        ▼
                                        PASS    WARNING    FAIL
                                        (≥0.70) (0.50-0.70) (<0.50)
                                                    │
                                            IEC 61508-Inspired
                                        Test-Level Aggregation
                                            (Hard-Fail Ratio φ)

Validation Modules

Module Method Output
Dynamics FMU C++ RNEA inverse dynamics solver (FMI 2.0 Co-Simulation) Torque ratio score S_dyn
Safety FMU Two-tier: hard gate at m_crit = 0.02 rad + geometric mean soft scoring Safety score S_saf
Smoothness Length-normalized Gaussian jerk decay function Smoothness score S_smo
Aggregation AHP-weighted sum + IEC 61508 ratio-based hard-fail classification PASS / WARNING / FAIL

Repository Structure

fmu_validation/
├── fmu_validation_core/
│   ├── __init__.py
│   ├── fmu_validator_node.py       # Central orchestrator (ROS 2 lifecycle node)
│   ├── dynamics_smoothness_fmu.py  # RNEA dynamics + jerk smoothness wrapper
│   ├── safety_fmu.py               # Two-tier safety validation module
│   ├── fmu_backend.py              # FMI 2.0 FMU loading and stepping
│   ├── common_utils.py             # Shared trajectory utilities
│   └── validator_utils.py          # Score computation helpers
├── scenarios/
│   ├── chasis_inspection.py        # 18-waypoint chassis inspection runner
│   └── rapid_sprint.py             # 4-waypoint rapid traversal runner
├── config/
│   ├── experiment_config.yaml      # Full 450-test experiment matrix
│   ├── ur10e_params.yaml           # UR10e joint specs and DH parameters
│   ├── validation_params.yaml      # Thresholds and scoring parameters
│   └── weights/
│       ├── baseline.yaml           # w_d=0.35, w_s=0.40, w_m=0.25
│       ├── safety_dominant.yaml    # w_s=0.60 (HRC scenarios)
│       ├── dynamics_dominant.yaml  # w_d=0.50 (high-payload)
│       ├── smoothness_focus.yaml   # w_m=0.45 (precision assembly)
│       └── equal.yaml              # w_d≈w_s≈w_m≈0.333
├── fmus/
│   └── ur10e_dynamics.fmu          # Pre-compiled RNEA Co-Simulation FMU
├── msg/
│   ├── ValidationResult.msg        # Per-trajectory validation output
│   └── ValidationMetrics.msg       # Raw physical metrics
├── launch/
│   └── validation.launch.py
├── CMakeLists.txt
├── package.xml
├── setup.py
└── README.md

Prerequisites

Dependency Version Notes
Ubuntu 22.04 LTS Tested platform
ROS 2 Humble Hawksbill ros-humble-desktop
MoveIt 2 2.5.5+ ros-humble-moveit
Gazebo Fortress (Ignition) Included with ROS 2 Humble
Python 3.10+ With numpy, scipy, pyyaml, pandas
FMPy 0.3.x pip install fmpy
UR packages --- ros-humble-ur-robot-driver, ros-humble-ur-description

Installation

# 1. Create workspace
mkdir -p ~/colcon_ws/src && cd ~/colcon_ws/src

# 2. Clone repository
git clone https://github.com/ESOGU-SRLAB/FMU-Based-Trajectory-Validation.git fmu_validation

# 3. Install dependencies
cd ~/colcon_ws
rosdep install --from-paths src --ignore-src -r -y
pip install fmpy numpy scipy pandas pyyaml

# 4. Build
colcon build --packages-select fmu_validation
source install/setup.bash

Usage

1. Launch the Validation Pipeline

# Terminal 1: Start UR10e simulation + MoveIt 2
ros2 launch ur_simulation ur10e_sim_moveit.launch.py

# Terminal 2: Start FMU validator node
ros2 run fmu_validation fmu_validator

2. Run Experiment Scenarios

# Chassis Inspection (18 waypoints, 225 tests)
ros2 run fmu_validation chasis_inspection

# Rapid Sprint (4 waypoints, 225 tests)
ros2 run fmu_validation rapid_sprint

3. Monitor in Real Time

# Validation results
ros2 topic echo /trajectory_validation/result

# Raw metrics
ros2 topic echo /trajectory_validation/metrics

# Lightweight status
ros2 topic echo /trajectory_validation/status

4. Configure Weight Parameters

Weight configurations can be changed at runtime:

ros2 param set /fmu_validator_node weight_dynamics 0.35
ros2 param set /fmu_validator_node weight_safety 0.40
ros2 param set /fmu_validator_node weight_smoothness 0.25

Or load a predefined configuration:

ros2 param load /fmu_validator_node config/weights/safety_dominant.yaml

Experiment Design

The full evaluation consists of 450 tests (2 scenarios x 225 each):

Parameter Values
Scenarios Chassis Inspection (18 wp), Rapid Sprint (4 wp)
Planners RRTConnect, RRT*, EST
Velocity scales 0.075x, 0.15x, 0.30x
Repetitions 5 per configuration
Weight configs Baseline, Safety-dominant, Dynamics-dominant, Smoothness-focus, Equal

Scoring Thresholds

Level Threshold Condition
PASS S >= 0.70 No hard failures
WARNING 0.50 <= S < 0.70 Borderline quality
FAIL S < 0.50 Below acceptable quality
HARD FAIL --- m < 0.02 rad OR rho >= 1.0

IEC 61508-Inspired Test-Level Aggregation

Regime Hard-Fail Ratio (phi) Decision
Normal phi = 0 Pure soft scoring
Random 0 < phi < 0.50 Dual condition: phi < 0.50 AND S >= 0.70
Systematic phi >= 0.50 Unconditional FAIL

Sim-to-Real Validation

Physical experiments on a real UR10e robot confirmed the FMU dynamics fidelity:

Joint Gravity Offset (Nm) Comp. RMSE (Nm) NRMSE (%) Correlation r
J1 (Shoulder Pan) 0.14 2.21 0.67 0.118
J2 (Shoulder Lift) 70.47 37.12 11.25 0.913
J3 (Elbow) 21.95 10.72 7.14 0.853
J4 (Wrist 1) 0.39 1.21 2.16 0.357
J5 (Wrist 2) -0.08 0.49 0.87 0.071
J6 (Wrist 3) -0.08 0.61 1.10 -0.043

19,651 samples/joint over 56 minutes. The gravity offset arises because the UR10e controller reports post-compensation effort, while the FMU RNEA computes full inverse dynamics including gravity.


Citation

If you use this framework in your research, please cite:

@article{kahraman2026fmu,
  title={{FMU}-Based Multi-Criteria Trajectory Validation of Industrial Robots},
  author={Kahraman, Serhat and Yilmaz, Cem Suha and Yilmaz, Metin and Yayan, Ugur},
  description = {Under Peer Review}
  journal={IEEE Access},
  year={2026},
  publisher={IEEE},
}

Acknowledgments

This project is supported by the European HORIZON-CHIPS-JU research project MATISSE and its members, including top-up funding by Vinnova (SE), FFG (AT), Business Finland (FI), Ministry of Universities and Research (IT), FCT (PT), and TUBITAK (TR).


License

This project is licensed under the BSD 3-Clause License. See LICENSE for details.


Contact

Department of Computer Engineering & Software Engineering, Eskisehir Osmangazi University, Turkey

About

A modular, FMI 2.0-compliant validation framework that evaluates industrial robot trajectories against dynamics, safety, and smoothness criteria in real time within a ROS 2 / MoveIt 2 / Gazebo digital twin pipeline.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors