unittest_libmodbus_client.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 <gtest/gtest.h>
19 
20 #include <thread>
21 #include <chrono>
22 #include <vector>
23 #include <numeric>
24 
25 #include <modbus/modbus.h>
26 
30 
32 
34 {
35 
36 using namespace prbt_hardware_support;
37 
38 // Each testcase should have its own port in order to avoid conflicts between them
39 constexpr unsigned int START_PORT {20500};
40 constexpr unsigned int END_PORT {20600};
41 static unsigned int ACTIVE_PORT_IDX {0};
42 static std::vector<unsigned int> PORTS_FOR_TEST(END_PORT - START_PORT);
43 
44 
45 constexpr unsigned int DEFAULT_REGISTER_SIZE {514};
46 constexpr unsigned int DEFAULT_WRITE_IDX {512};
47 constexpr unsigned int DEFAULT_READ_IDX {77};
48 
49 class LibModbusClientTest : public testing::Test
50 {
51 public:
52  static void SetUpTestCase(); // NOLINT
53  void TearDown() override;
54  unsigned int testPort();
55 
56 protected:
57  void shutdownModbusServer(PilzModbusServerMock *server, LibModbusClient& client);
58 };
59 
61 {
62  // Use next port on next test
64 }
65 
67 {
68  return PORTS_FOR_TEST.at(ACTIVE_PORT_IDX % PORTS_FOR_TEST.size());
69 }
70 
72 {
73  std::iota(PORTS_FOR_TEST.begin(), PORTS_FOR_TEST.end(), START_PORT);
74 }
75 
77 {
78  server->setTerminateFlag();
79  RegCont reg_to_write_by_client {1};
80  try
81  {
82  client.writeReadHoldingRegister(DEFAULT_REGISTER_SIZE, reg_to_write_by_client,
84  } catch (const ModbusExceptionDisconnect& /* ex */)
85  {
86  // Tolerated exception
87  }
88 
89  server->terminate();
90 }
91 
96 TEST_F(LibModbusClientTest, testModbusClientDtor)
97 {
98  ModbusClient* client = new LibModbusClient();
99  delete client;
100 }
101 
109 {
110  std::shared_ptr<LibModbusClient> client(new LibModbusClient());
111 }
112 
116 TEST_F(LibModbusClientTest, testInitialization)
117 {
118  LibModbusClient client;
119  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
120  server->startAsync(LOCALHOST, testPort());
121 
122  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
123 
124  shutdownModbusServer(server.get(), client);
125  client.close();
126 }
127 
131 TEST_F(LibModbusClientTest, testFailingInitIfNoServer)
132 {
133  LibModbusClient client;
134  EXPECT_FALSE(client.init(LOCALHOST, testPort()));
135 }
136 
140 TEST_F(LibModbusClientTest, testReadRegisters)
141 {
142  LibModbusClient client;
143  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
144  server->startAsync(LOCALHOST, testPort());
145 
146  server->setHoldingRegister(RegCont{1,2}, DEFAULT_WRITE_IDX);
147 
148  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
149 
151  RegCont res_expected{1,2};
152  EXPECT_EQ(res_expected, res);
153 
154  shutdownModbusServer(server.get(), client);
155  client.close();
156 }
157 
161 TEST_F(LibModbusClientTest, testWritingRegisters)
162 {
163  LibModbusClient client;
164  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
165  server->startAsync(LOCALHOST, testPort());
166 
167  const RegCont write_reg {1,2};
168  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
169 
170  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
171 
172  RegCont reg_to_write_by_client {8, 3, 7};
173 
174  client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client,
175  DEFAULT_WRITE_IDX, static_cast<int>(write_reg.size()));
176 
177  RegCont res = client.readHoldingRegister(DEFAULT_WRITE_IDX, static_cast<int>(write_reg.size()));
178  RegCont res_expected{1,2};
179  EXPECT_EQ(res_expected, res);
180 
181  RegCont actual_hold_reg {server->readHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client.size())};
182  for (RegCont::size_type i = 0; i < reg_to_write_by_client.size(); ++i)
183  {
184  EXPECT_EQ(reg_to_write_by_client.at(i), actual_hold_reg.at(i));
185  }
186 
187  shutdownModbusServer(server.get(), client);
188  client.close();
189 }
190 
196 TEST_F(LibModbusClientTest, testNegativeNumberOfRegistersToRead)
197 {
198  LibModbusClient client;
199  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
200  server->startAsync(LOCALHOST, testPort());
201 
202  server->setHoldingRegister(RegCont{1,2}, DEFAULT_WRITE_IDX);
203 
204  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
205 
206  const int negative_read_nb {-2};
207  RegCont reg_to_write_by_client {8, 3, 7};
208  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client,
209  DEFAULT_WRITE_IDX, negative_read_nb),
210  std::invalid_argument);
211 
212  shutdownModbusServer(server.get(), client);
213  client.close();
214 }
215 
220 TEST_F(LibModbusClientTest, testOutOfRangeRegisterSize)
221 {
222  LibModbusClient client;
223  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
224  server->startAsync(LOCALHOST, testPort());
225 
226  const RegCont write_reg {1,2};
227  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
228 
229  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
230 
231  RegCont reg_to_write_by_client(static_cast<unsigned int>(std::numeric_limits<int>::max()) + 1u, 0);
232  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client,
233  DEFAULT_WRITE_IDX, static_cast<int>(write_reg.size())),
234  std::invalid_argument);
235 
236  shutdownModbusServer(server.get(), client);
237  client.close();
238 }
239 
244 TEST_F(LibModbusClientTest, testDisconnectBeforeReadWriteOp)
245 {
246  LibModbusClient client;
247 
248  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, RegCont{8, 3, 7},
249  DEFAULT_WRITE_IDX, 0),
251 
252  client.close();
253 }
254 
259 TEST_F(LibModbusClientTest, testDisconnectDuringReadWriteOp)
260 {
261  LibModbusClient client;
262  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
263  server->startAsync(LOCALHOST, testPort());
264 
265  const RegCont write_reg {1,2};
266  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
267 
268  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
269  shutdownModbusServer(server.get(), client);
270 
271  RegCont reg_to_write_by_client {8, 3, 7};
272  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client,
273  DEFAULT_WRITE_IDX, static_cast<int>(write_reg.size())),
275 
276  client.close();
277 }
278 
282 TEST_F(LibModbusClientTest, testReadRegistersNoInit)
283 {
284  LibModbusClient client;
285  EXPECT_FALSE(client.init(LOCALHOST, testPort()));
286 
288 }
289 
293 TEST_F(LibModbusClientTest, testReadRegistersTerminatedServer)
294 {
295  LibModbusClient client;
296  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
297  server->startAsync(LOCALHOST, testPort());
298  server->setHoldingRegister(RegCont{1,2}, DEFAULT_WRITE_IDX);
299 
300  EXPECT_TRUE(client.init(LOCALHOST,testPort()));
301  shutdownModbusServer(server.get(), client);
302 
304  client.close();
305 }
306 
312 TEST_F(LibModbusClientTest, setResponseTimeout)
313 {
314  LibModbusClient client;
315  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(514));
316  server->startAsync(LOCALHOST, testPort());
317 
318  unsigned long timeout_ms = 3;
319 
320  EXPECT_TRUE(client.init(LOCALHOST,testPort()));
321  client.setResponseTimeoutInMs(timeout_ms);
322  EXPECT_EQ(timeout_ms, client.getResponseTimeoutInMs());
323 
324  shutdownModbusServer(server.get(), client);
325  client.close();
326 }
327 
328 } // namespace pilz_modbus_client_test
329 
330 int main(int argc, char *argv[])
331 {
332  testing::InitGoogleTest(&argc, argv);
333  return RUN_ALL_TESTS();
334 }
Offers a modbus server and read/write functionality via subscription/publication. ...
RegCont readHoldingRegister(int addr, int nb) override
See base class.
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
void close()
Close connection with server.
int main(int argc, char *argv[])
constexpr unsigned int DEFAULT_READ_IDX
bool init(const char *ip, unsigned int port) override
See base class.
RegCont writeReadHoldingRegister(const int write_addr, const RegCont &write_reg, const int read_addr, const int read_nb) override
See base class.
constexpr unsigned int START_PORT
static std::vector< unsigned int > PORTS_FOR_TEST(END_PORT-START_PORT)
constexpr unsigned int DEFAULT_REGISTER_SIZE
void setResponseTimeoutInMs(unsigned long timeout_ms) override
See base class.
TEST_F(LibModbusClientTest, testModbusClientDtor)
Test increases function coverage by ensuring that all Dtor variants are called.
unsigned long getResponseTimeoutInMs() override
See base class.
void terminate()
Terminate the Server. Reading or connecting to it will fail.
constexpr unsigned int DEFAULT_WRITE_IDX
constexpr const char *const LOCALHOST
Wrapper around libmodbus, see https://libmodbus.org/.
Expection thrown by prbt_hardware_support::LibModbusClient::readHoldingRegister if a disconnect from ...
void shutdownModbusServer(PilzModbusServerMock *server, LibModbusClient &client)


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