unittest_modbus_adapter_run_permitted.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 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 <string>
19 #include <vector>
20 #include <stdexcept>
21 #include <memory>
22 #include <functional>
23 
24 #include <gtest/gtest.h>
25 #include <gmock/gmock.h>
26 
29 #include <prbt_hardware_support/ModbusMsgInStamped.h>
34 
35 namespace prbt_hardware_support
36 {
37 static constexpr uint16_t RUN_PERMITTED_INVALID_VALUE{ 2 };
38 
40 
41 using namespace prbt_hardware_support;
42 using namespace modbus_api::v3;
43 
44 using std::placeholders::_1;
45 
46 class ModbusAdapterRunPermittedTest : public ::testing::Test
47 {
48 public:
49  ModbusMsgInStampedPtr createDefaultRunPermittedModbusMsg(uint16_t run_permitted_clear);
50 
51 public:
52  MOCK_METHOD1(sendRunPermittedUpdate, void(const bool run_permitted));
53 };
54 
55 ModbusMsgInStampedPtr ModbusAdapterRunPermittedTest::createDefaultRunPermittedModbusMsg(uint16_t run_permitted)
56 {
57  static int msg_time_counter{ 1 };
58  RegCont tab_reg(TEST_API_SPEC.size());
59  tab_reg[0] = run_permitted;
60  tab_reg[1] = MODBUS_API_VERSION_REQUIRED;
62  tab_reg) };
63  msg->header.stamp = ros::Time(msg_time_counter++);
64  return msg;
65 }
66 
71 TEST_F(ModbusAdapterRunPermittedTest, testModbusMsgWrapperExceptionDtor)
72 {
73  std::shared_ptr<ModbusMsgWrapperException> es{ new ModbusMsgWrapperException("Test msg") };
74 }
75 
80 TEST_F(ModbusAdapterRunPermittedTest, testModbusMsgRunPermittedWrapperDtor)
81 {
82  ModbusMsgInStampedConstPtr msg_const_ptr{ createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_TRUE) };
83  std::shared_ptr<ModbusMsgRunPermittedWrapper> ex{ new ModbusMsgRunPermittedWrapper(msg_const_ptr, TEST_API_SPEC) };
84 }
85 
89 TEST_F(ModbusAdapterRunPermittedTest, testRunPermittedClearMsg)
90 {
91  EXPECT_CALL(*this, sendRunPermittedUpdate(true)).Times(1);
92 
95  run_permitted_adapter.modbusMsgCallback(createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_TRUE));
96 }
97 
101 TEST_F(ModbusAdapterRunPermittedTest, testRunPermittedActiveMsg)
102 {
103  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
104 
107  run_permitted_adapter.modbusMsgCallback(createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE));
108 }
109 
113 TEST_F(ModbusAdapterRunPermittedTest, testRunPermittedInvalidMsg)
114 {
115  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
116 
119  run_permitted_adapter.modbusMsgCallback(createDefaultRunPermittedModbusMsg(RUN_PERMITTED_INVALID_VALUE));
120 }
121 
129 TEST_F(ModbusAdapterRunPermittedTest, testDisconnectNoRunPermittedMsg)
130 {
131  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
132 
135 
136  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_TRUE);
137  msg->disconnect.data = true;
138  run_permitted_adapter.modbusMsgCallback(msg);
139 }
140 
149 TEST_F(ModbusAdapterRunPermittedTest, testDisconnectWithRunPermittedMsg)
150 {
151  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
152 
155 
156  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
157  msg->disconnect.data = true;
158  run_permitted_adapter.modbusMsgCallback(msg);
159 }
160 
168 {
169  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
170 
173 
174  ModbusMsgInStampedPtr msg(new ModbusMsgInStamped());
175  ros::Time::init();
176  msg->header.stamp = ros::Time::now();
177  msg->disconnect.data = true;
178  run_permitted_adapter.modbusMsgCallback(msg);
179 }
180 
188 {
189  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
190 
193 
194  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
195  msg->holding_registers.data.pop_back();
196  run_permitted_adapter.modbusMsgCallback(msg);
197 }
198 
206 {
207  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
208 
211 
212  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
213  msg->holding_registers.data[1] = 0;
214  run_permitted_adapter.modbusMsgCallback(msg);
215 }
216 
227 {
228  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
229 
232 
233  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
234  msg->holding_registers.data[1] = 1;
235  run_permitted_adapter.modbusMsgCallback(msg);
236 }
237 
248 {
249  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
250 
253 
254  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
255  msg->holding_registers.data[1] = 2;
256  run_permitted_adapter.modbusMsgCallback(msg);
257 }
258 
266 {
267  EXPECT_CALL(*this, sendRunPermittedUpdate(false)).Times(1);
268 
271 
272  ModbusMsgInStampedPtr msg = createDefaultRunPermittedModbusMsg(MODBUS_RUN_PERMITTED_FALSE);
273  msg->holding_registers.data.erase(msg->holding_registers.data.begin());
274  msg->holding_registers.layout.data_offset = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::VERSION);
275  run_permitted_adapter.modbusMsgCallback(msg);
276 }
277 
281 TEST_F(ModbusAdapterRunPermittedTest, ModbusMsgExceptionCTOR)
282 {
283  std::shared_ptr<ModbusMsgRunPermittedStatusMissing> exception_ptr{ new ModbusMsgRunPermittedStatusMissing("test") };
284 }
285 
286 } // namespace prbt_hardware_support
287 
288 int main(int argc, char** argv)
289 {
290  testing::InitGoogleTest(&argc, argv);
291  return RUN_ALL_TESTS();
292 }
msg
int main(int argc, char **argv)
static constexpr uint16_t MODBUS_RUN_PERMITTED_FALSE
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
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
static const ModbusApiSpec TEST_API_SPEC
Wrapper class to add semantic to a raw ModbusMsgInStamped.
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
static void sendRunPermittedUpdate(ros::ServiceClient &run_permitted_service, const bool run_permitted)
static const std::string RUN_PERMITTED
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 void init()
std::map< std::string, unsigned short >::size_type size() const
Expection thrown upon construction of ModbusMsgRunPermittedWrapper if the message does not contain th...
Listens to the modbus_read topic and reacts to updated RUN_PERMITTED states.
ModbusMsgInStampedPtr createDefaultRunPermittedModbusMsg(uint16_t run_permitted_clear)
static constexpr uint16_t RUN_PERMITTED_INVALID_VALUE
Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the requir...
static Time now()
static constexpr uint16_t MODBUS_RUN_PERMITTED_TRUE
Specifies the meaning of the holding registers.


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