unittest_modbus_adapter_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 #include <algorithm>
21 #include <memory>
22 
23 #include <pilz_msgs/OperationModes.h>
24 
25 #include <pilz_testutils/async_test.h>
26 
32 
33 namespace prbt_hardware_support
34 {
35 using namespace modbus_api::v3;
36 
37 static constexpr int DEFAULT_QUEUE_SIZE_MODBUS{ 1 };
38 static const std::string SERVICE_NAME_OPERATION_MODE = "/prbt/get_operation_mode";
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 
45 
46 static const std::vector<uint16_t> OPERATION_MODES{ 1, 2, 3 };
47 
52 {
53 public:
57  void initialize();
58 
59  MOCK_METHOD1(callback, void(const pilz_msgs::OperationModesConstPtr& msg));
60 
61 protected:
62  ros::NodeHandle nh_;
63  ros::Subscriber subscriber_;
64 };
65 
67 {
68  subscriber_ =
69  nh_.subscribe(TOPIC_OPERATION_MODE, OPERATION_MODE_QUEUE_SIZE, &OperationModeSubscriberMock::callback, this);
70 }
71 
72 using ::testing::StrictMock;
73 
80 class ModbusAdapterOperationModeTest : public testing::Test, public testing::AsyncTest
81 {
82 public:
85 
86 protected:
87  using GetOperationMode = pilz_msgs::GetOperationMode;
88  using OperationModes = pilz_msgs::OperationModes;
89 
90 protected:
91  ros::AsyncSpinner spinner_{ 2 };
93  std::shared_ptr<ModbusAdapterOperationMode> adapter_operation_mode_;
96  StrictMock<OperationModeSubscriberMock> subscriber_;
97 };
98 
100 {
101  // Initialize for ROS time if not already initialized
102  if (!ros::Time::isValid())
103  {
104  ros::Time::init();
105  }
106 
107  adapter_operation_mode_.reset(new ModbusAdapterOperationMode(nh_, TEST_API_SPEC));
108  modbus_topic_pub_ = nh_.advertise<ModbusMsgInStamped>(TOPIC_MODBUS_READ, DEFAULT_QUEUE_SIZE_MODBUS);
109  operation_mode_client_ = nh_.serviceClient<GetOperationMode>(SERVICE_NAME_OPERATION_MODE);
110 
111  spinner_.start();
112 }
113 
115 {
116  // Before the destructors of the class members are called, we have
117  // to ensure that all topic and service calls done by the AsyncSpinner
118  // threads are finished. Otherwise, we sporadically will see threading
119  // exceptions like:
120  // "boost::mutex::~mutex(): Assertion `!res' failed".
121  spinner_.stop();
122 }
123 
128 TEST_F(ModbusAdapterOperationModeTest, testAdapterOperationModeDtor)
129 {
130  std::shared_ptr<AdapterOperationMode> adapter_op_mode(new AdapterOperationMode(nh_));
131 }
132 
137 TEST_F(ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperExceptionDtor)
138 {
139  std::shared_ptr<ModbusMsgOperationModeWrapperException> ex(new ModbusMsgOperationModeWrapperException("Test "
140  "message"));
141 }
142 
147 TEST_F(ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperDtor)
148 {
150  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
151  std::shared_ptr<ModbusMsgOperationModeWrapper> wrapper(
153 }
154 
155 MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode")
156 {
157  return arg->value == exp_mode;
158 }
159 
165 TEST_F(ModbusAdapterOperationModeTest, testInitialOperationMode)
166 {
167  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
168  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
169 
170  subscriber_.initialize();
171 
173 
174  GetOperationMode srv;
175  ASSERT_TRUE(operation_mode_client_.call(srv));
176  EXPECT_EQ(OperationModes::UNKNOWN, srv.response.mode.value);
177 }
178 
195 TEST_F(ModbusAdapterOperationModeTest, testMissingOperationModeRegister)
196 {
197  /**********
198  * Step 1 *
199  **********/
200  ROS_DEBUG("+++ Step 1 +++");
201  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
202  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
203 
204  subscriber_.initialize();
205 
207 
208  /**********
209  * Step 2 *
210  **********/
211  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
212  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
213 
216 
217  ROS_DEBUG("+++ Step 2 +++");
218  modbus_topic_pub_.publish(builder.setOperationMode(OperationModes::T1).build(ros::Time::now()));
219 
221 
222  /**********
223  * Step 3 *
224  **********/
225  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
226  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
227 
228  ModbusMsgInStampedPtr msg{ builder.setOperationMode(OperationModes::T1).build(ros::Time::now()) };
229 
230  ROS_DEBUG("+++ Step 3 +++");
231  // Remove operation mode from modbus message
234  << "For the test to work correctly, the operation mode register has to be stored in the last register.";
235  msg->holding_registers.data.erase(--msg->holding_registers.data.end());
236  const uint32_t new_offset = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::VERSION);
237  msg->holding_registers.layout.data_offset = new_offset;
238  ModbusMsgInBuilder::setDefaultLayout(&(msg->holding_registers.layout), new_offset,
239  static_cast<uint32_t>(msg->holding_registers.data.size()));
240 
241  modbus_topic_pub_.publish(msg);
242 
244 }
245 
261 TEST_F(ModbusAdapterOperationModeTest, testOperationModeChange)
262 {
263  /**********
264  * Step 1 *
265  **********/
266  ROS_DEBUG("+++ Step 1 +++");
267  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
268  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
269 
270  subscriber_.initialize();
271 
273 
274  /**********
275  * Step 2 *
276  **********/
279  for (const auto& mode : OPERATION_MODES)
280  {
281  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(mode)))
282  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
283 
284  modbus_topic_pub_.publish(builder.setOperationMode(mode).build(ros::Time::now()));
285 
287 
288  GetOperationMode srv;
289  ASSERT_TRUE(operation_mode_client_.call(srv));
290  EXPECT_EQ(mode, srv.response.mode.value);
291  }
292 }
293 
311 {
312  /**********
313  * Step 1 *
314  **********/
315  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
316  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
317 
318  subscriber_.initialize();
319 
321 
322  /**********
323  * Step 2 *
324  **********/
325  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
326  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
327 
329  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
330 
331  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
332 
334 
335  /**********
336  * Step 3 *
337  **********/
338  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
339  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
340 
341  uint32_t offset{ 0 };
342  RegCont holding_register;
343  ModbusMsgInStampedPtr msg{ ModbusMsgInBuilder::createDefaultModbusMsgIn(offset, holding_register) };
344  msg->disconnect.data = true;
345  modbus_topic_pub_.publish(msg);
346 
348 }
349 
366 TEST_F(ModbusAdapterOperationModeTest, testModbusUnexpectedOperationMode)
367 {
368  /**********
369  * Step 1 *
370  **********/
371  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
372  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
373 
374  subscriber_.initialize();
375 
377 
378  /**********
379  * Step 2 *
380  **********/
381  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
382  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
383 
385  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
386 
387  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
388 
390 
391  /**********
392  * Step 3 *
393  **********/
394  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
395  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
396 
397  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(1234 /* stupid value */);
398  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
399 
401 }
402 
416 TEST_F(ModbusAdapterOperationModeTest, testModbusIncorrectApiVersion)
417 {
418  /**********
419  * Step 0 *
420  **********/
421  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
422  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
423 
424  subscriber_.initialize();
425 
427 
428  /**********
429  * Step 1 *
430  **********/
431  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
432  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
433 
435  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
436 
437  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
438 
440 
441  /**********
442  * Step 2 *
443  **********/
444  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
445  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
446 
447  builder.setApiVersion(0 /* wrong version */).setOperationMode(OperationModes::T2);
448  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
449 
451 }
452 
453 } // namespace prbt_hardware_support
454 
455 int main(int argc, char* argv[])
456 {
457  ros::init(argc, argv, "unittest_modbus_adapter_operation_mode");
458  ros::NodeHandle nh;
459 
460  testing::InitGoogleTest(&argc, argv);
461  return RUN_ALL_TESTS();
462 }
msg
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
unsigned short getRegisterDefinition(const std::string &key) const
ModbusMsgInBuilder & setOperationMode(const uint16_t mode)
ROSCONSOLE_DECL void initialize()
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)
static const std::string OPERATION_MODE
static const ModbusApiSpec TEST_API_SPEC
static const std::string TOPIC_MODBUS_READ
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
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 bool isValid()
MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode")
static void init()
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.
Help on construction for ModbusMsgIn Messages.
ModbusMsgInStampedPtr build(const ros::Time &time) const
static const std::vector< uint16_t > OPERATION_MODES
static Time now()
static void setDefaultLayout(std_msgs::MultiArrayLayout *layout, const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont::size_type &size)
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.
#define ROS_DEBUG(...)


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