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

Component that handles Modbus coil read/write operations for 8-channel relay. More...

#include <cp_modbus_relay.hpp>

Inheritance diagram for cl_modbus_tcp_relay::CpModbusRelay:
Inheritance graph
Collaboration diagram for cl_modbus_tcp_relay::CpModbusRelay:
Collaboration graph

Public Member Functions

 CpModbusRelay ()
 
virtual ~CpModbusRelay ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TClient >
void onStateOrthogonalAllocation ()
 Configure component for event posting during orthogonal allocation.
 
bool writeCoil (int channel, bool state)
 
bool readCoil (int channel, bool &state)
 
bool writeAllCoils (bool state)
 
bool writeAllCoils (uint8_t mask)
 
bool readAllCoils (uint8_t &states)
 
template<typename T >
smacc2::SmaccSignalConnection onWriteSuccess (void(T::*callback)(int, bool), T *object)
 
template<typename T >
smacc2::SmaccSignalConnection onWriteFailure (void(T::*callback)(int, const std::string &), T *object)
 
template<typename T >
smacc2::SmaccSignalConnection onReadComplete (void(T::*callback)(uint8_t), T *object)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

smacc2::SmaccSignal< void(int channel, bool state)> onWriteSuccess_
 
smacc2::SmaccSignal< void(int channel, const std::string &error)> onWriteFailure_
 
smacc2::SmaccSignal< void(uint8_t states)> onReadComplete_
 

Static Public Attributes

static constexpr int NUM_CHANNELS = 8
 
static constexpr int COIL_BASE_ADDRESS = 0x0000
 

Private Member Functions

int channelToAddress (int channel) const
 
bool isValidChannel (int channel) const
 

Private Attributes

CpModbusConnectionconnectionComponent_
 
std::function< void()> postWriteSuccessEvent_
 
std::function< void()> postWriteFailureEvent_
 

Additional Inherited Members

- 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 Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Component that handles Modbus coil read/write operations for 8-channel relay.

Responsibilities:

  • Write single coil (channel on/off)
  • Write all coils simultaneously
  • Read single coil status
  • Read all coil statuses
  • Emit operation result signals

Channel numbering: 1-8 (user-friendly) Coil addresses: 0x0000-0x0007 (0-indexed internally)

Definition at line 51 of file cp_modbus_relay.hpp.

Constructor & Destructor Documentation

◆ CpModbusRelay()

cl_modbus_tcp_relay::CpModbusRelay::CpModbusRelay ( )

Definition at line 26 of file cp_modbus_relay.cpp.

26: connectionComponent_(nullptr) {}

◆ ~CpModbusRelay()

cl_modbus_tcp_relay::CpModbusRelay::~CpModbusRelay ( )
virtual

Definition at line 28 of file cp_modbus_relay.cpp.

28{}

Member Function Documentation

◆ channelToAddress()

int cl_modbus_tcp_relay::CpModbusRelay::channelToAddress ( int channel) const
inlineprivate

Definition at line 116 of file cp_modbus_relay.hpp.

116{ return COIL_BASE_ADDRESS + (channel - 1); }

References COIL_BASE_ADDRESS.

Referenced by readCoil(), and writeCoil().

Here is the caller graph for this function:

◆ isValidChannel()

bool cl_modbus_tcp_relay::CpModbusRelay::isValidChannel ( int channel) const
inlineprivate

Definition at line 119 of file cp_modbus_relay.hpp.

119{ return channel >= 1 && channel <= NUM_CHANNELS; }

References NUM_CHANNELS.

Referenced by readCoil(), and writeCoil().

Here is the caller graph for this function:

◆ onInitialize()

void cl_modbus_tcp_relay::CpModbusRelay::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 30 of file cp_modbus_relay.cpp.

31{
32 RCLCPP_INFO(getLogger(), "[CpModbusRelay] Initializing...");
33
34 // Require the connection component
36
38 {
39 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Failed to get CpModbusConnection component");
40 }
41 else
42 {
43 RCLCPP_INFO(getLogger(), "[CpModbusRelay] Initialized with connection component");
44 }
45}
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)

References connectionComponent_, smacc2::ISmaccComponent::getLogger(), and smacc2::ISmaccComponent::requiresComponent().

Here is the call graph for this function:

◆ onReadComplete()

template<typename T >
smacc2::SmaccSignalConnection cl_modbus_tcp_relay::CpModbusRelay::onReadComplete ( void(T::* callback )(uint8_t),
T * object )
inline

Definition at line 104 of file cp_modbus_relay.hpp.

105 {
106 return this->getStateMachine()->createSignalConnection(onReadComplete_, callback, object);
107 }
smacc2::SmaccSignal< void(uint8_t states)> onReadComplete_
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:

◆ onStateOrthogonalAllocation()

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

Configure component for event posting during orthogonal allocation.

Definition at line 66 of file cp_modbus_relay.hpp.

References smacc2::ISmaccComponent::postEvent(), postWriteFailureEvent_, and postWriteSuccessEvent_.

Here is the call graph for this function:

◆ onWriteFailure()

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

Definition at line 97 of file cp_modbus_relay.hpp.

99 {
100 return this->getStateMachine()->createSignalConnection(onWriteFailure_, callback, object);
101 }
smacc2::SmaccSignal< void(int channel, const std::string &error)> onWriteFailure_

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

Here is the call graph for this function:

◆ onWriteSuccess()

template<typename T >
smacc2::SmaccSignalConnection cl_modbus_tcp_relay::CpModbusRelay::onWriteSuccess ( void(T::* callback )(int, bool),
T * object )
inline

Definition at line 91 of file cp_modbus_relay.hpp.

92 {
93 return this->getStateMachine()->createSignalConnection(onWriteSuccess_, callback, object);
94 }
smacc2::SmaccSignal< void(int channel, bool state)> onWriteSuccess_

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

Here is the call graph for this function:

◆ readAllCoils()

bool cl_modbus_tcp_relay::CpModbusRelay::readAllCoils ( uint8_t & states)

Definition at line 183 of file cp_modbus_relay.cpp.

184{
186 {
187 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Not connected to Modbus device");
188 return false;
189 }
190
191 std::lock_guard<std::mutex> lock(connectionComponent_->getMutex());
192 modbus_t * ctx = connectionComponent_->getContext();
193
194 uint8_t coils[NUM_CHANNELS];
195
196 int rc = modbus_read_bits(ctx, COIL_BASE_ADDRESS, NUM_CHANNELS, coils);
197
198 if (rc == -1)
199 {
200 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Read all failed: %s", modbus_strerror(errno));
201 return false;
202 }
203
204 // Convert array to bitmask
205 states = 0;
206 for (int i = 0; i < NUM_CHANNELS; i++)
207 {
208 if (coils[i])
209 {
210 states |= (1 << i);
211 }
212 }
213
214 RCLCPP_DEBUG(getLogger(), "[CpModbusRelay] Read all coils: 0x%02X", states);
215 onReadComplete_(states);
216 return true;
217}

References COIL_BASE_ADDRESS, connectionComponent_, cl_modbus_tcp_relay::CpModbusConnection::getContext(), smacc2::ISmaccComponent::getLogger(), cl_modbus_tcp_relay::CpModbusConnection::getMutex(), cl_modbus_tcp_relay::CpModbusConnection::isConnected(), NUM_CHANNELS, and onReadComplete_.

Referenced by cl_modbus_tcp_relay::CbRelayStatus::readAllChannels().

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

◆ readCoil()

bool cl_modbus_tcp_relay::CpModbusRelay::readCoil ( int channel,
bool & state )

Definition at line 94 of file cp_modbus_relay.cpp.

95{
96 if (!isValidChannel(channel))
97 {
98 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Invalid channel: %d (must be 1-8)", channel);
99 return false;
100 }
101
103 {
104 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Not connected to Modbus device");
105 return false;
106 }
107
108 std::lock_guard<std::mutex> lock(connectionComponent_->getMutex());
109 modbus_t * ctx = connectionComponent_->getContext();
110
111 int address = channelToAddress(channel);
112 uint8_t status;
113
114 int rc = modbus_read_bits(ctx, address, 1, &status);
115
116 if (rc == -1)
117 {
118 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Read failed: %s", modbus_strerror(errno));
119 return false;
120 }
121
122 state = (status != 0);
123 RCLCPP_DEBUG(
124 getLogger(), "[CpModbusRelay] Read coil %d (channel %d) = %s", address, channel,
125 state ? "ON" : "OFF");
126 return true;
127}
bool isValidChannel(int channel) const
int channelToAddress(int channel) const

References channelToAddress(), connectionComponent_, cl_modbus_tcp_relay::CpModbusConnection::getContext(), smacc2::ISmaccComponent::getLogger(), cl_modbus_tcp_relay::CpModbusConnection::getMutex(), cl_modbus_tcp_relay::CpModbusConnection::isConnected(), and isValidChannel().

Referenced by cl_modbus_tcp_relay::CbRelayStatus::readSingleChannel().

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

◆ writeAllCoils() [1/2]

bool cl_modbus_tcp_relay::CpModbusRelay::writeAllCoils ( bool state)

Definition at line 129 of file cp_modbus_relay.cpp.

130{
131 // Create a mask with all bits set or cleared
132 uint8_t mask = state ? 0xFF : 0x00;
133 return writeAllCoils(mask);
134}

References writeAllCoils().

Referenced by cl_modbus_tcp_relay::CbAllRelaysOff::onEntry(), cl_modbus_tcp_relay::CbAllRelaysOn::onEntry(), and writeAllCoils().

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

◆ writeAllCoils() [2/2]

bool cl_modbus_tcp_relay::CpModbusRelay::writeAllCoils ( uint8_t mask)

Definition at line 136 of file cp_modbus_relay.cpp.

137{
139 {
140 std::string error = "Not connected to Modbus device";
141 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] %s", error.c_str());
142 onWriteFailure_(0, error);
144 return false;
145 }
146
147 std::lock_guard<std::mutex> lock(connectionComponent_->getMutex());
148 modbus_t * ctx = connectionComponent_->getContext();
149
150 // Convert bitmask to array of coil states
151 uint8_t coils[NUM_CHANNELS];
152 for (int i = 0; i < NUM_CHANNELS; i++)
153 {
154 coils[i] = (mask & (1 << i)) ? TRUE : FALSE;
155 }
156
157 RCLCPP_INFO(
158 getLogger(), "[CpModbusRelay] Writing all %d coils with mask 0x%02X", NUM_CHANNELS, mask);
159
160 int rc = modbus_write_bits(ctx, COIL_BASE_ADDRESS, NUM_CHANNELS, coils);
161
162 if (rc == -1)
163 {
164 std::string error = modbus_strerror(errno);
165 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Write all failed: %s", error.c_str());
166 onWriteFailure_(0, error);
168 return false;
169 }
170
171 RCLCPP_INFO(getLogger(), "[CpModbusRelay] Write all successful");
172
173 // Emit success for each channel that was turned on
174 for (int i = 0; i < NUM_CHANNELS; i++)
175 {
176 bool state = (mask & (1 << i)) != 0;
177 onWriteSuccess_(i + 1, state);
178 }
180 return true;
181}

References COIL_BASE_ADDRESS, connectionComponent_, cl_modbus_tcp_relay::CpModbusConnection::getContext(), smacc2::ISmaccComponent::getLogger(), cl_modbus_tcp_relay::CpModbusConnection::getMutex(), cl_modbus_tcp_relay::CpModbusConnection::isConnected(), NUM_CHANNELS, onWriteFailure_, onWriteSuccess_, postWriteFailureEvent_, and postWriteSuccessEvent_.

Here is the call graph for this function:

◆ writeCoil()

bool cl_modbus_tcp_relay::CpModbusRelay::writeCoil ( int channel,
bool state )

Definition at line 47 of file cp_modbus_relay.cpp.

48{
49 if (!isValidChannel(channel))
50 {
51 std::string error = "Invalid channel: " + std::to_string(channel) + " (must be 1-8)";
52 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] %s", error.c_str());
53 onWriteFailure_(channel, error);
55 return false;
56 }
57
59 {
60 std::string error = "Not connected to Modbus device";
61 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] %s", error.c_str());
62 onWriteFailure_(channel, error);
64 return false;
65 }
66
67 std::lock_guard<std::mutex> lock(connectionComponent_->getMutex());
68 modbus_t * ctx = connectionComponent_->getContext();
69
70 int address = channelToAddress(channel);
71 int value = state ? TRUE : FALSE;
72
73 RCLCPP_INFO(
74 getLogger(), "[CpModbusRelay] Writing coil %d (channel %d) = %s", address, channel,
75 state ? "ON" : "OFF");
76
77 int rc = modbus_write_bit(ctx, address, value);
78
79 if (rc == -1)
80 {
81 std::string error = modbus_strerror(errno);
82 RCLCPP_ERROR(getLogger(), "[CpModbusRelay] Write failed: %s", error.c_str());
83 onWriteFailure_(channel, error);
85 return false;
86 }
87
88 RCLCPP_INFO(getLogger(), "[CpModbusRelay] Write successful");
89 onWriteSuccess_(channel, state);
91 return true;
92}

References channelToAddress(), connectionComponent_, cl_modbus_tcp_relay::CpModbusConnection::getContext(), smacc2::ISmaccComponent::getLogger(), cl_modbus_tcp_relay::CpModbusConnection::getMutex(), cl_modbus_tcp_relay::CpModbusConnection::isConnected(), isValidChannel(), onWriteFailure_, onWriteSuccess_, postWriteFailureEvent_, and postWriteSuccessEvent_.

Referenced by cl_modbus_tcp_relay::CbRelayOff::onEntry(), and cl_modbus_tcp_relay::CbRelayOn::onEntry().

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

Member Data Documentation

◆ COIL_BASE_ADDRESS

int cl_modbus_tcp_relay::CpModbusRelay::COIL_BASE_ADDRESS = 0x0000
staticconstexpr

Definition at line 55 of file cp_modbus_relay.hpp.

Referenced by channelToAddress(), readAllCoils(), and writeAllCoils().

◆ connectionComponent_

CpModbusConnection* cl_modbus_tcp_relay::CpModbusRelay::connectionComponent_
private

Definition at line 110 of file cp_modbus_relay.hpp.

Referenced by onInitialize(), readAllCoils(), readCoil(), writeAllCoils(), and writeCoil().

◆ NUM_CHANNELS

int cl_modbus_tcp_relay::CpModbusRelay::NUM_CHANNELS = 8
staticconstexpr

Definition at line 54 of file cp_modbus_relay.hpp.

Referenced by isValidChannel(), readAllCoils(), and writeAllCoils().

◆ onReadComplete_

smacc2::SmaccSignal<void(uint8_t states)> cl_modbus_tcp_relay::CpModbusRelay::onReadComplete_

Definition at line 87 of file cp_modbus_relay.hpp.

Referenced by readAllCoils().

◆ onWriteFailure_

smacc2::SmaccSignal<void(int channel, const std::string & error)> cl_modbus_tcp_relay::CpModbusRelay::onWriteFailure_

Definition at line 86 of file cp_modbus_relay.hpp.

Referenced by writeAllCoils(), and writeCoil().

◆ onWriteSuccess_

smacc2::SmaccSignal<void(int channel, bool state)> cl_modbus_tcp_relay::CpModbusRelay::onWriteSuccess_

Definition at line 85 of file cp_modbus_relay.hpp.

Referenced by writeAllCoils(), and writeCoil().

◆ postWriteFailureEvent_

std::function<void()> cl_modbus_tcp_relay::CpModbusRelay::postWriteFailureEvent_
private

Definition at line 113 of file cp_modbus_relay.hpp.

Referenced by onStateOrthogonalAllocation(), writeAllCoils(), and writeCoil().

◆ postWriteSuccessEvent_

std::function<void()> cl_modbus_tcp_relay::CpModbusRelay::postWriteSuccessEvent_
private

Definition at line 112 of file cp_modbus_relay.hpp.

Referenced by onStateOrthogonalAllocation(), writeAllCoils(), and writeCoil().


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