18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 23 #include <pilz_msgs/OperationModes.h> 25 #include <pilz_testutils/async_test.h> 35 using namespace modbus_api::v3;
59 MOCK_METHOD1(callback,
void(
const pilz_msgs::OperationModesConstPtr&
msg));
72 using ::testing::StrictMock;
151 std::shared_ptr<ModbusMsgOperationModeWrapper> wrapper(
155 MATCHER_P(IsExpectedOperationMode, exp_mode,
"unexpected operation mode")
157 return arg->value == exp_mode;
167 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
170 subscriber_.initialize();
174 GetOperationMode srv;
175 ASSERT_TRUE(operation_mode_client_.call(srv));
176 EXPECT_EQ(OperationModes::UNKNOWN, srv.response.mode.value);
201 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
204 subscriber_.initialize();
211 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
225 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
234 <<
"For the test to work correctly, the operation mode register has to be stored in the last register.";
235 msg->holding_registers.data.erase(--
msg->holding_registers.data.end());
237 msg->holding_registers.layout.data_offset = new_offset;
239 static_cast<uint32_t>(
msg->holding_registers.data.size()));
241 modbus_topic_pub_.publish(
msg);
267 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
270 subscriber_.initialize();
281 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(mode)))
288 GetOperationMode srv;
289 ASSERT_TRUE(operation_mode_client_.call(srv));
290 EXPECT_EQ(mode, srv.response.mode.value);
315 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
318 subscriber_.initialize();
325 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
338 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
341 uint32_t offset{ 0 };
344 msg->disconnect.data =
true;
345 modbus_topic_pub_.publish(
msg);
371 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
374 subscriber_.initialize();
381 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
394 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
421 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
424 subscriber_.initialize();
431 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
444 EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
455 int main(
int argc,
char* argv[])
457 ros::init(argc, argv,
"unittest_modbus_adapter_operation_mode");
460 testing::InitGoogleTest(&argc, argv);
461 return RUN_ALL_TESTS();
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
ModbusMsgInBuilder & setOperationMode(const uint16_t mode)
ROSCONSOLE_DECL void initialize()
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
static constexpr int OPERATION_MODE_QUEUE_SIZE
int main(int argc, char *argv[])
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::ServiceClient operation_mode_client_
static const std::string OPERATION_MODE
static const ModbusApiSpec TEST_API_SPEC
StrictMock< OperationModeSubscriberMock > subscriber_
std::shared_ptr< ModbusAdapterOperationMode > adapter_operation_mode_
~ModbusAdapterOperationModeTest() override
static const std::string TOPIC_MODBUS_READ
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
Expection thrown upon construction of ModbusMsgOperationModeWrapper of the message does not contain t...
static const std::string SERVICE_NAME_OPERATION_MODE
Listens to the modbus_read topic and offers a service informing about the active operation mode...
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...
MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode")
static constexpr int DEFAULT_QUEUE_SIZE_MODBUS
static const std::string OPERATION_MODE_CALLBACK_EVENT
Wrapper class to add semantic to a raw ModbusMsgInStamped.
pilz_msgs::GetOperationMode GetOperationMode
Test fixture for unit-tests of the ModbusAdapterOperationMode.
Redirects callbacks of a ros::Subscriber to a mock method.
Help on construction for ModbusMsgIn Messages.
ModbusMsgInStampedPtr build(const ros::Time &time) const
static const std::vector< uint16_t > OPERATION_MODES
ModbusAdapterOperationModeTest()
static void setDefaultLayout(std_msgs::MultiArrayLayout *layout, const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont::size_type &size)
pilz_msgs::OperationModes OperationModes
ros::Publisher modbus_topic_pub_
Publishes information on the active operation mode. Also offers a service for querying the operation ...
ModbusMsgInBuilder & setApiVersion(const uint16_t version)
static const std::string TOPIC_OPERATION_MODE
void initialize()
Actual subscription takes place here.
Specifies the meaning of the holding registers.
static const std::string VERSION