FMIAdapter.h
Go to the documentation of this file.
1 // Copyright (c) 2018 - for information on the respective copyright owner
2 // see the NOTICE file and/or the repository https://github.com/boschresearch/fmi_adapter.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #pragma once
17 
18 #include <cassert>
19 #include <map>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
24 #include <ros/ros.h>
25 
26 struct fmi_xml_context_t;
27 typedef struct fmi_xml_context_t fmi_import_context_t;
28 struct fmi2_import_t;
29 struct fmi2_xml_variable_t;
30 typedef struct fmi2_xml_variable_t fmi2_import_variable_t;
31 struct jm_callbacks;
32 
33 namespace fmi_adapter {
34 
38 class FMIAdapter {
39  public:
42  explicit FMIAdapter(const std::string& fmuPath, ros::Duration stepSize = ros::Duration(0.0),
43  bool interpolateInput = true, const std::string& tmpPath = "");
44 
45  FMIAdapter(const FMIAdapter& other) = delete;
46 
47  FMIAdapter& operator=(const FMIAdapter&) = delete;
48 
49  virtual ~FMIAdapter();
50 
53  static std::string rosifyName(const std::string& name);
54 
57 
60 
63  std::vector<fmi2_import_variable_t*> getAllVariables() const;
64 
66  std::vector<fmi2_import_variable_t*> getInputVariables() const;
67 
69  std::vector<fmi2_import_variable_t*> getOutputVariables() const;
70 
72  std::vector<fmi2_import_variable_t*> getParameters() const;
73 
76  std::vector<std::string> getAllVariableNames() const;
77 
79  std::vector<std::string> getInputVariableNames() const;
80 
82  std::vector<std::string> getOutputVariableNames() const;
83 
85  std::vector<std::string> getParameterNames() const;
86 
88  void setInputValue(fmi2_import_variable_t* variable, ros::Time time, double value);
89 
92  void setInputValue(std::string variableName, ros::Time time, double value);
93 
95  ros::Duration getStepSize() const { return stepSize_; }
96 
100 
104  void exitInitializationMode(ros::Time simulationTime);
105 
107  ros::Time doStep();
108 
110  ros::Time doStep(const ros::Duration& stepSize);
111 
115  ros::Time doStepsUntil(const ros::Time& simulationTime);
116 
118  __attribute__((deprecated)) void calcUntil(ros::Time simulationTime) { doStepsUntil(simulationTime); }
119 
122 
124  double getOutputValue(fmi2_import_variable_t* variable) const;
125 
127  double getOutputValue(const std::string& variableName) const;
128 
131  void setInitialValue(fmi2_import_variable_t* variable, double value);
132 
135  void setInitialValue(const std::string& variableName, double value);
136 
142  void initializeFromROSParameters(const ros::NodeHandle& handle);
143 
144  private:
146  const std::string fmuPath_;
147 
150 
154 
156  std::string tmpPath_;
157 
159  bool removeTmpPathInDtor_{false};
160 
162 
165 
167  double fmuTime_{0.0};
168 
171 
173  fmi2_import_t* fmu_{nullptr};
174 
177 
180  void* fmiCallbacks_{nullptr};
181 
183  jm_callbacks* jmCallbacks_{nullptr};
184 
186  std::map<fmi2_import_variable_t*, std::map<ros::Time, double>> inputValuesByVariable_{};
187 
190  void doStepInternal(const ros::Duration& stepSize);
191 
194 };
195 
196 } // namespace fmi_adapter
std::vector< std::string > getParameterNames() const
Returns the names of all parameters of the wrapped FMU in the FMI Library&#39;s internal representation...
Definition: FMIAdapter.cpp:289
std::map< fmi2_import_variable_t *, std::map< ros::Time, double > > inputValuesByVariable_
Stores the mapping from timestamps to variable values for the FMU simulation.
Definition: FMIAdapter.h:186
std::vector< fmi2_import_variable_t * > getOutputVariables() const
Returns all output variables of the wrapped FMU in the FMI Library&#39;s internal representation.
Definition: FMIAdapter.cpp:260
static std::string rosifyName(const std::string &name)
Definition: FMIAdapter.cpp:220
void setInitialValue(fmi2_import_variable_t *variable, double value)
Definition: FMIAdapter.cpp:447
void doStepInternal(const ros::Duration &stepSize)
Definition: FMIAdapter.cpp:346
double getOutputValue(fmi2_import_variable_t *variable) const
Returns the current value of the given output variable.
Definition: FMIAdapter.cpp:424
std::vector< std::string > getInputVariableNames() const
Returns the names of all input variables of the wrapped FMU in the FMI Library&#39;s internal representat...
Definition: FMIAdapter.cpp:277
fmi2_import_t * fmu_
Pointer from the FMU Library types to the FMU instance.
Definition: FMIAdapter.h:173
std::vector< std::string > getAllVariableNames() const
Definition: FMIAdapter.cpp:272
ros::Time doStep()
Performs one simulation step using the configured step size and returns the current simulation time...
Definition: FMIAdapter.cpp:321
ros::Time getSimulationTime() const
Returns the current simulation time.
Definition: FMIAdapter.cpp:396
std::vector< fmi2_import_variable_t * > getAllVariables() const
Definition: FMIAdapter.cpp:249
FMIAdapter & operator=(const FMIAdapter &)=delete
__attribute__((deprecated)) void calcUntil(ros
This function has been replaced by doStepsUntil.
Definition: FMIAdapter.h:118
FMIAdapter(const std::string &fmuPath, ros::Duration stepSize=ros::Duration(0.0), bool interpolateInput=true, const std::string &tmpPath="")
Definition: FMIAdapter.cpp:112
std::vector< fmi2_import_variable_t * > getParameters() const
Returns all parameters of the wrapped FMU in the FMI Library&#39;s internal representation.
Definition: FMIAdapter.cpp:266
bool removeTmpPathInDtor_
In case that a random folder /tmp is being used (i.e. if given tmp path is ""), clean up this folder ...
Definition: FMIAdapter.h:159
bool isInInitializationMode() const
Definition: FMIAdapter.h:99
ros::Duration getStepSize() const
Returns the step-size used in the FMU simulation.
Definition: FMIAdapter.h:95
void exitInitializationMode(ros::Time simulationTime)
Definition: FMIAdapter.cpp:295
ros::Duration getDefaultExperimentStep() const
Returns the default experiment step-size of the FMU of this instance.
Definition: FMIAdapter.cpp:244
fmi_import_context_t * context_
Pointer from the FMU Library types to the FMU context.
Definition: FMIAdapter.h:176
std::vector< std::string > getOutputVariableNames() const
Returns the names of all output variables of the wrapped FMU in the FMI Library&#39;s internal representa...
Definition: FMIAdapter.cpp:283
ros::Time doStepsUntil(const ros::Time &simulationTime)
Definition: FMIAdapter.cpp:377
double fmuTime_
The current FMU&#39;s simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.
Definition: FMIAdapter.h:167
ros::Duration stepSize_
Step size for the FMU simulation.
Definition: FMIAdapter.h:149
std::string tmpPath_
Path to folder for extracting the FMU file temporarilly.
Definition: FMIAdapter.h:156
std::vector< fmi2_import_variable_t * > getInputVariables() const
Returns all input variables of the wrapped FMU in the FMI Library&#39;s internal representation.
Definition: FMIAdapter.cpp:254
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...
Definition: FMIAdapter.cpp:405
ros::Time simulationTime_
The current ROS-based simulation time. It is fmuTime_ = simulationTime_ - fmuTimeOffset_.
Definition: FMIAdapter.h:170
void initializeFromROSParameters(const ros::NodeHandle &handle)
Definition: FMIAdapter.cpp:470
ros::Time getSimulationTimeInternal() const
Returns the current simulation time. The state w.r.t. initialization mode is not checked.
Definition: FMIAdapter.h:193
struct fmi_xml_context_t fmi_import_context_t
Definition: FMIAdapter.h:27
bool canHandleVariableCommunicationStepSize() const
Returns true if the FMU of this instances supports a variable communication step-size.
Definition: FMIAdapter.cpp:239
struct fmi2_xml_variable_t fmi2_import_variable_t
Definition: FMIAdapter.h:30
jm_callbacks * jmCallbacks_
Further callback functions for FMI Library.
Definition: FMIAdapter.h:183
const std::string fmuPath_
Path of the FMU being wrapped by this instance.
Definition: FMIAdapter.h:146
ros::Duration fmuTimeOffset_
Offset between the FMU&#39;s simulation time and the ROS-based simulation time for doStep*(..) and setValue(..)
Definition: FMIAdapter.h:164


fmi_adapter
Author(s): Ralph Lange
autogenerated on Wed Nov 23 2022 03:42:28