18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 32 #include <pilz_testutils/async_test.h> 44 using std::placeholders::_1;
45 using std::placeholders::_2;
48 using ::testing::Return;
49 using ::testing::DoAll;
50 using ::testing::SetArgReferee;
59 const uint16_t brake_test_required_value,
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;
79 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperExceptionDtor)
88 TEST(ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperDtor)
91 std::shared_ptr<ModbusMsgBrakeTestWrapper> msg_wrapper{
107 TEST(ModbusAdapterBrakeTestTest, testNoMessageReceived)
114 prbt_hardware_support::IsBrakeTestRequired srv;
116 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
131 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequired)
139 prbt_hardware_support::IsBrakeTestRequired srv;
141 EXPECT_EQ(IsBrakeTestRequiredResponse::REQUIRED, srv.response.result);
156 TEST(ModbusAdapterBrakeTestTest, testBrakeTestNotRequired)
164 prbt_hardware_support::IsBrakeTestRequired srv;
166 EXPECT_EQ(IsBrakeTestRequiredResponse::NOT_REQUIRED, srv.response.result);
181 TEST(ModbusAdapterBrakeTestTest, testDisconnect)
183 constexpr uint32_t offset{0};
184 const RegCont holding_register;
186 msg->disconnect.data =
true;
194 prbt_hardware_support::IsBrakeTestRequired srv;
196 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
211 TEST(ModbusAdapterBrakeTestTest, testModbusIncorrectApiVersion)
219 prbt_hardware_support::IsBrakeTestRequired srv;
221 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
235 TEST(ModbusAdapterBrakeTestTest, testModbusWithoutApiVersion)
240 msg->holding_registers.data.clear();
248 prbt_hardware_support::IsBrakeTestRequired srv;
250 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
265 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterMissing)
275 prbt_hardware_support::IsBrakeTestRequired srv;
277 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
291 TEST(ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterUndefinedValue)
299 prbt_hardware_support::IsBrakeTestRequired srv;
301 EXPECT_EQ(IsBrakeTestRequiredResponse::UNKNOWN, srv.response.result);
308 TEST(ModbusAdapterBrakeTestTest, testModbusApiSpecExceptionDtor)
329 TEST(ModbusAdapterBrakeTestTest, testBrakeTestTriggeringWrongApiDef)
338 std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
349 std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
361 std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
373 std::bind(&ModbusMock::modbsWriteRegisterFunc, &mock, _1, _2),
383 TEST(ModbusAdapterBrakeTestTest, testMissingModbusWriteFunc)
389 SendBrakeTestResult srv;
391 EXPECT_FALSE(srv.response.success);
398 TEST(ModbusAdapterBrakeTestTest, testFailingModbusWriteFunc)
401 EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(1).WillOnce(Return(
false));
405 SendBrakeTestResult srv;
407 EXPECT_FALSE(srv.response.success);
414 TEST(ModbusAdapterBrakeTestTest, testSecondTimeFailingModbusWriteFunc)
417 EXPECT_CALL(mock, modbsWriteRegisterFunc(_,_)).Times(2).WillOnce(Return(
true)).WillOnce(Return(
false));
421 SendBrakeTestResult srv;
423 EXPECT_FALSE(srv.response.success);
429 MOCK_METHOD1(
call,
bool(WriteModbusRegister& srv));
430 MOCK_METHOD0(getService, std::string());
436 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallResponseFalse)
438 WriteModbusRegister res_exp;
439 res_exp.response.success =
false;
442 EXPECT_CALL(mock, getService()).WillRepeatedly(Return(
"TestServiceName"));
443 EXPECT_CALL(mock,
call(_)).Times(1).WillOnce(DoAll(SetArgReferee<0>(res_exp), Return(
true)));
445 EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
451 TEST(ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallFailure)
453 WriteModbusRegister res_exp;
454 res_exp.response.success =
false;
457 EXPECT_CALL(mock, getService()).WillRepeatedly(Return(
"TestServiceName"));
458 EXPECT_CALL(mock,
call(_)).Times(1).WillOnce(Return(
false));
460 EXPECT_FALSE(writeModbusRegisterCall<ServiceMock>(mock, 0, {}));
465 int main(
int argc,
char *argv[])
467 testing::InitGoogleMock(&argc, argv);
468 return RUN_ALL_TESTS();
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.
static const std::string VERSION