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 using namespace prbt_hardware_support;
36 
37 // Each testcase should have its own port in order to avoid conflicts between them
38 constexpr unsigned int START_PORT{ 20500 };
39 constexpr unsigned int END_PORT{ 20600 };
40 static unsigned int ACTIVE_PORT_IDX{ 0 };
41 static std::vector<unsigned int> PORTS_FOR_TEST(END_PORT - START_PORT);
42 
43 constexpr unsigned int DEFAULT_REGISTER_SIZE{ 514 };
44 constexpr unsigned int DEFAULT_WRITE_IDX{ 512 };
45 constexpr unsigned int DEFAULT_READ_IDX{ 77 };
46 
47 class LibModbusClientTest : public testing::Test
48 {
49 public:
50  static void SetUpTestCase(); // NOLINT
51  void TearDown() override;
52  unsigned int testPort();
53 
54 protected:
55  void shutdownModbusServer(PilzModbusServerMock* server, LibModbusClient& client);
56 };
57 
59 {
60  // Use next port on next test
62 }
63 
65 {
66  return PORTS_FOR_TEST.at(ACTIVE_PORT_IDX % PORTS_FOR_TEST.size());
67 }
68 
70 {
71  std::iota(PORTS_FOR_TEST.begin(), PORTS_FOR_TEST.end(), START_PORT);
72 }
73 
75 {
76  server->setTerminateFlag();
77  RegCont reg_to_write_by_client{ 1 };
78  try
79  {
82  }
83  catch (const ModbusExceptionDisconnect& /* ex */)
84  {
85  // Tolerated exception
86  }
87 
88  server->terminate();
89 }
90 
95 TEST_F(LibModbusClientTest, testModbusClientDtor)
96 {
97  ModbusClient* client = new LibModbusClient();
98  delete client;
99 }
100 
108 {
109  std::shared_ptr<LibModbusClient> client(new LibModbusClient());
110 }
111 
115 TEST_F(LibModbusClientTest, testInitialization)
116 {
117  LibModbusClient client;
118  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
119  server->startAsync(LOCALHOST, testPort());
120 
121  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
122 
123  shutdownModbusServer(server.get(), client);
124  client.close();
125 }
126 
130 TEST_F(LibModbusClientTest, testFailingInitIfNoServer)
131 {
132  LibModbusClient client;
133  EXPECT_FALSE(client.init(LOCALHOST, testPort()));
134 }
135 
139 TEST_F(LibModbusClientTest, testReadRegisters)
140 {
141  LibModbusClient client;
142  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
143  server->startAsync(LOCALHOST, testPort());
144 
145  server->setHoldingRegister(RegCont{ 1, 2 }, DEFAULT_WRITE_IDX);
146 
147  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
148 
150  RegCont res_expected{ 1, 2 };
151  EXPECT_EQ(res_expected, res);
152 
153  shutdownModbusServer(server.get(), client);
154  client.close();
155 }
156 
160 TEST_F(LibModbusClientTest, testWritingRegisters)
161 {
162  LibModbusClient client;
163  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
164  server->startAsync(LOCALHOST, testPort());
165 
166  const RegCont write_reg{ 1, 2 };
167  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
168 
169  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
170 
171  RegCont reg_to_write_by_client{ 8, 3, 7 };
172 
173  client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client, DEFAULT_WRITE_IDX,
174  static_cast<int>(write_reg.size()));
175 
176  RegCont res = client.readHoldingRegister(DEFAULT_WRITE_IDX, static_cast<int>(write_reg.size()));
177  RegCont res_expected{ 1, 2 };
178  EXPECT_EQ(res_expected, res);
179 
180  RegCont actual_hold_reg{ server->readHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client.size()) };
181  for (RegCont::size_type i = 0; i < reg_to_write_by_client.size(); ++i)
182  {
183  EXPECT_EQ(reg_to_write_by_client.at(i), actual_hold_reg.at(i));
184  }
185 
186  shutdownModbusServer(server.get(), client);
187  client.close();
188 }
189 
195 TEST_F(LibModbusClientTest, testNegativeNumberOfRegistersToRead)
196 {
197  LibModbusClient client;
198  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
199  server->startAsync(LOCALHOST, testPort());
200 
201  server->setHoldingRegister(RegCont{ 1, 2 }, DEFAULT_WRITE_IDX);
202 
203  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
204 
205  const int negative_read_nb{ -2 };
206  RegCont reg_to_write_by_client{ 8, 3, 7 };
207  EXPECT_THROW(
208  client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client, DEFAULT_WRITE_IDX, negative_read_nb),
209  std::invalid_argument);
210 
211  shutdownModbusServer(server.get(), client);
212  client.close();
213 }
214 
219 TEST_F(LibModbusClientTest, testOutOfRangeRegisterSize)
220 {
221  LibModbusClient client;
222  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
223  server->startAsync(LOCALHOST, testPort());
224 
225  const RegCont write_reg{ 1, 2 };
226  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
227 
228  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
229 
230  RegCont reg_to_write_by_client(static_cast<unsigned int>(std::numeric_limits<int>::max()) + 1u, 0);
231  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client, DEFAULT_WRITE_IDX,
232  static_cast<int>(write_reg.size())),
233  std::invalid_argument);
234 
235  shutdownModbusServer(server.get(), client);
236  client.close();
237 }
238 
243 TEST_F(LibModbusClientTest, testDisconnectBeforeReadWriteOp)
244 {
245  LibModbusClient client;
246 
247  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, RegCont{ 8, 3, 7 }, DEFAULT_WRITE_IDX, 0),
249 
250  client.close();
251 }
252 
257 TEST_F(LibModbusClientTest, testDisconnectDuringReadWriteOp)
258 {
259  LibModbusClient client;
260  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
261  server->startAsync(LOCALHOST, testPort());
262 
263  const RegCont write_reg{ 1, 2 };
264  server->setHoldingRegister(write_reg, DEFAULT_WRITE_IDX);
265 
266  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
267  shutdownModbusServer(server.get(), client);
268 
269  RegCont reg_to_write_by_client{ 8, 3, 7 };
270  EXPECT_THROW(client.writeReadHoldingRegister(DEFAULT_READ_IDX, reg_to_write_by_client, DEFAULT_WRITE_IDX,
271  static_cast<int>(write_reg.size())),
273 
274  client.close();
275 }
276 
280 TEST_F(LibModbusClientTest, testReadRegistersNoInit)
281 {
282  LibModbusClient client;
283  EXPECT_FALSE(client.init(LOCALHOST, testPort()));
284 
286 }
287 
291 TEST_F(LibModbusClientTest, testReadRegistersTerminatedServer)
292 {
293  LibModbusClient client;
294  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(DEFAULT_REGISTER_SIZE));
295  server->startAsync(LOCALHOST, testPort());
296  server->setHoldingRegister(RegCont{ 1, 2 }, DEFAULT_WRITE_IDX);
297 
298  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
299  shutdownModbusServer(server.get(), client);
300 
302  client.close();
303 }
304 
308 TEST_F(LibModbusClientTest, setResponseTimeout)
309 {
310  LibModbusClient client;
311  std::shared_ptr<PilzModbusServerMock> server(new PilzModbusServerMock(514));
312  server->startAsync(LOCALHOST, testPort());
313 
314  unsigned long timeout_ms = 3;
315 
316  EXPECT_TRUE(client.init(LOCALHOST, testPort()));
317  client.setResponseTimeoutInMs(timeout_ms);
318  EXPECT_EQ(timeout_ms, client.getResponseTimeoutInMs());
319 
320  shutdownModbusServer(server.get(), client);
321  client.close();
322 }
323 
324 } // namespace pilz_modbus_client_test
325 
326 int main(int argc, char* argv[])
327 {
328  testing::InitGoogleTest(&argc, argv);
329  return RUN_ALL_TESTS();
330 }
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
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)
static std::vector< unsigned int > PORTS_FOR_TEST(END_PORT - START_PORT)


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