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_testutils/async_test.h>
28 
30 #include <prbt_hardware_support/OperationModes.h>
33 
34 namespace prbt_hardware_support
35 {
36 
37 static constexpr uint16_t MODBUS_API_VERSION_VALUE {2};
38 
39 static const std::string TOPIC_OPERATION_MODE{"/prbt/operation_mode"};
40 static constexpr int OPERATION_MODE_QUEUE_SIZE{1};
41 
42 static const std::string OPERATION_MODE_CALLBACK_EVENT{"operation_mode_callback_event"};
43 
48 {
49 public:
53  void initialize();
54 
55  MOCK_METHOD1(callback, void(const OperationModesConstPtr& msg));
56 
57 protected:
60 };
61 
63 {
66  &OperationModeSubscriberMock::callback,
67  this);
68 }
69 
74 class OperationModeIntegrationTest : public testing::Test, public testing::AsyncTest
75 {
76 protected:
78  ros::NodeHandle nh_priv_{"~"};
79 };
80 
81 MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode"){ return arg->value == exp_mode; }
82 
112 TEST_F(OperationModeIntegrationTest, testOperationModeRequestAnnouncement)
113 {
114  /**********
115  * Setup *
116  **********/
117  std::string ip;
118  int port;
119  ASSERT_TRUE(nh_priv_.getParam("modbus_server_ip", ip));
120  ASSERT_TRUE(nh_priv_.getParam("modbus_server_port", port));
121 
122  ModbusApiSpec api_spec {nh_};
123 
124  unsigned int modbus_register_size {api_spec.getMaxRegisterDefinition() + 1U};
125 
126  /**********
127  * Step 1 *
128  **********/
129  prbt_hardware_support::PilzModbusServerMock modbus_server(modbus_register_size);
130 
131  std::thread modbus_server_thread( &initalizeAndRun<prbt_hardware_support::PilzModbusServerMock>,
132  std::ref(modbus_server), ip.c_str(), static_cast<unsigned int>(port) );
133 
134  waitForNode("/pilz_modbus_client_node");
135  waitForNode("/modbus_adapter_operation_mode_node");
136 
137  using ::testing::StrictMock;
138  StrictMock<OperationModeSubscriberMock> subscriber;
139 
140  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
141  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
142 
143  subscriber.initialize();
144 
146 
147  /**********
148  * Step 2 *
149  **********/
150  ASSERT_TRUE(api_spec.hasRegisterDefinition(modbus_api_spec::VERSION));
151  unsigned int version_register = api_spec.getRegisterDefinition(modbus_api_spec::VERSION);
152 
153  modbus_server.setHoldingRegister({{version_register, MODBUS_API_VERSION_VALUE}});
154 
155  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T1)))
156  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
157 
158  ASSERT_TRUE(api_spec.hasRegisterDefinition(modbus_api_spec::OPERATION_MODE));
159  unsigned int op_mode_register = api_spec.getRegisterDefinition(modbus_api_spec::OPERATION_MODE);
160 
161  modbus_server.setHoldingRegister({{op_mode_register, 1}});
162 
164 
165  /**********
166  * Step 3 *
167  **********/
168  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
169  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
170 
171  modbus_server.setHoldingRegister({{op_mode_register, 0}});
172 
174 
175  /**********
176  * Step 4 *
177  **********/
178  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::T2)))
179  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
180 
181  modbus_server.setHoldingRegister({{op_mode_register, 2}});
182 
184 
185  /**********
186  * Step 5 *
187  **********/
188  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::AUTO)))
189  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
190 
191  modbus_server.setHoldingRegister({{op_mode_register, 3}});
192 
194 
195  /**********
196  * Step 6 *
197  **********/
198  EXPECT_CALL(subscriber, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
199  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
200 
201  modbus_server.setHoldingRegister({{op_mode_register, 99}});
202 
204 
205  /**********
206  * Step 7 *
207  **********/
208  modbus_server.terminate();
209  modbus_server_thread.join();
210 }
211 
212 } // namespace prbt_hardware_support
213 
214 
215 int main(int argc, char *argv[])
216 {
217  ros::init(argc, argv, "integrationtest_operation_mode");
218  ros::NodeHandle nh;
219 
221  spinner.start();
222 
223  testing::InitGoogleTest(&argc, argv);
224  return RUN_ALL_TESTS();
225 }
msg
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 spinner()
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")
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 Tue Feb 2 2021 03:50:17