Program Listing for File FMIAdapter.hpp
↰ Return to documentation for file (/tmp/ws/src/fmi_adapter/fmi_adapter/include/fmi_adapter/FMIAdapter.hpp
)
// Copyright (c) 2019 - for information on the respective copyright owner
// see the NOTICE file and/or the repository https://github.com/boschresearch/fmi_adapter.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef FMI_ADAPTER__FMIADAPTER_HPP_
#define FMI_ADAPTER__FMIADAPTER_HPP_
#include <cassert>
#include <chrono>
#include <map>
#include <string>
#include <utility>
#include <vector>
#include <rclcpp/rclcpp.hpp>
struct fmi_xml_context_t;
typedef struct fmi_xml_context_t fmi_import_context_t;
struct fmi2_import_t;
struct fmi2_xml_variable_t;
typedef struct fmi2_xml_variable_t fmi2_import_variable_t;
struct jm_callbacks;
namespace fmi_adapter
{
namespace internal
{
const rclcpp::Duration ZERO_DURATION{std::chrono::nanoseconds(0)};
} // namespace internal
class FMIAdapter
{
public:
explicit FMIAdapter(
rclcpp::Logger logger, const std::string & fmuPath,
rclcpp::Duration stepSize = internal::ZERO_DURATION,
bool interpolateInput = true, const std::string & tmpPath = "");
RCLCPP_DISABLE_COPY(FMIAdapter)
virtual ~FMIAdapter();
static std::string rosifyName(const std::string & name);
bool canHandleVariableCommunicationStepSize() const;
rclcpp::Duration getDefaultExperimentStep() const;
std::vector<fmi2_import_variable_t *> getAllVariables() const;
std::vector<fmi2_import_variable_t *> getInputVariables() const;
std::vector<fmi2_import_variable_t *> getOutputVariables() const;
std::vector<fmi2_import_variable_t *> getParameters() const;
std::vector<std::string> getAllVariableNames() const;
std::vector<std::string> getInputVariableNames() const;
std::vector<std::string> getOutputVariableNames() const;
std::vector<std::string> getParameterNames() const;
void setInputValue(fmi2_import_variable_t * variable, const rclcpp::Time & time, double value);
void setInputValue(const std::string & variableName, const rclcpp::Time & time, double value);
rclcpp::Duration getStepSize() const {return stepSize_;}
bool isInInitializationMode() const {return inInitializationMode_;}
void exitInitializationMode(const rclcpp::Time & simulationTime);
rclcpp::Time doStep();
rclcpp::Time doStep(const rclcpp::Duration & stepSize);
rclcpp::Time doStepsUntil(const rclcpp::Time & simulationTime);
rclcpp::Time getSimulationTime() const;
double getOutputValue(fmi2_import_variable_t * variable) const;
double getOutputValue(const std::string & variableName) const;
double getValue(fmi2_import_variable_t * variable) const;
double getValue(const std::string & variableName) const;
void setInitialValue(fmi2_import_variable_t * variable, double value);
void setInitialValue(const std::string & variableName, double value);
void declareROSParameters(
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr nodeInterface);
void initializeFromROSParameters(
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr nodeInterface);
private:
rclcpp::Logger logger_;
const std::string fmuPath_;
rclcpp::Duration stepSize_;
bool interpolateInput_;
std::string tmpPath_;
bool removeTmpPathInDtor_{false};
bool inInitializationMode_{true};
rclcpp::Duration fmuTimeOffset_{internal::ZERO_DURATION};
double fmuTime_{0.0};
rclcpp::Time simulationTime_{0, 0, RCL_ROS_TIME};
fmi2_import_t * fmu_{nullptr};
fmi_import_context_t * context_{nullptr};
void * fmiCallbacks_{nullptr};
jm_callbacks * jmCallbacks_{nullptr};
std::map<fmi2_import_variable_t *, std::map<rclcpp::Time, double>> inputValuesByVariable_{};
void doStepInternal(const rclcpp::Duration & stepSize);
rclcpp::Time getSimulationTimeInternal() const
{
return rclcpp::Time(static_cast<uint64_t>(fmuTime_ * 1000000000.0), RCL_ROS_TIME) +
fmuTimeOffset_;
}
};
} // namespace fmi_adapter
#endif // FMI_ADAPTER__FMIADAPTER_HPP_