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 
31 
32 #include <pilz_testutils/async_test.h>
33 
34 namespace prbt_hardware_support
35 {
36 static constexpr unsigned int MODBUS_API_VERSION_REQUIRED{2};
37 
40 
43 
44 using std::placeholders::_1;
45 using std::placeholders::_2;
46 
47 using ::testing::_;
48 using ::testing::Return;
49 using ::testing::DoAll;
50 using ::testing::SetArgReferee;
51 
53 {
54 public:
55  MOCK_METHOD2(modbsWriteRegisterFunc, bool(const uint16_t&, const RegCont&));
56 };
57 
58 static ModbusMsgInStampedPtr createDefaultBrakeTestModbusMsg(
59  const uint16_t brake_test_required_value,
60  const unsigned int modbus_api_version = MODBUS_API_VERSION_REQUIRED,
61  const uint32_t brake_test_required_index = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::BRAKETEST_REQUEST)
62  )
63 {
64  const uint32_t first_index_to_read{TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::VERSION)};
65  const uint32_t last_index_to_read{brake_test_required_index};
66  static int msg_time_counter{1};
67  RegCont tab_reg(last_index_to_read - first_index_to_read + 1);
68  tab_reg[0] = static_cast<uint16_t>(modbus_api_version);
69  tab_reg[last_index_to_read - first_index_to_read] = brake_test_required_value;
70  ModbusMsgInStampedPtr msg{ModbusMsgInBuilder::createDefaultModbusMsgIn(first_index_to_read, tab_reg)};
71  msg->header.stamp = ros::Time(msg_time_counter++);
72  return msg;
73 }
74 
79 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperExceptionDtor)
80 {
81  std::shared_ptr<ModbusMsgBrakeTestWrapperException> msg_wrapper{new ModbusMsgBrakeTestWrapperException("Test msg")};
82 }
83 
88 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperDtor)
89 {
90  {
91  std::shared_ptr<ModbusMsgBrakeTestWrapper> msg_wrapper{
93  }
94 }
95 
107 TEST(ModbusAdapterBrakeTestTest, testNoMessageReceived)
108 {
109  ModbusMock mock;
110  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
112 
113 
114  prbt_hardware_support::IsBrakeTestRequired srv;
115  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
116  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
117 }
118 
131 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequired)
132 {
133  ModbusMock mock;
134  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
136 
138 
139  prbt_hardware_support::IsBrakeTestRequired srv;
140  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
141  EXPECT_EQ(IsBrakeTestRequiredResponse::REQUIRED, srv.response.result);
142 }
143 
156 TEST(ModbusAdapterBrakeTestTest, testBrakeTestNotRequired)
157 {
158  ModbusMock mock;
159  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
161 
163 
164  prbt_hardware_support::IsBrakeTestRequired srv;
165  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
166  EXPECT_EQ(IsBrakeTestRequiredResponse::NOT_REQUIRED, srv.response.result);
167 }
168 
181 TEST(ModbusAdapterBrakeTestTest, testDisconnect)
182 {
183  constexpr uint32_t offset{0};
184  const RegCont holding_register;
185  ModbusMsgInStampedPtr msg{ModbusMsgInBuilder::createDefaultModbusMsgIn(offset, holding_register)};
186  msg->disconnect.data = true;
187 
188  ModbusMock mock;
189  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
191 
192  brake_test_adapter.modbusMsgCallback(msg);
193 
194  prbt_hardware_support::IsBrakeTestRequired srv;
195  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
196  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
197 }
198 
211 TEST(ModbusAdapterBrakeTestTest, testModbusIncorrectApiVersion)
212 {
213  ModbusMock mock;
214  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
216 
218 
219  prbt_hardware_support::IsBrakeTestRequired srv;
220  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
221  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
222 }
223 
235 TEST(ModbusAdapterBrakeTestTest, testModbusWithoutApiVersion)
236 {
240  msg->holding_registers.data.clear();
241 
242  ModbusMock mock;
243  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
245 
246  brake_test_adapter.modbusMsgCallback(msg);
247 
248  prbt_hardware_support::IsBrakeTestRequired srv;
249  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
250  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
251 }
252 
265 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterMissing)
266 {
267  ModbusMock mock;
268  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
270 
274 
275  prbt_hardware_support::IsBrakeTestRequired srv;
276  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
277  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
278 }
279 
291 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterUndefinedValue)
292 {
293  ModbusMock mock;
294  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
296 
297  brake_test_adapter.modbusMsgCallback(createDefaultBrakeTestModbusMsg(555 /* some arbitrary value */));
298 
299  prbt_hardware_support::IsBrakeTestRequired srv;
300  EXPECT_TRUE(brake_test_adapter.isBrakeTestRequired(srv.request, srv.response));
301  EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
302 }
303 
308 TEST(ModbusAdapterBrakeTestTest, testModbusApiSpecExceptionDtor)
309 {
310  std::shared_ptr<ModbusAdapterBrakeTestException> ex {new ModbusAdapterBrakeTestException("Test msg")};
311 }
312 
329 TEST(ModbusAdapterBrakeTestTest, testBrakeTestTriggeringWrongApiDef)
330 {
331  /**********
332  * Step 1 *
333  **********/
334  {
335  ModbusApiSpec api_write_spec { {modbus_api_spec::BRAKETEST_RESULT, 78} };
336  ModbusMock mock;
337  ASSERT_THROW(ModbusAdapterBrakeTest bte_no_perf(
338  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
340  }
341 
342  /**********
343  * Step 2 *
344  **********/
345  {
346  ModbusApiSpec api_write_spec{ {modbus_api_spec::BRAKETEST_PERFORMED, 77} };
347  ModbusMock mock;
348  ASSERT_THROW(ModbusAdapterBrakeTest bte_no_res(
349  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
351  }
352 
353  /**********
354  * Step 3 *
355  **********/
356  {
359  ModbusMock mock;
360  ASSERT_NO_THROW(ModbusAdapterBrakeTest bte_one_apart(
361  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
362  TEST_API_SPEC, api_write_spec));
363  }
364 
365  /**********
366  * Step 4 *
367  **********/
368  {
371  ModbusMock mock;
372  ASSERT_THROW(ModbusAdapterBrakeTest bte_two_apart(
373  std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
375  }
376 
377 }
378 
383 TEST(ModbusAdapterBrakeTestTest, testMissingModbusWriteFunc)
384 {
385  ModbusMock mock;
386  ModbusAdapterBrakeTest brake_test_adapter(nullptr,
388 
389  SendBrakeTestResult srv;
390  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
391  EXPECT_FALSE(srv.response.success);
392 }
393 
398 TEST(ModbusAdapterBrakeTestTest, testFailingModbusWriteFunc)
399 {
400  ModbusMock mock;
401  EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(1).WillOnce(Return(false));
402  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
404 
405  SendBrakeTestResult srv;
406  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
407  EXPECT_FALSE(srv.response.success);
408 }
409 
414 TEST(ModbusAdapterBrakeTestTest, testSecondTimeFailingModbusWriteFunc)
415 {
416  ModbusMock mock;
417  EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(2).WillOnce(Return(true)).WillOnce(Return(false));
418  ModbusAdapterBrakeTest brake_test_adapter(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
420 
421  SendBrakeTestResult srv;
422  EXPECT_TRUE(brake_test_adapter.sendBrakeTestResult(srv.request, srv.response));
423  EXPECT_FALSE(srv.response.success);
424 }
425 
427 {
428 public:
429  MOCK_METHOD1(call, bool(WriteModbusRegister& srv));
430  MOCK_METHOD0(getService, std::string());
431 };
432 
436 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallResponseFalse)
437 {
438  WriteModbusRegister res_exp;
439  res_exp.response.success = false;
440 
441  ServiceMock mock;
442  EXPECT_CALL(mock, getService()).WillRepeatedly(Return("TestServiceName"));
443  EXPECT_CALL(mock, call(_)).Times(1).WillOnce(DoAll(SetArgReferee<0>(res_exp), Return(true)));
444 
445  EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
446 }
447 
451 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallFailure)
452 {
453  WriteModbusRegister res_exp;
454  res_exp.response.success = false;
455 
456  ServiceMock mock;
457  EXPECT_CALL(mock, getService()).WillRepeatedly(Return("TestServiceName"));
458  EXPECT_CALL(mock, call(_)).Times(1).WillOnce(Return(false));
459 
460  EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
461 }
462 
463 } // namespace prbt_hardware_support
464 
465 int main(int argc, char *argv[])
466 {
467  testing::InitGoogleMock(&argc, argv);
468  return RUN_ALL_TESTS();
469 }
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.
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
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED
bool isBrakeTestRequired(IsBrakeTestRequired::Request &, IsBrakeTestRequired::Response &res)
Stores the brake test required flag and initializes the brake test service, the first time the functi...
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.
unsigned short getRegisterDefinition(const std::string &key) const
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 Tue Feb 2 2021 03:50:17