18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 25 #include <modbus/modbus.h> 27 #include <pilz_msgs/OperationModes.h> 29 #include <pilz_testutils/async_test.h> 38 using namespace modbus_api::v3;
56 MOCK_METHOD1(callback,
void(
const pilz_msgs::OperationModesConstPtr&
msg));
83 MATCHER_P(IsExpectedOperationMode, exp_mode,
"unexpected operation mode")
85 return arg->value == exp_mode;
124 ASSERT_TRUE(nh_priv_.getParam(
"modbus_server_ip", ip));
125 ASSERT_TRUE(nh_priv_.getParam(
"modbus_server_port", port));
136 std::thread modbus_server_thread(&initalizeAndRun<prbt_hardware_support::PilzModbusServerMock>,
137 std::ref(modbus_server), ip.c_str(),
static_cast<unsigned int>(port));
140 waitForNode(
"/modbus_adapter_operation_mode_node");
142 using ::testing::StrictMock;
143 StrictMock<OperationModeSubscriberMock> subscriber;
145 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
148 subscriber.initialize();
160 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T1)))
173 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
183 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T2)))
193 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::AUTO)))
203 EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
214 modbus_server_thread.join();
219 int main(
int argc,
char* argv[])
221 ros::init(argc, argv,
"integrationtest_operation_mode");
227 testing::InitGoogleTest(&argc, argv);
228 return RUN_ALL_TESTS();
Offers a modbus server and read/write functionality via subscription/publication. ...
ROSCONSOLE_DECL void initialize()
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
void setHoldingRegister(std::initializer_list< std::pair< unsigned int, uint16_t > > reg_list)
static constexpr int OPERATION_MODE_QUEUE_SIZE
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
unsigned short getMaxRegisterDefinition() const
static const std::string OPERATION_MODE
OperationModeIntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> ModbusAdapte...
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
pilz_msgs::OperationModes OperationModes
MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode")
void terminate()
Terminate the Server. Reading or connecting to it will fail.
static const std::string OPERATION_MODE_CALLBACK_EVENT
inline ::testing::AssertionResult waitForNode(const std::string node_name, const double loop_frequency=10.0, const ros::Duration timeout=ros::Duration(10.0))
Blocks until a node defined by node_name comes up.
Redirects callbacks of a ros::Subscriber to a mock method.
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