Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
prbt_hardware_support::PilzModbusClient Class Reference

Connects to a modbus server and publishes the received data into ROS. More...

#include <pilz_modbus_client.h>

Public Member Functions

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 > &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. More...
 
void run ()
 Publishes the register values as messages. More...
 
void terminate ()
 Ends the infinite loop started in method 'run()'. More...
 

Static Public Member Functions

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...
 

Private Types

typedef std::unique_ptr< ModbusClientModbusClientUniquePtr
 
enum  State { not_initialized, initializing, initialized, running }
 States of the Modbus-client. More...
 

Private Member Functions

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 ()
 

Private Attributes

ModbusClientUniquePtr modbus_client_
 
ros::Publisher modbus_read_pub_
 
ros::ServiceServer modbus_write_service_
 
ros::Subscriber modbus_write_sub_
 
const double READ_FREQUENCY_HZ
 Defines how often the Modbus registers are read in. More...
 
std::vector< unsigned short > registers_to_read_
 Registers which have to be read. More...
 
const unsigned int RESPONSE_TIMEOUT_MS
 Defines how long we wait for a response from the Modbus-server. More...
 
std::atomic< Statestate_ { State::not_initialized }
 
std::atomic_bool stop_run_ { false }
 
std::queue< ModbusRegisterBlock > write_reg_blocks_
 
std::mutex write_reg_blocks_mutex_
 

Static Private Attributes

static constexpr double DEFAULT_MODBUS_READ_FREQUENCY_HZ { 500 }
 
static constexpr int DEFAULT_QUEUE_SIZE_MODBUS { 1 }
 

Detailed Description

Connects to a modbus server and publishes the received data into ROS.

Definition at line 39 of file pilz_modbus_client.h.

Member Typedef Documentation

◆ ModbusClientUniquePtr

Definition at line 41 of file pilz_modbus_client.h.

Member Enumeration Documentation

◆ State

States of the Modbus-client.

Enumerator
not_initialized 
initializing 
initialized 
running 

Definition at line 118 of file pilz_modbus_client.h.

Constructor & Destructor Documentation

◆ 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
nhNode handle.
registers_to_readRegisters which have to be read.
modbus_clientModbusClient to use
response_timeout_msTime to wait for a response from Modbus server.
modbus_read_topic_nameName of the topic to which is published.
modbus_write_service_nameName under which the modbus write service is advertised.
read_frequency_hzDefines how often Modbus registers are read in.

Definition at line 27 of file pilz_modbus_client.cpp.

Member Function Documentation

◆ init() [1/2]

bool prbt_hardware_support::PilzModbusClient::init ( const char *  ip,
unsigned int  port 
)

Tries to connect to a modbus server.

Parameters
ip
port
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
retriesNumber of retries getting a connection to the server. Set -1 for infinite retries.
timeout_msbetween 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

True if 'run()' method is active, false if 'run()' method is not active or, currently, finishing.

Definition at line 155 of file pilz_modbus_client.h.

◆ 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

Definition at line 94 of file pilz_modbus_client.cpp.

◆ 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

Ends the infinite loop started in method 'run()'.

Definition at line 150 of file pilz_modbus_client.h.

Member Data Documentation

◆ DEFAULT_MODBUS_READ_FREQUENCY_HZ

constexpr double prbt_hardware_support::PilzModbusClient::DEFAULT_MODBUS_READ_FREQUENCY_HZ { 500 }
staticprivate

Definition at line 135 of file pilz_modbus_client.h.

◆ DEFAULT_QUEUE_SIZE_MODBUS

constexpr int prbt_hardware_support::PilzModbusClient::DEFAULT_QUEUE_SIZE_MODBUS { 1 }
staticprivate

Definition at line 136 of file pilz_modbus_client.h.

◆ modbus_client_

ModbusClientUniquePtr prbt_hardware_support::PilzModbusClient::modbus_client_
private

Definition at line 141 of file pilz_modbus_client.h.

◆ modbus_read_pub_

ros::Publisher prbt_hardware_support::PilzModbusClient::modbus_read_pub_
private

Definition at line 142 of file pilz_modbus_client.h.

◆ modbus_write_service_

ros::ServiceServer prbt_hardware_support::PilzModbusClient::modbus_write_service_
private

Definition at line 144 of file pilz_modbus_client.h.

◆ modbus_write_sub_

ros::Subscriber prbt_hardware_support::PilzModbusClient::modbus_write_sub_
private

Definition at line 143 of file pilz_modbus_client.h.

◆ READ_FREQUENCY_HZ

const double prbt_hardware_support::PilzModbusClient::READ_FREQUENCY_HZ
private

Defines how often the Modbus registers are read in.

Definition at line 132 of file pilz_modbus_client.h.

◆ registers_to_read_

std::vector<unsigned short> prbt_hardware_support::PilzModbusClient::registers_to_read_
private

Registers which have to be read.

Definition at line 127 of file pilz_modbus_client.h.

◆ 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

Definition at line 139 of file pilz_modbus_client.h.

◆ stop_run_

std::atomic_bool prbt_hardware_support::PilzModbusClient::stop_run_ { false }
private

Definition at line 140 of file pilz_modbus_client.h.

◆ write_reg_blocks_

std::queue<ModbusRegisterBlock> prbt_hardware_support::PilzModbusClient::write_reg_blocks_
private

Definition at line 147 of file pilz_modbus_client.h.

◆ write_reg_blocks_mutex_

std::mutex prbt_hardware_support::PilzModbusClient::write_reg_blocks_mutex_
private

Definition at line 146 of file pilz_modbus_client.h.


The documentation for this class was generated from the following files:


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