[Documentation] [TitleIndex] [WordIndex

Package Summary

Wraps FMUs for co-simulation

  • Maintainer status: maintained
  • Maintainer: Ralph Lange <ralph.lange AT de.bosch DOT com>
  • Author: Ralph Lange <ralph.lange AT de.bosch DOT com>
  • License: Apache License 2.0
  • Source: git https://github.com/boschresearch/fmi_adapter.git (branch: melodic_and_noetic)

Package Summary

Wraps FMUs for co-simulation

  • Maintainer status: maintained
  • Maintainer: Ralph Lange <ralph.lange AT de.bosch DOT com>
  • Author: Ralph Lange <ralph.lange AT de.bosch DOT com>
  • License: Apache License 2.0
  • Source: git https://github.com/boschresearch/fmi_adapter.git (branch: melodic_and_noetic)

Please see https://index.ros.org/p/fmi_adapter/github-boschresearch-fmi_adapter_ros2 for the ROS 2 version of this package.

fmi_adapter

fmi_adapter is a small ROS 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.cpp), 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 according to the ROS clock. This approach is illustrated in the following diagram.

high-level_architecture_with_fmi_adapter_node.png

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

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

roslaunch fmi_adapter fmi_adapter_node.launch fmu_path:=[PathToTheFMUFile]

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.

high-level_architecture_with_application_node.png

For parsing the XML description of an FMU and for running the FMU's solver, fmi_adapter uses the C library FMI Library. This library is downloaded, compiled and linked in CMakeLists.txt of this package using cmake's externalproject_add command.

Examples

The fmi_adapter_examples package provides two FMUs and launch files to illustrate the use of the fmi_adapter node. Step-by-step instructions for creating your own FMU are also given.

damped_pendulum_with_transport_delay_in_rqt_plot.png

Please see https://github.com/boschresearch/fmi_adapter/blob/master/fmi_adapter_examples for details.

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.h from the fmi_adapter package in your C++ code.

#include "fmi_adapter/FMIAdapter.h"

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.

ros::Duration stepSize(0.001);
fmi_adapter::FMIAdapter adapter(fmuPath, stepSize);

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

ros::Subscriber subscriber =
    nHandle.subscribe<std_msgs::Float64>("angle_x", 1000, [&adapter](const std_msgs::Float64::ConstPtr& msg) {
      adapter.setInputValue("angleX", ros::Time::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:

ros::Timer timer = nHandle.createTimer(ros::Duration(0.01), [&](const ros::TimerEvent& event) {
    adapter.doStepsUntil(event.current_expected);
    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: Sets parameters and initial values of the FMU:

adapter.setInitialValue("dampingParam", 0.21);
adapter.setInitialValue("angleX", 1.3);

The function adapter.initializeFromROSParameters(nHandle) 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: Just before starting the spin thread, exit the FMU's initialization mode and set the ROS time that refers to the FMU's internal timepoint 0.0.

adapter.exitInitializationMode(ros::Time::now());
ros::spin();


2024-11-16 14:37