fmi_adapter

Wraps FMUs for co-simulation

README

General information about this repository, including legal information, build instructions and known issues/limitations, are given in README.md in the repository root.

The fmi_adapter package

fmi_adapter is a small ROS 2 package for wrapping functional mockup units (FMUs) for co-simulation of physical models into ROS nodes. FMUs are defined in the FMI standard. Currently, this package supports co-simulation FMUs according to the FMI 2.0 standard only.

FMUs can be created with a variety of modeling and simulation tools. Examples are Dymola, MATLAB/Simulink, OpenModelica, SimulationX, and Wolfram System Modeler.

Technically, a co-simulation FMU is a zip file (with suffix .fmu) containing a physical model and the corresponding solver as a shared library together with an XML file describing the inputs, outputs and parameters of the model and details of the solver configuration. An addition, the zip file may contain the source code of the model and solver in the C programming language.

fmi_adapter_node

fmi_adapter provides a ROS node fmi_adapter_node (class FMIAdapterNode derived from LifecycleNode), which takes an FMU and creates subscribers and publishers for the input and output variables of the FMU, respectively. Then, it runs the FMU’s solver with a user-definable update period. This approach is illustrated in the following diagram.

fmi_adapter in application node

The fmi_adapter_node also searches for counterparts for each FMU parameter and variable in the ROS node parameters and initializes the FMU correspondingly.

For this purpose, this package provide a launch file with argument fmu_path. Simply call

ros2 launch fmi_adapter fmi_adapter_node.launch.py fmu_path:=[PathToTheFMUFile]

Please see the README.md of the fmi_adapter_examples package for a step-by-step description how to use the fmi_adapter_node with a damped pendulum model and FMU.

fmi_adapter library

fmi_adapter provides a library with convenience functions based on common ROS types to load an FMU during runtime, to retrieve the input, output, and parameter names, to set timestamped input values, to run the FMU’s numeric solver, and to query the resulting output. These functions are provided by the class FMIAdapter. Instances of this class may be integrated in application-specific ROS nodes or libraries as illustrated in the following architecture diagram.

fmi_adapter in application node

For parsing the XML description of an FMU and for running the FMU’s solver, fmi_adapter uses the C library FMI Library. For this purpose, fmi_adapter depends on the fmilibrary_vendor package, which downloads and builds the FMI Library using cmake’s externalproject_add command.

Running an FMU inside a ROS node or library

In the following, we give some code snippets how to load and run an FMU file from an application-specific ROS node or library.

Step 1: Include the FMIAdapter.hpp from the fmi_adapter package in your C++ code.

#include "fmi_adapter/FMIAdapter.hpp"

Step 2: Instantiate the adapter class with the path to the FMU file and the desired simulation step size. If the step-size argument is omitted, the default step size specified in the FMU file will be used.

rclcpp::Duration stepSize(0.001);
auto adapter = std::make_shared<fmi_adapter::FMIAdapter>(get_logger(), fmuPath, stepSize);

Step 3: Create subscribers or timers to set the FMU’s input values. For example:

auto subscription = create_subscription<std_msgs::msg::Float64>("angle_x", 1000,
    [this](std_msgs::msg::Float64::SharedPtr msg) {
      adapter->setInputValue("angleX", now(), msg->data);
    });

In this example, angle_x is the topic name whereas angleX is the corresponding input variable of the FMU.

Use adapter->getInputVariableNames() to get a list of all input variables.

Step 4: Create a timer or subscriber that triggers the simulation of the FMU using adapter->doStepsUntil(..). For example:

auto timer = create_wall_timer(update_period,
    [this]() {
      adapter->doStepsUntil(now());
      double y = adapter->getOutputValue("angleY");
      // ... e.g., publish y on a topic ...
    });

Use adapter->getOutputVariableNames() to get a list of all output variables.

Step 5: Set parameters and initial values of the FMU:

adapter->setInitialValue("dampingParam", 0.21);
adapter->setInitialValue("angleX", 1.3);

The function adapter->initializeFromROSParameters(get_node_parameters_interface()) may be used to initialize all parameters from the corresponding ROS parameters. Please note that all characters in the FMU parameter names that are not supported by ROS are replaced by an ‘_’, cf. FMIAdapter::rosifyName(name).

Step 6: As last setup step, exit the FMU’s initialization mode and set the ROS time that refers to the FMU’s internal timepoint 0.0.

adapter->exitInitializationMode(now());

Papers

If you want to cite this repository/package, please cite the following book chapter (PDF available at Springer Link) instead:

Ralph Lange, Silvio Traversaro, Oliver Lenord, and Christian Bertsch: Integrating the Functional Mock-Up Interface with ROS and Gazebo. In: Anis Koubaa (ed.) Robot Operating System (ROS): The Complete Reference (Volume 5), Springer, pp. 187–231, 2021.

@INBOOK{Lange_et_al_2021_Integrating_the_FMI_with_ROS_and_Gazebo,
  author = {Ralph Lange and Silvio Traversaro and Oliver Lenord and Christian Bertsch},
  title = {Integrating the Functional Mock-Up Interface with ROS and Gazebo},
  editor = {Anis Koubaa},
  booktitle = {Robot Operating System (ROS): The Complete Reference (Volume 5)},
  year = {2021},
  publisher = {Springer},
  pages = {187--231},
  doi = {10.1007/978-3-030-45956-7_7}
}