18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 25 #include <modbus/modbus.h> 27 #include <pilz_testutils/async_test.h> 30 #include <prbt_hardware_support/OperationModes.h> 66 &OperationModeSubscriberMock::callback,
81 MATCHER_P(IsExpectedOperationMode, exp_mode,
"unexpected operation mode"){
return arg->value == exp_mode; }
119 ASSERT_TRUE(nh_priv_.getParam(
"modbus_server_ip", ip));
120 ASSERT_TRUE(nh_priv_.getParam(
"modbus_server_port", port));
124 unsigned int modbus_register_size {api_spec.getMaxRegisterDefinition() + 1U};
131 std::thread modbus_server_thread( &initalizeAndRun<prbt_hardware_support::PilzModbusServerMock>,
132 std::ref(modbus_server), ip.c_str(),
static_cast<unsigned int>(port) );
135 waitForNode(
"/modbus_adapter_operation_mode_node");
137 using ::testing::StrictMock;
138 StrictMock<OperationModeSubscriberMock> subscriber;
140 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
143 subscriber.initialize();
155 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T1)))
168 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
178 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T2)))
188 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::AUTO)))
198 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
209 modbus_server_thread.join();
215 int main(
int argc,
char *argv[])
217 ros::init(argc, argv,
"integrationtest_operation_mode");
223 testing::InitGoogleTest(&argc, argv);
224 return RUN_ALL_TESTS();
MOCK_METHOD1(callback, void(const OperationModesConstPtr &msg))
Offers a modbus server and read/write functionality via subscription/publication. ...
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)
void setHoldingRegister(std::initializer_list< std::pair< unsigned int, uint16_t > > reg_list)
static constexpr int OPERATION_MODE_QUEUE_SIZE
void waitForNode(std::string node_name, double loop_frequency=10.0)
Blocks until a node defined by node_name comes up.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static constexpr uint16_t MODBUS_API_VERSION_VALUE
static const std::string OPERATION_MODE
OperationModeIntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> ModbusAdapte...
void terminate()
Terminate the Server. Reading or connecting to it will fail.
static const std::string OPERATION_MODE_CALLBACK_EVENT
Redirects callbacks of a ros::Subscriber to a mock method.
MATCHER_P(IsExpectedOperationMode, exp_mode,"unexpected operation mode")
ros::Subscriber subscriber_
int main(int argc, char *argv[])
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