FMIAdapterTest.cpp
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 #include <string>
17 #include <vector>
18 
19 #include <gtest/gtest.h>
20 
21 #include <ros/ros.h>
22 
23 #include "fmi_adapter/FMIAdapter.h"
24 
25 
26 namespace {
27 
28 const double EPSILON = 0.01;
29 
30 
31 class FMIAdapterTest : public ::testing::Test {
32  public:
33  FMIAdapterTest() : handle_("~") {
34  int trials = 0;
35  while (!handle_.getParam("test_fmus_path", test_FMUs_path_)) {
36  // roslaunch may require some time until parameter is set ...
37  ++trials;
38  if (trials > 10) {
39  ROS_ERROR("Parameter 'test_fmus_path' not specified!");
40  throw std::runtime_error("Parameter 'test_fmus_path' not specified!");
41  }
42  ros::Duration(0.1).sleep();
43  }
44  }
45 
46  ros::NodeHandle handle_;
47 
48  std::string test_FMUs_path_ = "";
49 };
50 
51 
52 // The FMU TransportDelay.fmu is built for x86-64 (AMD64). Therefore, run unit
53 // tests on this architecture only.
54 #ifdef __x86_64__
55 
56 
57 TEST_F(FMIAdapterTest, ctorWithImplicitDefaultExperimentStepSize) {
58  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
59  EXPECT_EQ(wrapper.getStepSize(), ros::Duration(0.001));
60 }
61 
62 
63 TEST_F(FMIAdapterTest, ctorWithExplicitDefaultExperimentStepSize) {
64  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu", ros::Duration(0.0));
65  EXPECT_EQ(wrapper.getStepSize(), ros::Duration(0.001));
66 }
67 
68 
69 TEST_F(FMIAdapterTest, ctorWithExplicitStepSize) {
70  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu", ros::Duration(0.004));
71  EXPECT_EQ(wrapper.getStepSize(), ros::Duration(0.004));
72 }
73 
74 
75 TEST_F(FMIAdapterTest, canHandleVariableCommunicationStepSize) {
76  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
77  EXPECT_FALSE(wrapper.canHandleVariableCommunicationStepSize());
78 }
79 
80 
81 TEST_F(FMIAdapterTest, getDefaultExperimentStep) {
82  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
83  EXPECT_EQ(wrapper.getDefaultExperimentStep(), ros::Duration(0.001));
84 }
85 
86 
87 TEST_F(FMIAdapterTest, getAllVariableNames) {
88  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
89  wrapper.exitInitializationMode(ros::Time::now());
90  std::vector<std::string> expectedNames = {"x", "y", "d"};
91  std::vector<std::string> actualNames = wrapper.getAllVariableNames();
92  EXPECT_EQ(expectedNames, actualNames);
93 }
94 
95 
96 TEST_F(FMIAdapterTest, doStepsUntil_withInterpolation) {
97  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
98  const ros::Duration DELAY(2.0);
99 
100  wrapper.setInitialValue("x", 2.0);
101  const ros::Time startTime = ros::Time::now();
102  wrapper.exitInitializationMode(startTime);
103 
104  wrapper.setInputValue("x", startTime + ros::Duration(4.0), 2.0);
105  wrapper.setInputValue("x", startTime + ros::Duration(7.0), 3.0);
106  wrapper.setInputValue("x", startTime + ros::Duration(9.0), -1.0);
107 
108  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(0.5));
109  EXPECT_NEAR(2.0, wrapper.getOutputValue("y"), EPSILON);
110  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(4.5));
111  EXPECT_NEAR(2.167, wrapper.getOutputValue("y"), EPSILON);
112  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(7.0));
113  EXPECT_NEAR(3.0, wrapper.getOutputValue("y"), EPSILON);
114  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(8.5));
115  EXPECT_NEAR(0.0, wrapper.getOutputValue("y"), EPSILON);
116  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(9.5));
117  EXPECT_NEAR(-1.0, wrapper.getOutputValue("y"), EPSILON);
118 }
119 
120 
121 TEST_F(FMIAdapterTest, doStepsUntil_withoutInterpolation) {
122  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu", ros::Duration(0.001), false);
123  const ros::Duration DELAY(2.0);
124 
125  wrapper.setInitialValue("x", 2.0);
126  const ros::Time startTime = ros::Time::now();
127  wrapper.exitInitializationMode(startTime);
128 
129  wrapper.setInputValue("x", startTime + ros::Duration(4.0), 2.0);
130  wrapper.setInputValue("x", startTime + ros::Duration(7.0), 3.0);
131  wrapper.setInputValue("x", startTime + ros::Duration(9.0), -1.0);
132 
133  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(0.5));
134  EXPECT_NEAR(2.0, wrapper.getOutputValue("y"), EPSILON);
135  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(4.5));
136  EXPECT_NEAR(2.0, wrapper.getOutputValue("y"), EPSILON);
137  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(7.1));
138  EXPECT_NEAR(3.0, wrapper.getOutputValue("y"), EPSILON);
139  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(8.5));
140  EXPECT_NEAR(3.0, wrapper.getOutputValue("y"), EPSILON);
141  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(9.5));
142  EXPECT_NEAR(-1.0, wrapper.getOutputValue("y"), EPSILON);
143 }
144 
145 
146 TEST_F(FMIAdapterTest, doStepsUntil_interpolationAfterExtrapolation) {
147  fmi_adapter::FMIAdapter wrapper(test_FMUs_path_ + "TransportDelay.fmu");
148  const ros::Duration DELAY(2.0);
149 
150  wrapper.setInitialValue("x", 2.0);
151  const ros::Time startTime = ros::Time::now();
152  wrapper.exitInitializationMode(startTime);
153 
154  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(1.0));
155  EXPECT_NEAR(2.0, wrapper.getOutputValue("y"), EPSILON);
156  wrapper.setInputValue("x", startTime + ros::Duration(4.0), 1.0);
157  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(2.9));
158  EXPECT_NEAR(2.0, wrapper.getOutputValue("y"), EPSILON);
159  wrapper.doStepsUntil(startTime + DELAY + ros::Duration(3.5));
160  EXPECT_NEAR(1.125, wrapper.getOutputValue("y"), EPSILON);
161 }
162 
163 
164 #endif // __x86_64__
165 
166 
167 } // namespace
TEST_F(XmlRpcTest, Introspection)
static Time now()
bool sleep() const
#define ROS_ERROR(...)


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