Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
fmi_adapter::FMIAdapter Class Reference

#include <FMIAdapter.h>

Public Member Functions

 __attribute__ ((deprecated)) void calcUntil(ros
 This function has been replaced by doStepsUntil. More...
 
bool canHandleVariableCommunicationStepSize () const
 Returns true if the FMU of this instances supports a variable communication step-size. More...
 
ros::Time doStep ()
 Performs one simulation step using the configured step size and returns the current simulation time. More...
 
ros::Time doStep (const ros::Duration &stepSize)
 Performs one simulation step using the given step size and returns the current simulation time. More...
 
ros::Time doStepsUntil (const ros::Time &simulationTime)
 
void exitInitializationMode (ros::Time simulationTime)
 
 FMIAdapter (const FMIAdapter &other)=delete
 
 FMIAdapter (const std::string &fmuPath, ros::Duration stepSize=ros::Duration(0.0), bool interpolateInput=true, const std::string &tmpPath="")
 
std::vector< std::string > getAllVariableNames () const
 
std::vector< fmi2_import_variable_t * > getAllVariables () const
 
ros::Duration getDefaultExperimentStep () const
 Returns the default experiment step-size of the FMU of this instance. More...
 
std::vector< std::string > getInputVariableNames () const
 Returns the names of all input variables of the wrapped FMU in the FMI Library's internal representation. More...
 
std::vector< fmi2_import_variable_t * > getInputVariables () const
 Returns all input variables of the wrapped FMU in the FMI Library's internal representation. More...
 
double getOutputValue (const std::string &variableName) const
 Returns the current value of the output variable with the given name. More...
 
double getOutputValue (fmi2_import_variable_t *variable) const
 Returns the current value of the given output variable. More...
 
std::vector< std::string > getOutputVariableNames () const
 Returns the names of all output variables of the wrapped FMU in the FMI Library's internal representation. More...
 
std::vector< fmi2_import_variable_t * > getOutputVariables () const
 Returns all output variables of the wrapped FMU in the FMI Library's internal representation. More...
 
std::vector< std::string > getParameterNames () const
 Returns the names of all parameters of the wrapped FMU in the FMI Library's internal representation. More...
 
std::vector< fmi2_import_variable_t * > getParameters () const
 Returns all parameters of the wrapped FMU in the FMI Library's internal representation. More...
 
ros::Time getSimulationTime () const
 Returns the current simulation time. More...
 
ros::Duration getStepSize () const
 Returns the step-size used in the FMU simulation. More...
 
void initializeFromROSParameters (const ros::NodeHandle &handle)
 
bool isInInitializationMode () const
 
FMIAdapteroperator= (const FMIAdapter &)=delete
 
void setInitialValue (const std::string &variableName, double value)
 
void setInitialValue (fmi2_import_variable_t *variable, double value)
 
void setInputValue (fmi2_import_variable_t *variable, ros::Time time, double value)
 Stores a value for the given variable to be considered by doStep*(..) at the given time of the FMU simulation. More...
 
void setInputValue (std::string variableName, ros::Time time, double value)
 
virtual ~FMIAdapter ()
 

Static Public Member Functions

static std::string rosifyName (const std::string &name)
 

Private Member Functions

void doStepInternal (const ros::Duration &stepSize)
 
ros::Time getSimulationTimeInternal () const
 Returns the current simulation time. The state w.r.t. initialization mode is not checked. More...
 

Private Attributes

fmi_import_context_tcontext_ {nullptr}
 Pointer from the FMU Library types to the FMU context. More...
 
void * fmiCallbacks_ {nullptr}
 
fmi2_import_t * fmu_ {nullptr}
 Pointer from the FMU Library types to the FMU instance. More...
 
const std::string fmuPath_
 Path of the FMU being wrapped by this instance. More...
 
double fmuTime_ {0.0}
 The current FMU's simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_. More...
 
ros::Duration fmuTimeOffset_ {0.0}
 Offset between the FMU's simulation time and the ROS-based simulation time for doStep*(..) and setValue(..) More...
 
bool inInitializationMode_ {true}
 
std::map< fmi2_import_variable_t *, std::map< ros::Time, double > > inputValuesByVariable_ {}
 Stores the mapping from timestamps to variable values for the FMU simulation. More...
 
bool interpolateInput_
 
jm_callbacks * jmCallbacks_ {nullptr}
 Further callback functions for FMI Library. More...
 
bool removeTmpPathInDtor_ {false}
 In case that a random folder /tmp is being used (i.e. if given tmp path is ""), clean up this folder in dtor. More...
 
ros::Time simulationTime_ {0.0}
 The current ROS-based simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_. More...
 
ros::Duration stepSize_
 Step size for the FMU simulation. More...
 
std::string tmpPath_
 Path to folder for extracting the FMU file temporarilly. More...
 

Detailed Description

An instance of this class wraps a FMU and allows to simulate it using the ROS time notion and standard C++ types. In the background, the FMI Library (a BSD-licensed C library) is used for interacting with the FMU. This class also provides concenvience functions to read parameters and initial values from ROS parameters.

Definition at line 38 of file FMIAdapter.h.

Constructor & Destructor Documentation

◆ FMIAdapter() [1/2]

fmi_adapter::FMIAdapter::FMIAdapter ( const std::string &  fmuPath,
ros::Duration  stepSize = ros::Duration(0.0),
bool  interpolateInput = true,
const std::string &  tmpPath = "" 
)
explicit

This ctor creates an instance using the FMU from the given path. If the step-size argument is zero, the default experiment step-size given in the FMU is used.

Definition at line 112 of file FMIAdapter.cpp.

◆ FMIAdapter() [2/2]

fmi_adapter::FMIAdapter::FMIAdapter ( const FMIAdapter other)
delete

◆ ~FMIAdapter()

fmi_adapter::FMIAdapter::~FMIAdapter ( )
virtual

Definition at line 201 of file FMIAdapter.cpp.

Member Function Documentation

◆ __attribute__()

fmi_adapter::FMIAdapter::__attribute__ ( (deprecated)  )
inline

This function has been replaced by doStepsUntil.

Definition at line 118 of file FMIAdapter.h.

◆ canHandleVariableCommunicationStepSize()

bool fmi_adapter::FMIAdapter::canHandleVariableCommunicationStepSize ( ) const

Returns true if the FMU of this instances supports a variable communication step-size.

Definition at line 239 of file FMIAdapter.cpp.

◆ doStep() [1/2]

ros::Time fmi_adapter::FMIAdapter::doStep ( )

Performs one simulation step using the configured step size and returns the current simulation time.

Definition at line 321 of file FMIAdapter.cpp.

◆ doStep() [2/2]

ros::Time fmi_adapter::FMIAdapter::doStep ( const ros::Duration stepSize)

Performs one simulation step using the given step size and returns the current simulation time.

Definition at line 332 of file FMIAdapter.cpp.

◆ doStepInternal()

void fmi_adapter::FMIAdapter::doStepInternal ( const ros::Duration stepSize)
private

Performs one simulation step using the given step size. Argument and state w.r.t. initialization mode are not checked.

Definition at line 346 of file FMIAdapter.cpp.

◆ doStepsUntil()

ros::Time fmi_adapter::FMIAdapter::doStepsUntil ( const ros::Time simulationTime)

Advances the simulation of the wrapped FMU until the given point in time (modulo step-size). In detail, the simulation is performed iteratively using the configured step-size. Before each simulation step the relevant input values passed previously by setInputValue(..) are set depending on the given timestamps.

Definition at line 377 of file FMIAdapter.cpp.

◆ exitInitializationMode()

void fmi_adapter::FMIAdapter::exitInitializationMode ( ros::Time  simulationTime)

Exits the initialization mode and starts the simulation of the wrapped FMU. Uses the given timestamp as start time for the simulation whereas the FMU internally starts at time 0. All times passed to setValue(..) and doStep*(..) are translated correspondingly.

Definition at line 295 of file FMIAdapter.cpp.

◆ getAllVariableNames()

std::vector< std::string > fmi_adapter::FMIAdapter::getAllVariableNames ( ) const

Returns the names of all variables (including parameters and aliases) of the wrapped FMU in the FMI Library's internal representation.

Definition at line 272 of file FMIAdapter.cpp.

◆ getAllVariables()

std::vector< fmi2_import_variable_t * > fmi_adapter::FMIAdapter::getAllVariables ( ) const

Returns all variables (including parameters, aliases, etc.) of the wrapped FMU in the FMI Library's internal representation.

Definition at line 249 of file FMIAdapter.cpp.

◆ getDefaultExperimentStep()

ros::Duration fmi_adapter::FMIAdapter::getDefaultExperimentStep ( ) const

Returns the default experiment step-size of the FMU of this instance.

Definition at line 244 of file FMIAdapter.cpp.

◆ getInputVariableNames()

std::vector< std::string > fmi_adapter::FMIAdapter::getInputVariableNames ( ) const

Returns the names of all input variables of the wrapped FMU in the FMI Library's internal representation.

Definition at line 277 of file FMIAdapter.cpp.

◆ getInputVariables()

std::vector< fmi2_import_variable_t * > fmi_adapter::FMIAdapter::getInputVariables ( ) const

Returns all input variables of the wrapped FMU in the FMI Library's internal representation.

Definition at line 254 of file FMIAdapter.cpp.

◆ getOutputValue() [1/2]

double fmi_adapter::FMIAdapter::getOutputValue ( const std::string &  variableName) const

Returns the current value of the output variable with the given name.

Definition at line 437 of file FMIAdapter.cpp.

◆ getOutputValue() [2/2]

double fmi_adapter::FMIAdapter::getOutputValue ( fmi2_import_variable_t variable) const

Returns the current value of the given output variable.

Definition at line 424 of file FMIAdapter.cpp.

◆ getOutputVariableNames()

std::vector< std::string > fmi_adapter::FMIAdapter::getOutputVariableNames ( ) const

Returns the names of all output variables of the wrapped FMU in the FMI Library's internal representation.

Definition at line 283 of file FMIAdapter.cpp.

◆ getOutputVariables()

std::vector< fmi2_import_variable_t * > fmi_adapter::FMIAdapter::getOutputVariables ( ) const

Returns all output variables of the wrapped FMU in the FMI Library's internal representation.

Definition at line 260 of file FMIAdapter.cpp.

◆ getParameterNames()

std::vector< std::string > fmi_adapter::FMIAdapter::getParameterNames ( ) const

Returns the names of all parameters of the wrapped FMU in the FMI Library's internal representation.

Definition at line 289 of file FMIAdapter.cpp.

◆ getParameters()

std::vector< fmi2_import_variable_t * > fmi_adapter::FMIAdapter::getParameters ( ) const

Returns all parameters of the wrapped FMU in the FMI Library's internal representation.

Definition at line 266 of file FMIAdapter.cpp.

◆ getSimulationTime()

ros::Time fmi_adapter::FMIAdapter::getSimulationTime ( ) const

Returns the current simulation time.

Definition at line 396 of file FMIAdapter.cpp.

◆ getSimulationTimeInternal()

ros::Time fmi_adapter::FMIAdapter::getSimulationTimeInternal ( ) const
inlineprivate

Returns the current simulation time. The state w.r.t. initialization mode is not checked.

Definition at line 193 of file FMIAdapter.h.

◆ getStepSize()

ros::Duration fmi_adapter::FMIAdapter::getStepSize ( ) const
inline

Returns the step-size used in the FMU simulation.

Definition at line 95 of file FMIAdapter.h.

◆ initializeFromROSParameters()

void fmi_adapter::FMIAdapter::initializeFromROSParameters ( const ros::NodeHandle handle)

Tries to read inital values for each variable (including parameters and aliases) from the ROS parameter set. The function only considers private ROS parameters, i.e. parameters that have the node name as prefix. Note that ROS parameter names may use the characters [A-Za-z0-9_] only. Therefore, all other characters in an FMU variable name are mapped to '_'. For example, to pass a value for the FMU variable 'dx[2]', use the ROS parameter '/my_node_name/dx_2_'.

Definition at line 470 of file FMIAdapter.cpp.

◆ isInInitializationMode()

bool fmi_adapter::FMIAdapter::isInInitializationMode ( ) const
inline

Returns true if the wrapped FMU is still in initialization mode, which allows to set parameters and initial values.

Definition at line 99 of file FMIAdapter.h.

◆ operator=()

FMIAdapter& fmi_adapter::FMIAdapter::operator= ( const FMIAdapter )
delete

◆ rosifyName()

std::string fmi_adapter::FMIAdapter::rosifyName ( const std::string &  name)
static

This helper function returns a ROSified version of the given variable name for use with ROS parameters. It simply replaces all special charaters not supported by ROS with an '_'.

Definition at line 220 of file FMIAdapter.cpp.

◆ setInitialValue() [1/2]

void fmi_adapter::FMIAdapter::setInitialValue ( const std::string &  variableName,
double  value 
)

Sets the given value of the variable (or parameter or alias) with the given name as initial values. This function may be called only while isInInitializationMode() = true.

Definition at line 460 of file FMIAdapter.cpp.

◆ setInitialValue() [2/2]

void fmi_adapter::FMIAdapter::setInitialValue ( fmi2_import_variable_t variable,
double  value 
)

Sets the given value of the given variable (or parameter or alias) as initial values. This function may be called only while isInInitializationMode() = true.

Definition at line 447 of file FMIAdapter.cpp.

◆ setInputValue() [1/2]

void fmi_adapter::FMIAdapter::setInputValue ( fmi2_import_variable_t variable,
ros::Time  time,
double  value 
)

Stores a value for the given variable to be considered by doStep*(..) at the given time of the FMU simulation.

Definition at line 405 of file FMIAdapter.cpp.

◆ setInputValue() [2/2]

void fmi_adapter::FMIAdapter::setInputValue ( std::string  variableName,
ros::Time  time,
double  value 
)

Stores a value for the variable with the given name to be considered by doStep*(..) at the given time of the FMU simulation.

Definition at line 414 of file FMIAdapter.cpp.

Member Data Documentation

◆ context_

fmi_import_context_t* fmi_adapter::FMIAdapter::context_ {nullptr}
private

Pointer from the FMU Library types to the FMU context.

Definition at line 176 of file FMIAdapter.h.

◆ fmiCallbacks_

void* fmi_adapter::FMIAdapter::fmiCallbacks_ {nullptr}
private

Callback functions for FMI Library. Cannot use type fmi2_callback_functions_t here as it is a typedef of an anonymous struct, cf. https://stackoverflow.com/questions/7256436/forward-declarations-of-unnamed-struct

Definition at line 180 of file FMIAdapter.h.

◆ fmu_

fmi2_import_t* fmi_adapter::FMIAdapter::fmu_ {nullptr}
private

Pointer from the FMU Library types to the FMU instance.

Definition at line 173 of file FMIAdapter.h.

◆ fmuPath_

const std::string fmi_adapter::FMIAdapter::fmuPath_
private

Path of the FMU being wrapped by this instance.

Definition at line 146 of file FMIAdapter.h.

◆ fmuTime_

double fmi_adapter::FMIAdapter::fmuTime_ {0.0}
private

The current FMU's simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.

Definition at line 167 of file FMIAdapter.h.

◆ fmuTimeOffset_

ros::Duration fmi_adapter::FMIAdapter::fmuTimeOffset_ {0.0}
private

Offset between the FMU's simulation time and the ROS-based simulation time for doStep*(..) and setValue(..)

Definition at line 164 of file FMIAdapter.h.

◆ inInitializationMode_

bool fmi_adapter::FMIAdapter::inInitializationMode_ {true}
private

Definition at line 161 of file FMIAdapter.h.

◆ inputValuesByVariable_

std::map<fmi2_import_variable_t*, std::map<ros::Time, double> > fmi_adapter::FMIAdapter::inputValuesByVariable_ {}
private

Stores the mapping from timestamps to variable values for the FMU simulation.

Definition at line 186 of file FMIAdapter.h.

◆ interpolateInput_

bool fmi_adapter::FMIAdapter::interpolateInput_
private

States whether between input values should be considered as continuous, piecewise linear signal (true) or as non-continuous, piecewise constant signal (false).

Definition at line 153 of file FMIAdapter.h.

◆ jmCallbacks_

jm_callbacks* fmi_adapter::FMIAdapter::jmCallbacks_ {nullptr}
private

Further callback functions for FMI Library.

Definition at line 183 of file FMIAdapter.h.

◆ removeTmpPathInDtor_

bool fmi_adapter::FMIAdapter::removeTmpPathInDtor_ {false}
private

In case that a random folder /tmp is being used (i.e. if given tmp path is ""), clean up this folder in dtor.

Definition at line 159 of file FMIAdapter.h.

◆ simulationTime_

ros::Time fmi_adapter::FMIAdapter::simulationTime_ {0.0}
private

The current ROS-based simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.

Definition at line 170 of file FMIAdapter.h.

◆ stepSize_

ros::Duration fmi_adapter::FMIAdapter::stepSize_
private

Step size for the FMU simulation.

Definition at line 149 of file FMIAdapter.h.

◆ tmpPath_

std::string fmi_adapter::FMIAdapter::tmpPath_
private

Path to folder for extracting the FMU file temporarilly.

Definition at line 156 of file FMIAdapter.h.


The documentation for this class was generated from the following files:


fmi_adapter
Author(s): Ralph Lange
autogenerated on Thu Nov 24 2022 03:51:09