integrationtest_operation_mode.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <gtest/gtest.h>
19 #include <gmock/gmock.h>
20 
21 #include <memory>
22 #include <string>
23 
24 #include <ros/ros.h>
25 #include <modbus/modbus.h>
26 
27 #include <pilz_msgs/OperationModes.h>
28 
29 #include <pilz_testutils/async_test.h>
30 
35 
36 namespace prbt_hardware_support
37 {
38 using namespace modbus_api::v3;
39 
40 static const std::string TOPIC_OPERATION_MODE{ "/prbt/operation_mode" };
41 static constexpr int OPERATION_MODE_QUEUE_SIZE{ 1 };
42 
43 static const std::string OPERATION_MODE_CALLBACK_EVENT{ "operation_mode_callback_event" };
44 
49 {
50 public:
54  void initialize();
55 
56  MOCK_METHOD1(callback, void(const pilz_msgs::OperationModesConstPtr& msg));
57 
58 protected:
61 };
62 
64 {
65  subscriber_ =
66  nh_.subscribe(TOPIC_OPERATION_MODE, OPERATION_MODE_QUEUE_SIZE, &OperationModeSubscriberMock::callback, this);
67 }
68 
73 class OperationModeIntegrationTest : public testing::Test, public testing::AsyncTest
74 {
75 protected:
76  using OperationModes = pilz_msgs::OperationModes;
77 
78 protected:
80  ros::NodeHandle nh_priv_{ "~" };
81 };
82 
83 MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode")
84 {
85  return arg->value == exp_mode;
86 }
87 
117 TEST_F(OperationModeIntegrationTest, testOperationModeRequestAnnouncement)
118 {
119  /**********
120  * Setup *
121  **********/
122  std::string ip;
123  int port;
124  ASSERT_TRUE(nh_priv_.getParam("modbus_server_ip", ip));
125  ASSERT_TRUE(nh_priv_.getParam("modbus_server_port", port));
126 
127  ModbusApiSpec api_spec{ nh_ };
128 
129  unsigned int modbus_register_size{ api_spec.getMaxRegisterDefinition() + 1U };
130 
131  /**********
132  * Step 1 *
133  **********/
134  prbt_hardware_support::PilzModbusServerMock modbus_server(modbus_register_size);
135 
136  std::thread modbus_server_thread(&initalizeAndRun<prbt_hardware_support::PilzModbusServerMock>,
137  std::ref(modbus_server), ip.c_str(), static_cast<unsigned int>(port));
138 
139  waitForNode("/pilz_modbus_client_node");
140  waitForNode("/modbus_adapter_operation_mode_node");
141 
142  using ::testing::StrictMock;
143  StrictMock<OperationModeSubscriberMock> subscriber;
144 
145  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
146  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
147 
148  subscriber.initialize();
149 
151 
152  /**********
153  * Step 2 *
154  **********/
155  ASSERT_TRUE(api_spec.hasRegisterDefinition(modbus_api_spec::VERSION));
156  unsigned int version_register = api_spec.getRegisterDefinition(modbus_api_spec::VERSION);
157 
158  modbus_server.setHoldingRegister({ { version_register, MODBUS_API_VERSION_REQUIRED } });
159 
160  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T1)))
161  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
162 
163  ASSERT_TRUE(api_spec.hasRegisterDefinition(modbus_api_spec::OPERATION_MODE));
164  unsigned int op_mode_register = api_spec.getRegisterDefinition(modbus_api_spec::OPERATION_MODE);
165 
166  modbus_server.setHoldingRegister({ { op_mode_register, 1 } });
167 
169 
170  /**********
171  * Step 3 *
172  **********/
173  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
174  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
175 
176  modbus_server.setHoldingRegister({ { op_mode_register, 0 } });
177 
179 
180  /**********
181  * Step 4 *
182  **********/
183  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T2)))
184  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
185 
186  modbus_server.setHoldingRegister({ { op_mode_register, 2 } });
187 
189 
190  /**********
191  * Step 5 *
192  **********/
193  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::AUTO)))
194  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
195 
196  modbus_server.setHoldingRegister({ { op_mode_register, 3 } });
197 
199 
200  /**********
201  * Step 6 *
202  **********/
203  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
204  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
205 
206  modbus_server.setHoldingRegister({ { op_mode_register, 99 } });
207 
209 
210  /**********
211  * Step 7 *
212  **********/
213  modbus_server.terminate();
214  modbus_server_thread.join();
215 }
216 
217 } // namespace prbt_hardware_support
218 
219 int main(int argc, char* argv[])
220 {
221  ros::init(argc, argv, "integrationtest_operation_mode");
222  ros::NodeHandle nh;
223 
225  spinner.start();
226 
227  testing::InitGoogleTest(&argc, argv);
228  return RUN_ALL_TESTS();
229 }
msg
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)
static const std::string OPERATION_MODE
OperationModeIntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> ModbusAdapte...
void spinner()
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
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.
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.


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34