#include <handler.hpp>
Public Member Functions | |
| void | clearData () |
| const std::vector< std::shared_ptr< DataType > > | getData () |
| Handler (const std::shared_ptr< ros::NodeHandle > nh, const std::string name, const std::shared_ptr< ros::Publisher > error_pub, const std::string server_ip, const modbus_error_recovery_mode recovery=MODBUS_ERROR_RECOVERY_NONE, const unsigned server_port=MODBUS_TCP_DEFAULT_PORT) | |
| void | setData (const std::vector< std::shared_ptr< DataType >> &data) |
| void | stop () |
| ~Handler () | |
Private Member Functions | |
| void | readData (const std::size_t index) |
Private Attributes | |
| modbus_t * | ctx_ |
| std::vector< std::shared_ptr< DataType > > | data_ |
| std::shared_ptr< ros::Publisher > | error_publisher_ |
| std::mutex | modbus_mutex_ |
| std::string | name_ |
| std::shared_ptr< ros::NodeHandle > | nh_ |
| std::atomic< bool > | run_ |
| std::vector< std::unique_ptr< std::thread > > | threads_ |
Definition at line 22 of file handler.hpp.
| industrial_modbus_tcp::Handler::Handler | ( | const std::shared_ptr< ros::NodeHandle > | nh, |
| const std::string | name, | ||
| const std::shared_ptr< ros::Publisher > | error_pub, | ||
| const std::string | server_ip, | ||
| const modbus_error_recovery_mode | recovery = MODBUS_ERROR_RECOVERY_NONE, |
||
| const unsigned | server_port = MODBUS_TCP_DEFAULT_PORT |
||
| ) |
Definition at line 6 of file handler.cpp.
| industrial_modbus_tcp::Handler::~Handler | ( | ) |
Definition at line 37 of file handler.cpp.
| void industrial_modbus_tcp::Handler::clearData | ( | ) |
Clear vector of data fetched (calls stop())
Definition at line 56 of file handler.cpp.
| const std::vector< std::shared_ptr< DataType > > industrial_modbus_tcp::Handler::getData | ( | ) |
Data that are currently fetched
Definition at line 77 of file handler.cpp.
|
private |
Thread safe function to retrieve data using the information in data_
| index | the data_ index |
Definition at line 82 of file handler.cpp.
| void industrial_modbus_tcp::Handler::setData | ( | const std::vector< std::shared_ptr< DataType >> & | data | ) |
Set data to be fetched (starts fetching data)
Definition at line 64 of file handler.cpp.
| void industrial_modbus_tcp::Handler::stop | ( | ) |
Stop fetching data
Definition at line 44 of file handler.cpp.
|
private |
Modbus structure
Definition at line 84 of file handler.hpp.
|
private |
Data to be fetched on the Modbus server How fast Topic to publish
Definition at line 91 of file handler.hpp.
|
private |
Publisher for errors
Definition at line 63 of file handler.hpp.
|
private |
A modbus context is supposedely thread safe (https://libmodbus.org/docs/v3.0.6/) This is not the case, so this mutex makes sure we have no concurent calls to the modbus conctext
Definition at line 97 of file handler.hpp.
|
private |
Name of the handler
Definition at line 79 of file handler.hpp.
|
private |
Node handle
Definition at line 58 of file handler.hpp.
|
private |
Wether the threads are running or not
Definition at line 74 of file handler.hpp.
|
private |
One thread per data fetched
Definition at line 102 of file handler.hpp.