SMACC2
Loading...
Searching...
No Matches
cl_modbus_tcp_relay::CpModbusConnection Class Reference

Component that manages Modbus TCP connection lifecycle and heartbeat monitoring. More...

#include <cp_modbus_connection.hpp>

Inheritance diagram for cl_modbus_tcp_relay::CpModbusConnection:
Inheritance graph
Collaboration diagram for cl_modbus_tcp_relay::CpModbusConnection:
Collaboration graph

Public Member Functions

 CpModbusConnection ()
 
virtual ~CpModbusConnection ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TClient >
void onStateOrthogonalAllocation ()
 Configure component for event posting during orthogonal allocation.
 
bool connect ()
 
void disconnect ()
 
bool reconnect ()
 
bool isConnected () const
 
modbus_t * getContext ()
 
std::mutex & getMutex ()
 
std::string getIpAddress () const
 
int getPort () const
 
int getSlaveId () const
 
template<typename T >
smacc2::SmaccSignalConnection onConnectionLost (void(T::*callback)(), T *object)
 
template<typename T >
smacc2::SmaccSignalConnection onConnectionRestored (void(T::*callback)(), T *object)
 
template<typename T >
smacc2::SmaccSignalConnection onConnectionError (void(T::*callback)(const std::string &), T *object)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 
- Public Member Functions inherited from smacc2::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (rclcpp::Duration duration)
 
void executeUpdate (rclcpp::Node::SharedPtr node)
 
void setUpdatePeriod (rclcpp::Duration duration)
 

Public Attributes

smacc2::SmaccSignal< void()> onConnectionLost_
 
smacc2::SmaccSignal< void()> onConnectionRestored_
 
smacc2::SmaccSignal< void(const std::string &)> onConnectionError_
 

Protected Member Functions

void update () override
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Member Functions inherited from smacc2::ISmaccUpdatable

Private Member Functions

template<typename T >
void declareAndLoadParam (const std::string &name, T &value, const T &default_val)
 

Private Attributes

std::string ip_address_
 
int port_
 
int slave_id_
 
int heartbeat_interval_ms_
 
bool connect_on_init_
 
modbus_t * ctx_
 
bool connected_
 
std::mutex mutex_
 
std::function< void()> postConnectionLostEvent_
 
std::function< void()> postConnectionRestoredEvent_
 

Additional Inherited Members

- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Component that manages Modbus TCP connection lifecycle and heartbeat monitoring.

Responsibilities:

  • Create/destroy modbus_t context
  • Manage TCP connection state
  • Periodic heartbeat via ISmaccUpdatable (reads coil status to verify connectivity)
  • Emit connection state change signals
  • Thread-safe connection access via mutex

Configuration is loaded from YAML parameters: modbus_relay.ip_address: IP address of the relay (default: "192.168.1.254") modbus_relay.port: Modbus TCP port (default: 502) modbus_relay.slave_id: Modbus slave ID (default: 1) modbus_relay.heartbeat_interval_ms: Heartbeat check interval (default: 1000) modbus_relay.connect_on_init: Connect automatically on init (default: true)

Definition at line 56 of file cp_modbus_connection.hpp.

Constructor & Destructor Documentation

◆ CpModbusConnection()

cl_modbus_tcp_relay::CpModbusConnection::CpModbusConnection ( )

◆ ~CpModbusConnection()

cl_modbus_tcp_relay::CpModbusConnection::~CpModbusConnection ( )
virtual

Definition at line 38 of file cp_modbus_connection.cpp.

39{
40 disconnect();
41 if (ctx_)
42 {
43 modbus_free(ctx_);
44 ctx_ = nullptr;
45 }
46}

References ctx_, and disconnect().

Here is the call graph for this function:

Member Function Documentation

◆ connect()

bool cl_modbus_tcp_relay::CpModbusConnection::connect ( )

Definition at line 114 of file cp_modbus_connection.cpp.

115{
116 std::lock_guard<std::mutex> lock(mutex_);
117
118 if (!ctx_)
119 {
120 RCLCPP_ERROR(getLogger(), "[CpModbusConnection] Cannot connect: context is null");
121 return false;
122 }
123
124 if (connected_)
125 {
126 RCLCPP_DEBUG(getLogger(), "[CpModbusConnection] Already connected");
127 return true;
128 }
129
130 RCLCPP_INFO(
131 getLogger(), "[CpModbusConnection] Connecting to %s:%d...", ip_address_.c_str(), port_);
132
133 int rc = modbus_connect(ctx_);
134 if (rc == -1)
135 {
136 std::string error_msg = std::string("Connection failed: ") + modbus_strerror(errno);
137 RCLCPP_ERROR(getLogger(), "[CpModbusConnection] %s", error_msg.c_str());
138 onConnectionError_(error_msg);
139 return false;
140 }
141
142 connected_ = true;
143 RCLCPP_INFO(getLogger(), "[CpModbusConnection] Connected successfully");
144 return true;
145}
smacc2::SmaccSignal< void(const std::string &)> onConnectionError_
rclcpp::Logger getLogger() const

References connected_, ctx_, smacc2::ISmaccComponent::getLogger(), ip_address_, mutex_, onConnectionError_, and port_.

Referenced by onInitialize(), and reconnect().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ declareAndLoadParam()

template<typename T >
void cl_modbus_tcp_relay::CpModbusConnection::declareAndLoadParam ( const std::string & name,
T & value,
const T & default_val )
private

Definition at line 49 of file cp_modbus_connection.cpp.

51{
52 auto node = getNode();
53 if (!node->has_parameter(name))
54 {
55 node->declare_parameter(name, default_val);
56 }
57 node->get_parameter(name, value);
58}
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getNode().

Referenced by onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disconnect()

void cl_modbus_tcp_relay::CpModbusConnection::disconnect ( )

Definition at line 147 of file cp_modbus_connection.cpp.

148{
149 std::lock_guard<std::mutex> lock(mutex_);
150
151 if (ctx_ && connected_)
152 {
153 modbus_close(ctx_);
154 connected_ = false;
155 RCLCPP_INFO(getLogger(), "[CpModbusConnection] Disconnected");
156 }
157}

References connected_, ctx_, smacc2::ISmaccComponent::getLogger(), and mutex_.

Referenced by reconnect(), and ~CpModbusConnection().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getContext()

modbus_t * cl_modbus_tcp_relay::CpModbusConnection::getContext ( )

◆ getIpAddress()

std::string cl_modbus_tcp_relay::CpModbusConnection::getIpAddress ( ) const
inline

Definition at line 88 of file cp_modbus_connection.hpp.

88{ return ip_address_; }

References ip_address_.

◆ getMutex()

std::mutex & cl_modbus_tcp_relay::CpModbusConnection::getMutex ( )

◆ getPort()

int cl_modbus_tcp_relay::CpModbusConnection::getPort ( ) const
inline

Definition at line 89 of file cp_modbus_connection.hpp.

89{ return port_; }

References port_.

◆ getSlaveId()

int cl_modbus_tcp_relay::CpModbusConnection::getSlaveId ( ) const
inline

Definition at line 90 of file cp_modbus_connection.hpp.

90{ return slave_id_; }

References slave_id_.

◆ isConnected()

bool cl_modbus_tcp_relay::CpModbusConnection::isConnected ( ) const

Definition at line 166 of file cp_modbus_connection.cpp.

167{
168 std::lock_guard<std::mutex> lock(mutex_);
169 return connected_;
170}

References connected_, and mutex_.

Referenced by cl_modbus_tcp_relay::CpModbusRelay::readAllCoils(), cl_modbus_tcp_relay::CpModbusRelay::readCoil(), cl_modbus_tcp_relay::CpModbusRelay::writeAllCoils(), and cl_modbus_tcp_relay::CpModbusRelay::writeCoil().

Here is the caller graph for this function:

◆ onConnectionError()

template<typename T >
smacc2::SmaccSignalConnection cl_modbus_tcp_relay::CpModbusConnection::onConnectionError ( void(T::* callback )(const std::string &),
T * object )
inline

Definition at line 111 of file cp_modbus_connection.hpp.

113 {
114 return this->getStateMachine()->createSignalConnection(onConnectionError_, callback, object);
115 }
ISmaccStateMachine * getStateMachine()
smacc2::SmaccSignalConnection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onConnectionLost()

template<typename T >
smacc2::SmaccSignalConnection cl_modbus_tcp_relay::CpModbusConnection::onConnectionLost ( void(T::* callback )(),
T * object )
inline

Definition at line 99 of file cp_modbus_connection.hpp.

100 {
101 return this->getStateMachine()->createSignalConnection(onConnectionLost_, callback, object);
102 }
smacc2::SmaccSignal< void()> onConnectionLost_

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onConnectionRestored()

template<typename T >
smacc2::SmaccSignalConnection cl_modbus_tcp_relay::CpModbusConnection::onConnectionRestored ( void(T::* callback )(),
T * object )
inline

Definition at line 105 of file cp_modbus_connection.hpp.

106 {
107 return this->getStateMachine()->createSignalConnection(onConnectionRestored_, callback, object);
108 }
smacc2::SmaccSignal< void()> onConnectionRestored_

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onInitialize()

void cl_modbus_tcp_relay::CpModbusConnection::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 74 of file cp_modbus_connection.cpp.

75{
76 RCLCPP_INFO(getLogger(), "[CpModbusConnection] Initializing...");
77
78 // Load configuration from YAML with defaults
79 declareAndLoadParam("modbus_relay.ip_address", ip_address_, std::string("192.168.1.254"));
80 declareAndLoadParam("modbus_relay.port", port_, 502);
81 declareAndLoadParam("modbus_relay.slave_id", slave_id_, 1);
82 declareAndLoadParam("modbus_relay.heartbeat_interval_ms", heartbeat_interval_ms_, 1000);
83 declareAndLoadParam("modbus_relay.connect_on_init", connect_on_init_, true);
84
85 RCLCPP_INFO(
86 getLogger(),
87 "[CpModbusConnection] Config: %s:%d (slave=%d, heartbeat=%dms, connect_on_init=%s)",
89 connect_on_init_ ? "true" : "false");
90
91 // Set update period for heartbeat
92 this->setUpdatePeriod(rclcpp::Duration::from_seconds(heartbeat_interval_ms_ / 1000.0));
93
94 // Create modbus context
95 ctx_ = modbus_new_tcp(ip_address_.c_str(), port_);
96 if (ctx_)
97 {
98 modbus_set_slave(ctx_, slave_id_);
99 modbus_set_response_timeout(ctx_, 1, 0); // 1 second timeout
100
102 {
103 connect();
104 }
105 }
106 else
107 {
108 std::string error_msg = "Failed to create modbus context";
109 RCLCPP_ERROR(getLogger(), "[CpModbusConnection] %s", error_msg.c_str());
110 onConnectionError_(error_msg);
111 }
112}
void declareAndLoadParam(const std::string &name, T &value, const T &default_val)
void setUpdatePeriod(rclcpp::Duration duration)

References connect(), connect_on_init_, ctx_, declareAndLoadParam(), smacc2::ISmaccComponent::getLogger(), heartbeat_interval_ms_, ip_address_, onConnectionError_, port_, smacc2::ISmaccUpdatable::setUpdatePeriod(), and slave_id_.

Here is the call graph for this function:

◆ onStateOrthogonalAllocation()

template<typename TOrthogonal , typename TClient >
void cl_modbus_tcp_relay::CpModbusConnection::onStateOrthogonalAllocation ( )
inline

Configure component for event posting during orthogonal allocation.

Definition at line 68 of file cp_modbus_connection.hpp.

References postConnectionLostEvent_, postConnectionRestoredEvent_, and smacc2::ISmaccComponent::postEvent().

Here is the call graph for this function:

◆ reconnect()

bool cl_modbus_tcp_relay::CpModbusConnection::reconnect ( )

Definition at line 159 of file cp_modbus_connection.cpp.

160{
161 RCLCPP_INFO(getLogger(), "[CpModbusConnection] Reconnecting...");
162 disconnect();
163 return connect();
164}

References connect(), disconnect(), and smacc2::ISmaccComponent::getLogger().

Here is the call graph for this function:

◆ update()

void cl_modbus_tcp_relay::CpModbusConnection::update ( )
overrideprotectedvirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 176 of file cp_modbus_connection.cpp.

177{
178 std::lock_guard<std::mutex> lock(mutex_);
179
180 if (!ctx_)
181 {
182 return;
183 }
184
185 if (!connected_)
186 {
187 // Try to reconnect if not connected
188 RCLCPP_DEBUG(getLogger(), "[CpModbusConnection] Not connected, attempting to connect...");
189 int rc = modbus_connect(ctx_);
190 if (rc == 0)
191 {
192 connected_ = true;
193 RCLCPP_INFO(getLogger(), "[CpModbusConnection] Connection restored");
196 {
198 }
199 }
200 return;
201 }
202
203 // Heartbeat: Try to read a single coil to verify connectivity
204 uint8_t status;
205 int rc = modbus_read_bits(ctx_, 0x0000, 1, &status);
206
207 if (rc == -1)
208 {
209 connected_ = false;
210 std::string error_msg = modbus_strerror(errno);
211 RCLCPP_WARN(getLogger(), "[CpModbusConnection] Heartbeat failed: %s", error_msg.c_str());
214 {
216 }
217 }
218 else
219 {
220 RCLCPP_DEBUG(getLogger(), "[CpModbusConnection] Heartbeat OK (coil 0 status: %d)", status);
221 }
222}

References connected_, ctx_, smacc2::ISmaccComponent::getLogger(), mutex_, onConnectionLost_, onConnectionRestored_, postConnectionLostEvent_, and postConnectionRestoredEvent_.

Here is the call graph for this function:

Member Data Documentation

◆ connect_on_init_

bool cl_modbus_tcp_relay::CpModbusConnection::connect_on_init_
private

Definition at line 126 of file cp_modbus_connection.hpp.

Referenced by onInitialize().

◆ connected_

bool cl_modbus_tcp_relay::CpModbusConnection::connected_
private

Definition at line 130 of file cp_modbus_connection.hpp.

Referenced by connect(), disconnect(), isConnected(), and update().

◆ ctx_

modbus_t* cl_modbus_tcp_relay::CpModbusConnection::ctx_
private

◆ heartbeat_interval_ms_

int cl_modbus_tcp_relay::CpModbusConnection::heartbeat_interval_ms_
private

Definition at line 125 of file cp_modbus_connection.hpp.

Referenced by onInitialize().

◆ ip_address_

std::string cl_modbus_tcp_relay::CpModbusConnection::ip_address_
private

Definition at line 122 of file cp_modbus_connection.hpp.

Referenced by connect(), getIpAddress(), and onInitialize().

◆ mutex_

std::mutex cl_modbus_tcp_relay::CpModbusConnection::mutex_
mutableprivate

Definition at line 131 of file cp_modbus_connection.hpp.

Referenced by connect(), disconnect(), getMutex(), isConnected(), and update().

◆ onConnectionError_

smacc2::SmaccSignal<void(const std::string &)> cl_modbus_tcp_relay::CpModbusConnection::onConnectionError_

Definition at line 95 of file cp_modbus_connection.hpp.

Referenced by connect(), and onInitialize().

◆ onConnectionLost_

smacc2::SmaccSignal<void()> cl_modbus_tcp_relay::CpModbusConnection::onConnectionLost_

Definition at line 93 of file cp_modbus_connection.hpp.

Referenced by update().

◆ onConnectionRestored_

smacc2::SmaccSignal<void()> cl_modbus_tcp_relay::CpModbusConnection::onConnectionRestored_

Definition at line 94 of file cp_modbus_connection.hpp.

Referenced by update().

◆ port_

int cl_modbus_tcp_relay::CpModbusConnection::port_
private

Definition at line 123 of file cp_modbus_connection.hpp.

Referenced by connect(), getPort(), and onInitialize().

◆ postConnectionLostEvent_

std::function<void()> cl_modbus_tcp_relay::CpModbusConnection::postConnectionLostEvent_
private

Definition at line 134 of file cp_modbus_connection.hpp.

Referenced by onStateOrthogonalAllocation(), and update().

◆ postConnectionRestoredEvent_

std::function<void()> cl_modbus_tcp_relay::CpModbusConnection::postConnectionRestoredEvent_
private

Definition at line 135 of file cp_modbus_connection.hpp.

Referenced by onStateOrthogonalAllocation(), and update().

◆ slave_id_

int cl_modbus_tcp_relay::CpModbusConnection::slave_id_
private

Definition at line 124 of file cp_modbus_connection.hpp.

Referenced by getSlaveId(), and onInitialize().


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