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_testutils/async_test.h>
24 
27 #include <prbt_hardware_support/OperationModes.h>
30 
31 namespace prbt_hardware_support
32 {
33 static constexpr int DEFAULT_QUEUE_SIZE_MODBUS{1};
34 static const std::string SERVICE_NAME_OPERATION_MODE = "/prbt/get_operation_mode";
35 static const std::string TOPIC_OPERATION_MODE{"/prbt/operation_mode"};
36 static constexpr int OPERATION_MODE_QUEUE_SIZE{1};
37 
38 static const std::string OPERATION_MODE_CALLBACK_EVENT{"operation_mode_callback_event"};
39 
40 static constexpr unsigned int MODBUS_API_VERSION_REQUIRED{2};
41 
44 
45 static const std::vector<uint16_t> OPERATION_MODES{1, 2, 3};
46 
51 {
52 public:
56  void initialize();
57 
58  MOCK_METHOD1(callback, void(const OperationModesConstPtr& msg));
59 
60 protected:
63 };
64 
66 {
69  &OperationModeSubscriberMock::callback,
70  this);
71 }
72 
73 using ::testing::StrictMock;
74 
81 class ModbusAdapterOperationModeTest : public testing::Test, public testing::AsyncTest
82 {
83 public:
86 
87 protected:
88  ros::AsyncSpinner spinner_{2};
90  std::shared_ptr<ModbusAdapterOperationMode> adapter_operation_mode_;
93  StrictMock<OperationModeSubscriberMock> subscriber_;
94 };
95 
97 {
98  // Initialize for ROS time if not already initialized
99  if(!ros::Time::isValid())
100  {
101  ros::Time::init();
102  }
103 
104  adapter_operation_mode_.reset(new ModbusAdapterOperationMode(nh_, test_api_spec));
105  modbus_topic_pub_ = nh_.advertise<ModbusMsgInStamped>(TOPIC_MODBUS_READ, DEFAULT_QUEUE_SIZE_MODBUS);
106  operation_mode_client_ = nh_.serviceClient<prbt_hardware_support::GetOperationMode>(SERVICE_NAME_OPERATION_MODE);
107 
108  spinner_.start();
109 }
110 
112 {
113  // Before the destructors of the class members are called, we have
114  // to ensure that all topic and service calls done by the AsyncSpinner
115  // threads are finished. Otherwise, we sporadically will see threading
116  // exceptions like:
117  // "boost::mutex::~mutex(): Assertion `!res' failed".
118  spinner_.stop();
119 }
120 
125 TEST_F(ModbusAdapterOperationModeTest, testAdapterOperationModeDtor)
126 {
127  std::shared_ptr<AdapterOperationMode> adapter_op_mode (new AdapterOperationMode(nh_));
128 }
129 
134 TEST_F(ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperExceptionDtor)
135 {
136  std::shared_ptr<ModbusMsgOperationModeWrapperException> ex (new ModbusMsgOperationModeWrapperException("Test message"));
137 }
138 
143 TEST_F(ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperDtor)
144 {
146  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
147  std::shared_ptr<ModbusMsgOperationModeWrapper> wrapper (new ModbusMsgOperationModeWrapper(builder.build(ros::Time::now()), test_api_spec));
148 }
149 
150 MATCHER_P(IsExpectedOperationMode, exp_mode, "unexpected operation mode"){ return arg->value == exp_mode; }
151 
157 TEST_F(ModbusAdapterOperationModeTest, testInitialOperationMode)
158 {
159  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
160  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
161 
162  subscriber_.initialize();
163 
165 
166  GetOperationMode srv;
167  ASSERT_TRUE(operation_mode_client_.call(srv));
168  EXPECT_EQ(OperationModes::UNKNOWN, srv.response.mode.value);
169 }
170 
187 TEST_F(ModbusAdapterOperationModeTest, testMissingOperationModeRegister)
188 {
189  /**********
190  * Step 1 *
191  **********/
192  ROS_DEBUG("+++ Step 1 +++");
193  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
194  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
195 
196  subscriber_.initialize();
197 
199 
200  /**********
201  * Step 2 *
202  **********/
203  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
204  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
205 
208 
209  ROS_DEBUG("+++ Step 2 +++");
210  modbus_topic_pub_.publish(builder.setOperationMode(OperationModes::T1).build(ros::Time::now()));
211 
213 
214  /**********
215  * Step 3 *
216  **********/
217  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
218  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
219 
220  ModbusMsgInStampedPtr msg {builder.setOperationMode(OperationModes::T1).build(ros::Time::now())};
221 
222  ROS_DEBUG("+++ Step 3 +++");
223  // Remove operation mode from modbus message
225  << "For the test to work correctly, the operation mode register has to be stored in the last register.";
226  msg->holding_registers.data.erase(--msg->holding_registers.data.end());
227  const uint32_t new_offset = test_api_spec.getRegisterDefinition(modbus_api_spec::VERSION);
228  msg->holding_registers.layout.data_offset = new_offset;
229  ModbusMsgInBuilder::setDefaultLayout(&(msg->holding_registers.layout), new_offset, static_cast<uint32_t>(msg->holding_registers.data.size()));
230 
231  modbus_topic_pub_.publish(msg);
232 
234 }
235 
251 TEST_F(ModbusAdapterOperationModeTest, testOperationModeChange)
252 {
253  /**********
254  * Step 1 *
255  **********/
256  ROS_DEBUG("+++ Step 1 +++");
257  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
258  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
259 
260  subscriber_.initialize();
261 
263 
264  /**********
265  * Step 2 *
266  **********/
269  for (const auto& mode : OPERATION_MODES)
270  {
271  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(mode)))
272  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
273 
274  modbus_topic_pub_.publish(builder.setOperationMode(mode).build(ros::Time::now()));
275 
277 
278  GetOperationMode srv;
279  ASSERT_TRUE(operation_mode_client_.call(srv));
280  EXPECT_EQ(mode, srv.response.mode.value);
281  }
282 }
283 
301 {
302  /**********
303  * Step 1 *
304  **********/
305  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
306  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
307 
308  subscriber_.initialize();
309 
311 
312  /**********
313  * Step 2 *
314  **********/
315  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
316  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
317 
319  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
320 
321  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
322 
324 
325  /**********
326  * Step 3 *
327  **********/
328  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
329  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
330 
331  uint32_t offset{0};
332  RegCont holding_register;
333  ModbusMsgInStampedPtr msg{ModbusMsgInBuilder::createDefaultModbusMsgIn(offset, holding_register)};
334  msg->disconnect.data = true;
335  modbus_topic_pub_.publish(msg);
336 
338 }
339 
356 TEST_F(ModbusAdapterOperationModeTest, testModbusUnexpectedOperationMode)
357 {
358  /**********
359  * Step 1 *
360  **********/
361  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
362  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
363 
364  subscriber_.initialize();
365 
367 
368  /**********
369  * Step 2 *
370  **********/
371  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
372  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
373 
375  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
376 
377  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
378 
380 
381  /**********
382  * Step 3 *
383  **********/
384  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
385  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
386 
387  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(1234 /* stupid value */);
388  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
389 
391 }
392 
406 TEST_F(ModbusAdapterOperationModeTest, testModbusIncorrectApiVersion)
407 {
408  /**********
409  * Step 0 *
410  **********/
411  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
412  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
413 
414  subscriber_.initialize();
415 
417 
418  /**********
419  * Step 1 *
420  **********/
421  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::T1)))
422  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
423 
425  builder.setApiVersion(MODBUS_API_VERSION_REQUIRED).setOperationMode(OperationModes::T1);
426 
427  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
428 
430 
431  /**********
432  * Step 2 *
433  **********/
434  EXPECT_CALL(subscriber_, callback(IsExpectedOperationMode(OperationModes::UNKNOWN)))
435  .WillOnce(ACTION_OPEN_BARRIER_VOID(OPERATION_MODE_CALLBACK_EVENT));
436 
437  builder.setApiVersion(0 /* wrong version */).setOperationMode(OperationModes::T2);
438  modbus_topic_pub_.publish(builder.build(ros::Time::now()));
439 
441 }
442 
443 } // namespace prbt_hardware_support
444 
445 int main(int argc, char *argv[])
446 {
447  ros::init(argc, argv, "unittest_modbus_adapter_operation_mode");
448  ros::NodeHandle nh;
449 
450  testing::InitGoogleTest(&argc, argv);
451  return RUN_ALL_TESTS();
452 }
msg
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
MOCK_METHOD1(callback, void(const OperationModesConstPtr &msg))
ModbusMsgInStampedPtr build(const ros::Time &time) const
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
ModbusMsgInBuilder & setOperationMode(const uint16_t mode)
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)
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 std::string TOPIC_MODBUS_READ
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()
static void init()
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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.
MATCHER_P(IsExpectedOperationMode, exp_mode,"unexpected operation mode")
Help on construction for ModbusMsgIn Messages.
unsigned short getRegisterDefinition(const std::string &key) 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 Tue Feb 2 2021 03:50:17