19 #include <gtest/gtest.h> 28 const double EPSILON = 0.01;
31 class FMIAdapterTest :
public ::testing::Test {
33 FMIAdapterTest() : handle_(
"~") {
35 while (!handle_.getParam(
"test_fmus_path", test_FMUs_path_)) {
39 ROS_ERROR(
"Parameter 'test_fmus_path' not specified!");
40 throw std::runtime_error(
"Parameter 'test_fmus_path' not specified!");
48 std::string test_FMUs_path_ =
"";
57 TEST_F(FMIAdapterTest, ctorWithImplicitDefaultExperimentStepSize) {
63 TEST_F(FMIAdapterTest, ctorWithExplicitDefaultExperimentStepSize) {
69 TEST_F(FMIAdapterTest, ctorWithExplicitStepSize) {
75 TEST_F(FMIAdapterTest, canHandleVariableCommunicationStepSize) {
77 EXPECT_FALSE(wrapper.canHandleVariableCommunicationStepSize());
81 TEST_F(FMIAdapterTest, getDefaultExperimentStep) {
83 EXPECT_EQ(wrapper.getDefaultExperimentStep(),
ros::Duration(0.001));
87 TEST_F(FMIAdapterTest, getAllVariableNames) {
90 std::vector<std::string> expectedNames = {
"x",
"y",
"d"};
91 std::vector<std::string> actualNames = wrapper.getAllVariableNames();
92 EXPECT_EQ(expectedNames, actualNames);
96 TEST_F(FMIAdapterTest, doStepsUntil_withInterpolation) {
100 wrapper.setInitialValue(
"x", 2.0);
102 wrapper.exitInitializationMode(startTime);
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);
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);
121 TEST_F(FMIAdapterTest, doStepsUntil_withoutInterpolation) {
125 wrapper.setInitialValue(
"x", 2.0);
127 wrapper.exitInitializationMode(startTime);
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);
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);
146 TEST_F(FMIAdapterTest, doStepsUntil_interpolationAfterExtrapolation) {
150 wrapper.setInitialValue(
"x", 2.0);
152 wrapper.exitInitializationMode(startTime);
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);
TEST_F(XmlRpcTest, Introspection)