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 
38 static constexpr bool RUN_PERMITTED_CLEAR {true};
39 static constexpr bool RUN_PERMITTED_ACTIVE {false};
40 
43 
44 static constexpr int MODBUS_API_VERSION_FOR_TESTING {2};
45 
46 using namespace prbt_hardware_support;
47 
48 using std::placeholders::_1;
49 
50 
51 class ModbusAdapterRunPermittedTest : public ::testing::Test
52 {
53 public:
54  ModbusMsgInStampedPtr createDefaultRunPermittedModbusMsg(bool run_permitted_clear);
55 
56 public:
57  MOCK_METHOD1(sendRunPermittedUpdate, void(const bool run_permitted));
58 
59 };
60 
62 {
63  static int msg_time_counter {1};
64  RegCont tab_reg(TEST_API_SPEC.size());
65  tab_reg[0] = run_permitted;
66  tab_reg[1] = MODBUS_API_VERSION_FOR_TESTING;
68  msg->header.stamp = ros::Time(msg_time_counter++);
69  return msg;
70 }
71 
76 TEST_F(ModbusAdapterRunPermittedTest, testModbusMsgWrapperExceptionDtor)
77 {
78  std::shared_ptr<ModbusMsgWrapperException> es{new ModbusMsgWrapperException("Test msg")};
79 }
80 
85 TEST_F(ModbusAdapterRunPermittedTest, testModbusMsgRunPermittedWrapperDtor)
86 {
87  ModbusMsgInStampedConstPtr msg_const_ptr {createDefaultRunPermittedModbusMsg(RUN_PERMITTED_CLEAR)};
88  std::shared_ptr<ModbusMsgRunPermittedWrapper> ex {new ModbusMsgRunPermittedWrapper(msg_const_ptr, TEST_API_SPEC)};
89 }
90 
96 TEST_F(ModbusAdapterRunPermittedTest, testRunPermittedClearMsg)
97 {
98  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_CLEAR)).Times(1);
99 
102 }
103 
108 TEST_F(ModbusAdapterRunPermittedTest, testRunPermittedActiveMsg)
109 {
110  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
111 
114 }
115 
123 TEST_F(ModbusAdapterRunPermittedTest, testDisconnectNoRunPermittedMsg)
124 {
125  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
126 
128 
130  msg->disconnect.data = true;
131  run_permitted_adapter.modbusMsgCallback( msg );
132 }
133 
142 TEST_F(ModbusAdapterRunPermittedTest, testDisconnectWithRunPermittedMsg)
143 {
144  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
145 
147 
149  msg->disconnect.data = true;
150  run_permitted_adapter.modbusMsgCallback( msg );
151 }
152 
160 {
161  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
162 
164 
165  ModbusMsgInStampedPtr msg (new ModbusMsgInStamped());
166  ros::Time::init();
167  msg->header.stamp = ros::Time::now();
168  msg->disconnect.data = true;
169  run_permitted_adapter.modbusMsgCallback( msg );
170 }
171 
179 {
180  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
181 
183 
185  msg->holding_registers.data.pop_back();
186  run_permitted_adapter.modbusMsgCallback( msg );
187 }
188 
196 {
197  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
198 
200 
202  msg->holding_registers.data[1] = 0;
203  run_permitted_adapter.modbusMsgCallback( msg );
204 }
205 
206 
217 {
218  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
219 
221 
223  msg->holding_registers.data[1] = 1;
224  run_permitted_adapter.modbusMsgCallback( msg );
225 }
226 
227 
235 {
236  EXPECT_CALL(*this, sendRunPermittedUpdate(RUN_PERMITTED_ACTIVE)).Times(1);
237 
239 
241  msg->holding_registers.data.erase(msg->holding_registers.data.begin());
242  msg->holding_registers.layout.data_offset = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::VERSION);
243  run_permitted_adapter.modbusMsgCallback( msg );
244 }
245 
249 TEST_F(ModbusAdapterRunPermittedTest, ModbusMsgExceptionCTOR)
250 {
251  std::shared_ptr<ModbusMsgRunPermittedStatusMissing> exception_ptr{new ModbusMsgRunPermittedStatusMissing("test")};
252 }
253 
254 } // namespace prbt_hardware_support
255 
256 int main(int argc, char** argv)
257 {
258  testing::InitGoogleTest(&argc, argv);
259  return RUN_ALL_TESTS();
260 }
msg
int main(int argc, char **argv)
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
std::map< std::string, unsigned short >::size_type size() const
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
ModbusMsgInStampedPtr createDefaultRunPermittedModbusMsg(bool run_permitted_clear)
static const ModbusApiSpec TEST_API_SPEC
Wrapper class to add semantic to a raw ModbusMsgInStamped.
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()
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.
unsigned short getRegisterDefinition(const std::string &key) const
Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the requir...
static Time now()
MOCK_METHOD1(sendRunPermittedUpdate, void(const bool run_permitted))
Specifies the meaning of the holding registers.


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17