unittest_modbus_adapter_brake_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <gtest/gtest.h>
19 #include <gmock/gmock.h>
20 #include <functional>
21 #include <memory>
22 
23 #include <pilz_msgs/IsBrakeTestRequired.h>
24 #include <pilz_msgs/IsBrakeTestRequiredResult.h>
25 
34 
35 #include <pilz_testutils/async_test.h>
36 
37 namespace prbt_hardware_support
38 {
39 static constexpr unsigned int MODBUS_API_VERSION_REQUIRED{2};
40 
43 
46 
47 using std::placeholders::_1;
48 using std::placeholders::_2;
49 
50 using ::testing::_;
51 using ::testing::Return;
52 using ::testing::DoAll;
53 using ::testing::SetArgReferee;
54 
56 {
57 public:
58  MOCK_METHOD2(modbsWriteRegisterFunc, bool(const uint16_t&, const RegCont&));
59 };
60 
61 static ModbusMsgInStampedPtr createDefaultBrakeTestModbusMsg(
62  const uint16_t brake_test_required_value,
63  const unsigned int modbus_api_version = MODBUS_API_VERSION_REQUIRED,
64  const uint32_t brake_test_required_index = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::BRAKETEST_REQUEST)
65  )
66 {
67  const uint32_t first_index_to_read{TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::VERSION)};
68  const uint32_t last_index_to_read{brake_test_required_index};
69  static int msg_time_counter{1};
70  RegCont tab_reg(last_index_to_read - first_index_to_read + 1);
71  tab_reg[0] = static_cast<uint16_t>(modbus_api_version);
72  tab_reg[last_index_to_read - first_index_to_read] = brake_test_required_value;
73  ModbusMsgInStampedPtr msg{ModbusMsgInBuilder::createDefaultModbusMsgIn(first_index_to_read, tab_reg)};
74  msg->header.stamp = ros::Time(msg_time_counter++);
75  return msg;
76 }
77 
82 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperExceptionDtor)
83 {
84  std::shared_ptr<ModbusMsgBrakeTestWrapperException> msg_wrapper{new ModbusMsgBrakeTestWrapperException("Test msg")};
85 }
86 
91 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperDtor)
92 {
93  {
94  std::shared_ptr<ModbusMsgBrakeTestWrapper> msg_wrapper{
96  }
97 }
98 
110 TEST(ModbusAdapterBrakeTestTest, testNoMessageReceived)
111 {
112  ModbusMock mock;
113  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
115 
116 
117  pilz_msgs::IsBrakeTestRequired srv;
118  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
119  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
120 }
121 
134 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequired)
135 {
136  ModbusMock mock;
137  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
139 
141 
142  pilz_msgs::IsBrakeTestRequired srv;
143  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
144  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::REQUIRED, srv.response.result.value);
145 }
146 
159 TEST(ModbusAdapterBrakeTestTest, testBrakeTestNotRequired)
160 {
161  ModbusMock mock;
162  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
164 
166 
167  pilz_msgs::IsBrakeTestRequired srv;
168  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
169  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::NOT_REQUIRED, srv.response.result.value);
170 }
171 
184 TEST(ModbusAdapterBrakeTestTest, testDisconnect)
185 {
186  constexpr uint32_t offset{0};
187  const RegCont holding_register;
188  ModbusMsgInStampedPtr msg{ModbusMsgInBuilder::createDefaultModbusMsgIn(offset, holding_register)};
189  msg->disconnect.data = true;
190 
191  ModbusMock mock;
192  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
194 
195  brake_test_adapter.modbusMsgCallback(msg);
196 
197  pilz_msgs::IsBrakeTestRequired srv;
198  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
199  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
200 }
201 
214 TEST(ModbusAdapterBrakeTestTest, testModbusIncorrectApiVersion)
215 {
216  ModbusMock mock;
217  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
219 
221 
222  pilz_msgs::IsBrakeTestRequired srv;
223  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
224  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
225 }
226 
238 TEST(ModbusAdapterBrakeTestTest, testModbusWithoutApiVersion)
239 {
243  msg->holding_registers.data.clear();
244 
245  ModbusMock mock;
246  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
248 
249  brake_test_adapter.modbusMsgCallback(msg);
250 
251  pilz_msgs::IsBrakeTestRequired srv;
252  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
253  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
254 }
255 
268 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterMissing)
269 {
270  ModbusMock mock;
271  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
273 
277 
278  pilz_msgs::IsBrakeTestRequired srv;
279  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
280  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
281 }
282 
294 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterUndefinedValue)
295 {
296  ModbusMock mock;
297  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
299 
300  brake_test_adapter.modbusMsgCallback(createDefaultBrakeTestModbusMsg(555 /* some arbitrary value */));
301 
302  pilz_msgs::IsBrakeTestRequired srv;
303  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
304  EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
305 }
306 
311 TEST(ModbusAdapterBrakeTestTest, testModbusApiSpecExceptionDtor)
312 {
313  std::shared_ptr<ModbusAdapterBrakeTestException> ex {new ModbusAdapterBrakeTestException("Test msg")};
314 }
315 
332 TEST(ModbusAdapterBrakeTestTest, testBrakeTestTriggeringWrongApiDef)
333 {
334  /**********
335  * Step 1 *
336  **********/
337  {
338  ModbusApiSpec api_write_spec { {modbus_api_spec::BRAKETEST_RESULT, 78} };
339  ModbusMock mock;
340  ASSERT_THROW(ModbusAdapterBrakeTest bte_no_perf(
341  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
343  }
344 
345  /**********
346  * Step 2 *
347  **********/
348  {
349  ModbusApiSpec api_write_spec{ {modbus_api_spec::BRAKETEST_PERFORMED, 77} };
350  ModbusMock mock;
351  ASSERT_THROW(ModbusAdapterBrakeTest bte_no_res(
352  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
354  }
355 
356  /**********
357  * Step 3 *
358  **********/
359  {
362  ModbusMock mock;
363  ASSERT_NO_THROW(ModbusAdapterBrakeTest bte_one_apart(
364  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
365  TEST_API_SPEC, api_write_spec));
366  }
367 
368  /**********
369  * Step 4 *
370  **********/
371  {
374  ModbusMock mock;
375  ASSERT_THROW(ModbusAdapterBrakeTest bte_two_apart(
376  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
378  }
379 
380 }
381 
386 TEST(ModbusAdapterBrakeTestTest, testMissingModbusWriteFunc)
387 {
388  ModbusMock mock;
389  ModbusAdapterBrakeTest brake_test_adapter(nullptr,
391 
392  SendBrakeTestResult srv;
393  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
394  EXPECT_FALSE(srv.response.success);
395 }
396 
401 TEST(ModbusAdapterBrakeTestTest, testFailingModbusWriteFunc)
402 {
403  ModbusMock mock;
404  EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(1).WillOnce(Return(false));
405  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
407 
408  SendBrakeTestResult srv;
409  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
410  EXPECT_FALSE(srv.response.success);
411 }
412 
417 TEST(ModbusAdapterBrakeTestTest, testSecondTimeFailingModbusWriteFunc)
418 {
419  ModbusMock mock;
420  EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(2).WillOnce(Return(true)).WillOnce(Return(false));
421  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
423 
424  SendBrakeTestResult srv;
425  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
426  EXPECT_FALSE(srv.response.success);
427 }
428 
430 {
431 public:
432  MOCK_METHOD1(call, bool(WriteModbusRegister& srv));
433  MOCK_METHOD0(getService, std::string());
434 };
435 
439 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallResponseFalse)
440 {
441  WriteModbusRegister res_exp;
442  res_exp.response.success = false;
443 
444  ServiceMock mock;
445  EXPECT_CALL(mock, getService()).WillRepeatedly(Return("TestServiceName"));
446  EXPECT_CALL(mock, call(_)).Times(1).WillOnce(DoAll(SetArgReferee<0>(res_exp), Return(true)));
447 
448  EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
449 }
450 
454 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallFailure)
455 {
456  WriteModbusRegister res_exp;
457  res_exp.response.success = false;
458 
459  ServiceMock mock;
460  EXPECT_CALL(mock, getService()).WillRepeatedly(Return("TestServiceName"));
461  EXPECT_CALL(mock, call(_)).Times(1).WillOnce(Return(false));
462 
463  EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
464 }
465 
466 } // namespace prbt_hardware_support
467 
468 int main(int argc, char *argv[])
469 {
470  testing::InitGoogleMock(&argc, argv);
471  return RUN_ALL_TESTS();
472 }
msg
static const std::string BRAKETEST_PERFORMED
static const std::string BRAKETEST_REQUEST
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
unsigned short getRegisterDefinition(const std::string &key) const
static const std::string BRAKETEST_RESULT
static const ModbusApiSpec TEST_API_WRITE_SPEC
MOCK_METHOD2(modbsWriteRegisterFunc, bool(const uint16_t &, const RegCont &))
static constexpr uint16_t REGISTER_VALUE_BRAKETEST_NOT_REQUIRED
bool call(const std::string &service_name, MReq &req, MRes &res)
int main(int argc, char *argv[])
Expection thrown upon construction of ModbusMsgBrakeTestWrapper of the message does not contain the r...
static const ModbusApiSpec TEST_API_SPEC
Exception thrown by the ModbusAdapterBrakeTest class.
bool sendBrakeTestResult(SendBrakeTestResult::Request &req, SendBrakeTestResult::Response &res)
Sends the brake test result data to the modbus client.
static ModbusMsgInStampedPtr createDefaultModbusMsgIn(const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont &holding_register)
Creates a standard ModbusMsgIn which contains default values for all essential elements of the messag...
static constexpr uint16_t REGISTER_VALUE_BRAKETEST_REQUIRED
bool isBrakeTestRequired(pilz_msgs::IsBrakeTestRequired::Request &, pilz_msgs::IsBrakeTestRequired::Response &res)
Stores the brake test required flag and initializes the brake test service, the first time the functi...
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED
static ModbusMsgInStampedPtr createDefaultBrakeTestModbusMsg(const uint16_t brake_test_required_value, const unsigned int modbus_api_version=MODBUS_API_VERSION_REQUIRED, const uint32_t brake_test_required_index=TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::BRAKETEST_REQUEST))
Wrapper class to add semantic to a raw ModbusMsgInStamped.
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus message arrives.
TEST(IntegrationtestExecuteBrakeTest, testBrakeTestService)
Listens to the modbus_read topic and publishes a message informing about a required brake test...
Specifies the meaning of the holding registers.


prbt_hardware_support
Author(s):
autogenerated on Thu Feb 13 2020 03:16:51