18 #include <gtest/gtest.h>
19 #include <gmock/gmock.h>
23 #include <pilz_msgs/IsBrakeTestRequired.h>
24 #include <pilz_msgs/IsBrakeTestRequiredResult.h>
36 #include <pilz_testutils/async_test.h>
40 using namespace modbus_api::v3;
48 using std::placeholders::_1;
49 using std::placeholders::_2;
52 using ::testing::DoAll;
53 using ::testing::Return;
54 using ::testing::SetArgReferee;
59 MOCK_METHOD2(modbsWriteRegisterFunc,
bool(
const uint16_t&,
const RegCont&));
67 const uint32_t last_index_to_read{ brake_test_required_index };
68 static int msg_time_counter{ 1 };
69 RegCont tab_reg(last_index_to_read - first_index_to_read + 1);
70 tab_reg[0] =
static_cast<uint16_t
>(modbus_api_version);
71 tab_reg[last_index_to_read - first_index_to_read] = brake_test_required_value;
81 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperExceptionDtor)
90 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperDtor)
109 TEST(ModbusAdapterBrakeTestTest, testNoMessageReceived)
115 pilz_msgs::IsBrakeTestRequired srv;
117 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
132 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequired)
140 pilz_msgs::IsBrakeTestRequired srv;
142 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::REQUIRED, srv.response.result.value);
157 TEST(ModbusAdapterBrakeTestTest, testBrakeTestNotRequired)
165 pilz_msgs::IsBrakeTestRequired srv;
167 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::NOT_REQUIRED, srv.response.result.value);
182 TEST(ModbusAdapterBrakeTestTest, testDisconnect)
184 constexpr uint32_t offset{ 0 };
185 const RegCont holding_register;
187 msg->disconnect.data =
true;
195 pilz_msgs::IsBrakeTestRequired srv;
197 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
212 TEST(ModbusAdapterBrakeTestTest, testModbusIncorrectApiVersion)
220 pilz_msgs::IsBrakeTestRequired srv;
222 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
236 TEST(ModbusAdapterBrakeTestTest, testModbusWithoutApiVersion)
241 msg->holding_registers.data.clear();
249 pilz_msgs::IsBrakeTestRequired srv;
251 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
266 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterMissing)
276 pilz_msgs::IsBrakeTestRequired srv;
278 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
292 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterUndefinedValue)
300 pilz_msgs::IsBrakeTestRequired srv;
302 EXPECT_EQ(pilz_msgs::IsBrakeTestRequiredResult::UNKNOWN, srv.response.result.value);
309 TEST(ModbusAdapterBrakeTestTest, testModbusApiSpecExceptionDtor)
330 TEST(ModbusAdapterBrakeTestTest, testBrakeTestTriggeringWrongApiDef)
338 ASSERT_THROW(
ModbusAdapterBrakeTest bte_no_perf(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
349 ASSERT_THROW(
ModbusAdapterBrakeTest bte_no_res(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
361 ASSERT_NO_THROW(
ModbusAdapterBrakeTest bte_one_apart(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
372 ASSERT_THROW(
ModbusAdapterBrakeTest bte_two_apart(std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
382 TEST(ModbusAdapterBrakeTestTest, testMissingModbusWriteFunc)
387 SendBrakeTestResult srv;
389 EXPECT_FALSE(srv.response.success);
396 TEST(ModbusAdapterBrakeTestTest, testFailingModbusWriteFunc)
399 EXPECT_CALL(mock, modbsWriteRegisterFunc(_, _)).Times(1).WillOnce(Return(
false));
403 SendBrakeTestResult srv;
405 EXPECT_FALSE(srv.response.success);
412 TEST(ModbusAdapterBrakeTestTest, testSecondTimeFailingModbusWriteFunc)
415 EXPECT_CALL(mock, modbsWriteRegisterFunc(_, _)).Times(2).WillOnce(Return(
true)).WillOnce(Return(
false));
419 SendBrakeTestResult srv;
421 EXPECT_FALSE(srv.response.success);
427 MOCK_METHOD1(
call,
bool(WriteModbusRegister& srv));
428 MOCK_METHOD0(getService, std::string());
434 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallResponseFalse)
436 WriteModbusRegister res_exp;
437 res_exp.response.success =
false;
440 EXPECT_CALL(mock, getService()).WillRepeatedly(Return(
"TestServiceName"));
441 EXPECT_CALL(mock,
call(_)).Times(1).WillOnce(DoAll(SetArgReferee<0>(res_exp), Return(
true)));
443 EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
449 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallFailure)
451 WriteModbusRegister res_exp;
452 res_exp.response.success =
false;
455 EXPECT_CALL(mock, getService()).WillRepeatedly(Return(
"TestServiceName"));
456 EXPECT_CALL(mock,
call(_)).Times(1).WillOnce(Return(
false));
458 EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
463 int main(
int argc,
char* argv[])
465 testing::InitGoogleMock(&argc, argv);
466 return RUN_ALL_TESTS();