26 struct fmi_xml_context_t;
29 struct fmi2_xml_variable_t;
43 bool interpolateInput =
true,
const std::string& tmpPath =
"");
53 static std::string
rosifyName(
const std::string& name);
std::vector< std::string > getParameterNames() const
Returns the names of all parameters of the wrapped FMU in the FMI Library's internal representation...
std::map< fmi2_import_variable_t *, std::map< ros::Time, double > > inputValuesByVariable_
Stores the mapping from timestamps to variable values for the FMU simulation.
bool inInitializationMode_
std::vector< fmi2_import_variable_t * > getOutputVariables() const
Returns all output variables of the wrapped FMU in the FMI Library's internal representation.
static std::string rosifyName(const std::string &name)
void setInitialValue(fmi2_import_variable_t *variable, double value)
void doStepInternal(const ros::Duration &stepSize)
double getOutputValue(fmi2_import_variable_t *variable) const
Returns the current value of the given output variable.
std::vector< std::string > getInputVariableNames() const
Returns the names of all input variables of the wrapped FMU in the FMI Library's internal representat...
fmi2_import_t * fmu_
Pointer from the FMU Library types to the FMU instance.
std::vector< std::string > getAllVariableNames() const
ros::Time doStep()
Performs one simulation step using the configured step size and returns the current simulation time...
ros::Time getSimulationTime() const
Returns the current simulation time.
std::vector< fmi2_import_variable_t * > getAllVariables() const
FMIAdapter & operator=(const FMIAdapter &)=delete
__attribute__((deprecated)) void calcUntil(ros
This function has been replaced by doStepsUntil.
FMIAdapter(const std::string &fmuPath, ros::Duration stepSize=ros::Duration(0.0), bool interpolateInput=true, const std::string &tmpPath="")
std::vector< fmi2_import_variable_t * > getParameters() const
Returns all parameters of the wrapped FMU in the FMI Library's internal representation.
bool removeTmpPathInDtor_
In case that a random folder /tmp is being used (i.e. if given tmp path is ""), clean up this folder ...
bool isInInitializationMode() const
ros::Duration getStepSize() const
Returns the step-size used in the FMU simulation.
void exitInitializationMode(ros::Time simulationTime)
ros::Duration getDefaultExperimentStep() const
Returns the default experiment step-size of the FMU of this instance.
fmi_import_context_t * context_
Pointer from the FMU Library types to the FMU context.
std::vector< std::string > getOutputVariableNames() const
Returns the names of all output variables of the wrapped FMU in the FMI Library's internal representa...
ros::Time doStepsUntil(const ros::Time &simulationTime)
double fmuTime_
The current FMU's simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.
ros::Duration stepSize_
Step size for the FMU simulation.
std::string tmpPath_
Path to folder for extracting the FMU file temporarilly.
std::vector< fmi2_import_variable_t * > getInputVariables() const
Returns all input variables of the wrapped FMU in the FMI Library's internal representation.
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 si...
ros::Time simulationTime_
The current ROS-based simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.
void initializeFromROSParameters(const ros::NodeHandle &handle)
ros::Time getSimulationTimeInternal() const
Returns the current simulation time. The state w.r.t. initialization mode is not checked.
struct fmi_xml_context_t fmi_import_context_t
bool canHandleVariableCommunicationStepSize() const
Returns true if the FMU of this instances supports a variable communication step-size.
struct fmi2_xml_variable_t fmi2_import_variable_t
jm_callbacks * jmCallbacks_
Further callback functions for FMI Library.
const std::string fmuPath_
Path of the FMU being wrapped by this instance.
ros::Duration fmuTimeOffset_
Offset between the FMU's simulation time and the ROS-based simulation time for doStep*(..) and setValue(..)