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 <ros/ros.h>
19 
20 #include <cstddef>
21 #include <vector>
22 #include <errno.h>
23 #include <limits>
24 #include <stdexcept>
25 
28 
29 namespace prbt_hardware_support
30 {
31 
33 {
34  close();
35 }
36 
37 bool LibModbusClient::init(const char* ip, unsigned int port)
38 {
39  modbus_connection_ = modbus_new_tcp(ip, port);
40 
41  if (modbus_connect(modbus_connection_) == -1)
42  {
43  ROS_ERROR_STREAM_NAMED("LibModbusClient", "Could not establish modbus connection." << modbus_strerror(errno));
44  modbus_free(modbus_connection_);
45  modbus_connection_ = nullptr;
46  return false;
47  }
48  return true;
49 }
50 
51 void LibModbusClient::setResponseTimeoutInMs(unsigned long timeout_ms)
52 {
53  struct timeval response_timeout;
54  response_timeout.tv_sec = timeout_ms/1000;
55  response_timeout.tv_usec = (timeout_ms % 1000) * 1000;
56  modbus_set_response_timeout(modbus_connection_, &response_timeout);
57 }
58 
60 {
61  struct timeval response_timeout;
62  modbus_get_response_timeout(modbus_connection_, &response_timeout);
63  return response_timeout.tv_sec * 1000L + (response_timeout.tv_usec / 1000L);
64 }
65 
67 {
68  ROS_DEBUG("readHoldingRegister()");
69  if(modbus_connection_ == nullptr)
70  {
71  throw ModbusExceptionDisconnect("Modbus disconnected!");
72  }
73 
74  RegCont tab_reg(static_cast<RegCont::size_type>(nb));
75  int rc {-1};
76 
77  rc = modbus_read_registers(modbus_connection_, addr, nb, tab_reg.data());
78  if (rc == -1)
79  {
80  std::ostringstream errStream;
81  errStream << "Failed to read " << nb;
82  errStream << " registers starting from " << addr;
83  errStream << " with err: " << modbus_strerror(errno);
84  ROS_ERROR_STREAM_NAMED("LibModbusClient", errStream.str());
85  throw ModbusExceptionDisconnect(errStream.str());
86  }
87 
88  return tab_reg;
89 }
90 
92  const RegCont& write_reg,
93  const int read_addr, const int read_nb)
94 {
95  if(modbus_connection_ == nullptr)
96  {
97  throw ModbusExceptionDisconnect("Modbus disconnected!");
98  }
99 
100  if (read_nb < 0)
101  {
102  throw std::invalid_argument("Argument \"read_nb\" must not be negative");
103  }
104  RegCont read_reg(static_cast<RegCont::size_type>(read_nb));
105 
106  if (write_reg.size() > std::numeric_limits<int>::max())
107  {
108  throw std::invalid_argument("Argument \"write_reg\" must not exceed max value of type \"int\"");
109  }
110 
111  int rc {-1};
112  rc = modbus_write_and_read_registers(modbus_connection_,
113  write_addr, static_cast<int>(write_reg.size()), write_reg.data(),
114  read_addr, read_nb, read_reg.data());
115  ROS_DEBUG_NAMED("LibModbusClient", "modbus_write_and_read_registers: writing from %i %i registers\
116  and reading from %i %i registers",
117  write_addr, static_cast<int>(write_reg.size()), read_addr, read_nb);
118  if (rc == -1)
119  {
120  std::string err = "Failed to write and read modbus registers: ";
121  err.append(modbus_strerror(errno));
122  ROS_ERROR_STREAM_NAMED("LibModbusClient", err);
123  throw ModbusExceptionDisconnect(err);
124  }
125 
126  return read_reg;
127 }
128 
130 {
131  if (modbus_connection_)
132  {
133  modbus_close(modbus_connection_);
134  modbus_free(modbus_connection_);
135  modbus_connection_ = nullptr;
136  }
137 }
138 
139 } // namespace prbt_hardware_support
virtual ~LibModbusClient() override
See base class.
#define ROS_ERROR_STREAM_NAMED(name, args)
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.
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.
#define ROS_DEBUG_NAMED(name,...)
void setResponseTimeoutInMs(unsigned long timeout_ms) override
See base class.
unsigned long getResponseTimeoutInMs() override
See base class.
Expection thrown by prbt_hardware_support::LibModbusClient::readHoldingRegister if a disconnect from ...
#define ROS_DEBUG(...)


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