18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 23 #include <pilz_testutils/async_test.h> 27 #include <prbt_hardware_support/OperationModes.h> 69 &OperationModeSubscriberMock::callback,
73 using ::testing::StrictMock;
150 MATCHER_P(IsExpectedOperationMode, exp_mode,
"unexpected operation mode"){
return arg->value == exp_mode; }
159 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
166 GetOperationMode srv;
167 ASSERT_TRUE(operation_mode_client_.call(srv));
168 EXPECT_EQ(OperationModes::UNKNOWN, srv.response.mode.value);
193 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
203 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
217 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
225 <<
"For the test to work correctly, the operation mode register has to be stored in the last register.";
226 msg->holding_registers.data.erase(--
msg->holding_registers.data.end());
228 msg->holding_registers.layout.data_offset = new_offset;
231 modbus_topic_pub_.publish(
msg);
257 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
271 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(mode)))
278 GetOperationMode srv;
279 ASSERT_TRUE(operation_mode_client_.call(srv));
280 EXPECT_EQ(mode, srv.response.mode.value);
305 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
315 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
328 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
334 msg->disconnect.data =
true;
335 modbus_topic_pub_.publish(
msg);
361 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
371 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
384 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
411 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
421 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
434 EXPECT_CALL(
subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
445 int main(
int argc,
char *argv[])
447 ros::init(argc, argv,
"unittest_modbus_adapter_operation_mode");
450 testing::InitGoogleTest(&argc, argv);
451 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
MOCK_METHOD1(callback, void(const OperationModesConstPtr &msg))
ModbusMsgInStampedPtr build(const ros::Time &time) const
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
ModbusMsgInBuilder & setOperationMode(const uint16_t mode)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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
virtual ~ModbusAdapterOperationModeTest()
StrictMock< OperationModeSubscriberMock > subscriber_
std::shared_ptr< ModbusAdapterOperationMode > adapter_operation_mode_
static const std::string TOPIC_MODBUS_READ
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...
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED
static constexpr int DEFAULT_QUEUE_SIZE_MODBUS
static const ModbusApiSpec test_api_spec
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static const std::string OPERATION_MODE_CALLBACK_EVENT
Wrapper class to add semantic to a raw ModbusMsgInStamped.
Test fixture for unit-tests of the ModbusAdapterOperationMode.
Redirects callbacks of a ros::Subscriber to a mock method.
MATCHER_P(IsExpectedOperationMode, exp_mode,"unexpected operation mode")
Help on construction for ModbusMsgIn Messages.
unsigned short getRegisterDefinition(const std::string &key) const
static const std::vector< uint16_t > OPERATION_MODES
ModbusAdapterOperationModeTest()
ros::Subscriber subscriber_
static void setDefaultLayout(std_msgs::MultiArrayLayout *layout, const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont::size_type &size)
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