Connects to a modbus server and publishes the received data into ROS.
More...
#include <pilz_modbus_client.h>
|
bool | init (const char *ip, unsigned int port) |
| Tries to connect to a modbus server. More...
|
|
bool | init (const char *ip, unsigned int port, int retries, const ros::Duration &timeout_ms) |
| Tries to connect to a modbus server. More...
|
|
bool | isRunning () |
| True if 'run()' method is active, false if 'run()' method is not active or, currently, finishing. More...
|
|
| PilzModbusClient (ros::NodeHandle &nh, const std::vector< unsigned short > ®isters_to_read, ModbusClientUniquePtr modbus_client, unsigned int response_timeout_ms, const std::string &modbus_read_topic_name, const std::string &modbus_write_service_name, double read_frequency_hz=DEFAULT_MODBUS_READ_FREQUENCY_HZ) |
| Sets up publisher. To open the modbus connection call PilzModbusClient::init. More...
|
|
void | run () |
| Publishes the register values as messages. More...
|
|
void | terminate () |
| Ends the infinite loop started in method 'run()'. More...
|
|
|
static std::vector< std::vector< unsigned short > > | splitIntoBlocks (std::vector< unsigned short > &in) |
| Splits a vector of integers into a vector of vectors with consecutive groups. More...
|
|
|
bool | modbus_write_service_cb (WriteModbusRegister::Request &req, WriteModbusRegister::Response &res) |
| Stores the register which have to be send to the modbus server in a local buffer for further processing by the modbus thread. More...
|
|
void | sendDisconnectMsg () |
|
Connects to a modbus server and publishes the received data into ROS.
Definition at line 39 of file pilz_modbus_client.h.
◆ ModbusClientUniquePtr
◆ State
States of the Modbus-client.
Enumerator |
---|
not_initialized | |
initializing | |
initialized | |
running | |
Definition at line 118 of file pilz_modbus_client.h.
◆ PilzModbusClient()
prbt_hardware_support::PilzModbusClient::PilzModbusClient |
( |
ros::NodeHandle & |
nh, |
|
|
const std::vector< unsigned short > & |
registers_to_read, |
|
|
ModbusClientUniquePtr |
modbus_client, |
|
|
unsigned int |
response_timeout_ms, |
|
|
const std::string & |
modbus_read_topic_name, |
|
|
const std::string & |
modbus_write_service_name, |
|
|
double |
read_frequency_hz = DEFAULT_MODBUS_READ_FREQUENCY_HZ |
|
) |
| |
Sets up publisher. To open the modbus connection call PilzModbusClient::init.
- Parameters
-
nh | Node handle. |
registers_to_read | Registers which have to be read. |
modbus_client | ModbusClient to use |
response_timeout_ms | Time to wait for a response from Modbus server. |
modbus_read_topic_name | Name of the topic to which is published. |
modbus_write_service_name | Name under which the modbus write service is advertised. |
read_frequency_hz | Defines how often Modbus registers are read in. |
Definition at line 27 of file pilz_modbus_client.cpp.
◆ init() [1/2]
bool prbt_hardware_support::PilzModbusClient::init |
( |
const char * |
ip, |
|
|
unsigned int |
port |
|
) |
| |
Tries to connect to a modbus server.
- Parameters
-
- Returns
- True if a connection is established, false otherwise.
Definition at line 70 of file pilz_modbus_client.cpp.
◆ init() [2/2]
bool prbt_hardware_support::PilzModbusClient::init |
( |
const char * |
ip, |
|
|
unsigned int |
port, |
|
|
int |
retries, |
|
|
const ros::Duration & |
timeout_ms |
|
) |
| |
Tries to connect to a modbus server.
- Parameters
-
ip | |
port | |
retries | Number of retries getting a connection to the server. Set -1 for infinite retries. |
timeout_ms | between retries |
- Returns
- True if a connection is established, false otherwise.
Definition at line 41 of file pilz_modbus_client.cpp.
◆ isRunning()
bool prbt_hardware_support::PilzModbusClient::isRunning |
( |
| ) |
|
|
inline |
◆ modbus_write_service_cb()
bool prbt_hardware_support::PilzModbusClient::modbus_write_service_cb |
( |
WriteModbusRegister::Request & |
req, |
|
|
WriteModbusRegister::Response & |
res |
|
) |
| |
|
inlineprivate |
Stores the register which have to be send to the modbus server in a local buffer for further processing by the modbus thread.
Definition at line 160 of file pilz_modbus_client.h.
◆ run()
void prbt_hardware_support::PilzModbusClient::run |
( |
| ) |
|
Publishes the register values as messages.
The value of the modbus register is read in a loop. Once a loop the value is published as a message. In order for clients to differentiate between messages notifying about changes in the register the timestamp of the message is only changed if a register value changed.
Definition at line 103 of file pilz_modbus_client.cpp.
◆ sendDisconnectMsg()
void prbt_hardware_support::PilzModbusClient::sendDisconnectMsg |
( |
| ) |
|
|
private |
◆ splitIntoBlocks()
std::vector< std::vector< unsigned short > > prbt_hardware_support::PilzModbusClient::splitIntoBlocks |
( |
std::vector< unsigned short > & |
in | ) |
|
|
static |
Splits a vector of integers into a vector of vectors with consecutive groups.
Definition at line 197 of file pilz_modbus_client.cpp.
◆ terminate()
void prbt_hardware_support::PilzModbusClient::terminate |
( |
| ) |
|
|
inline |
◆ DEFAULT_MODBUS_READ_FREQUENCY_HZ
constexpr double prbt_hardware_support::PilzModbusClient::DEFAULT_MODBUS_READ_FREQUENCY_HZ { 500 } |
|
staticprivate |
◆ DEFAULT_QUEUE_SIZE_MODBUS
constexpr int prbt_hardware_support::PilzModbusClient::DEFAULT_QUEUE_SIZE_MODBUS { 1 } |
|
staticprivate |
◆ modbus_client_
◆ modbus_read_pub_
ros::Publisher prbt_hardware_support::PilzModbusClient::modbus_read_pub_ |
|
private |
◆ modbus_write_service_
◆ modbus_write_sub_
◆ READ_FREQUENCY_HZ
const double prbt_hardware_support::PilzModbusClient::READ_FREQUENCY_HZ |
|
private |
◆ registers_to_read_
std::vector<unsigned short> prbt_hardware_support::PilzModbusClient::registers_to_read_ |
|
private |
◆ RESPONSE_TIMEOUT_MS
const unsigned int prbt_hardware_support::PilzModbusClient::RESPONSE_TIMEOUT_MS |
|
private |
Defines how long we wait for a response from the Modbus-server.
Definition at line 130 of file pilz_modbus_client.h.
◆ state_
std::atomic<State> prbt_hardware_support::PilzModbusClient::state_ { State::not_initialized } |
|
private |
◆ stop_run_
std::atomic_bool prbt_hardware_support::PilzModbusClient::stop_run_ { false } |
|
private |
◆ write_reg_blocks_
std::queue<ModbusRegisterBlock> prbt_hardware_support::PilzModbusClient::write_reg_blocks_ |
|
private |
◆ write_reg_blocks_mutex_
std::mutex prbt_hardware_support::PilzModbusClient::write_reg_blocks_mutex_ |
|
private |
The documentation for this class was generated from the following files: