Offers a modbus server and read/write functionality via subscription/publication.
More...
#include <pilz_modbus_server_mock.h>
|
bool | init (const char *ip, unsigned int port) |
| Allocates needed resources for running the server. More...
|
|
| PilzModbusServerMock (const unsigned int &holding_register_size) |
|
RegCont | readHoldingRegister (const RegCont::size_type start_index, const RegCont::size_type num_reg_to_read) |
| Reads the specified number of registers, beginning at the specified start point from the holding register. More...
|
|
void | run () |
| Run the server and publish the register values as messages. The value of the modbus register is read in a loop. Once in a loop pass 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. More...
|
|
void | setHoldingRegister (std::initializer_list< std::pair< unsigned int, uint16_t > > reg_list) |
|
void | setHoldingRegister (const RegCont &data, unsigned int start_index) |
| Set the values in the holding register. More...
|
|
void | setTerminateFlag () |
|
void | start (const char *ip, const unsigned int port) |
| Start the modbus server and make it accessible for clients. More...
|
|
void | startAsync (const char *ip, const unsigned int port) |
| Start the modbus server asynchronously and make it accessible for clients. More...
|
|
void | terminate () |
| Terminate the Server. Reading or connecting to it will fail. More...
|
|
| ~PilzModbusServerMock () |
|
Offers a modbus server and read/write functionality via subscription/publication.
Definition at line 40 of file pilz_modbus_server_mock.h.
◆ PilzModbusServerMock()
prbt_hardware_support::PilzModbusServerMock::PilzModbusServerMock |
( |
const unsigned int & |
holding_register_size | ) |
|
◆ ~PilzModbusServerMock()
prbt_hardware_support::PilzModbusServerMock::~PilzModbusServerMock |
( |
| ) |
|
◆ init()
bool prbt_hardware_support::PilzModbusServerMock::init |
( |
const char * |
ip, |
|
|
unsigned int |
port |
|
) |
| |
Allocates needed resources for running the server.
This needs to be called before a successful run()
- Parameters
-
ip | The ip the server attaches to |
port | The used port |
- Returns
- True on success, false otherwise
Definition at line 57 of file pilz_modbus_server_mock.cpp.
◆ readHoldingRegister()
RegCont prbt_hardware_support::PilzModbusServerMock::readHoldingRegister |
( |
const RegCont::size_type |
start_index, |
|
|
const RegCont::size_type |
num_reg_to_read |
|
) |
| |
Reads the specified number of registers, beginning at the specified start point from the holding register.
- Parameters
-
start_index | Index of first register to read. |
num_reg_to_read | Number of registers to read. |
- Returns
- the registers which were read.
Definition at line 121 of file pilz_modbus_server_mock.cpp.
◆ run()
void prbt_hardware_support::PilzModbusServerMock::run |
( |
| ) |
|
Run the server and publish the register values as messages. The value of the modbus register is read in a loop. Once in a loop pass 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 149 of file pilz_modbus_server_mock.cpp.
◆ setHoldingRegister() [1/2]
void prbt_hardware_support::PilzModbusServerMock::setHoldingRegister |
( |
std::initializer_list< std::pair< unsigned int, uint16_t > > |
reg_list | ) |
|
◆ setHoldingRegister() [2/2]
void prbt_hardware_support::PilzModbusServerMock::setHoldingRegister |
( |
const RegCont & |
data, |
|
|
unsigned int |
start_index |
|
) |
| |
Set the values in the holding register.
- Parameters
-
data | The values in the holding register |
start_index | The index from where the value is set, other values remain untouched. |
Definition at line 94 of file pilz_modbus_server_mock.cpp.
◆ setTerminateFlag()
void prbt_hardware_support::PilzModbusServerMock::setTerminateFlag |
( |
| ) |
|
|
inline |
◆ shutdownSignalReceived()
bool prbt_hardware_support::PilzModbusServerMock::shutdownSignalReceived |
( |
| ) |
|
|
inlineprivate |
◆ start()
void prbt_hardware_support::PilzModbusServerMock::start |
( |
const char * |
ip, |
|
|
const unsigned int |
port |
|
) |
| |
Start the modbus server and make it accessible for clients.
- Parameters
-
ip | The ip the server attaches to |
port | The used port |
Definition at line 134 of file pilz_modbus_server_mock.cpp.
◆ startAsync()
void prbt_hardware_support::PilzModbusServerMock::startAsync |
( |
const char * |
ip, |
|
|
const unsigned int |
port |
|
) |
| |
Start the modbus server asynchronously and make it accessible for clients.
- Parameters
-
ip | The ip the server attaches to |
port | The used port |
Returns as soon as it is running
Definition at line 140 of file pilz_modbus_server_mock.cpp.
◆ terminate()
void prbt_hardware_support::PilzModbusServerMock::terminate |
( |
| ) |
|
|
inline |
◆ DISCONNECT_TIMEOUT_IN_SEC
constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::DISCONNECT_TIMEOUT_IN_SEC { 1 } |
|
staticprivate |
◆ DISCONNECT_TIMEOUT_IN_USEC
constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::DISCONNECT_TIMEOUT_IN_USEC { 0 } |
|
staticprivate |
◆ holding_register_size_
const unsigned int prbt_hardware_support::PilzModbusServerMock::holding_register_size_ |
|
private |
◆ mb_mapping_
modbus_mapping_t* prbt_hardware_support::PilzModbusServerMock::mb_mapping_ { nullptr } |
|
private |
◆ modbus_connection_
modbus_t* prbt_hardware_support::PilzModbusServerMock::modbus_connection_ { nullptr } |
|
private |
◆ modbus_register_access_mutex
std::mutex prbt_hardware_support::PilzModbusServerMock::modbus_register_access_mutex |
|
private |
◆ RESPONSE_TIMEOUT_IN_SEC
constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::RESPONSE_TIMEOUT_IN_SEC { 0 } |
|
staticprivate |
◆ RESPONSE_TIMEOUT_IN_USEC
constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::RESPONSE_TIMEOUT_IN_USEC { 10000 } |
|
staticprivate |
◆ running_cv_
std::condition_variable prbt_hardware_support::PilzModbusServerMock::running_cv_ |
|
private |
◆ running_mutex_
std::mutex prbt_hardware_support::PilzModbusServerMock::running_mutex_ |
|
private |
◆ socket_
int prbt_hardware_support::PilzModbusServerMock::socket_ { -1 } |
|
private |
◆ terminate_
std::atomic_bool prbt_hardware_support::PilzModbusServerMock::terminate_ { false } |
|
private |
◆ terminate_register_idx_
const unsigned int prbt_hardware_support::PilzModbusServerMock::terminate_register_idx_ |
|
private |
◆ TERMINATE_SIGNAL
constexpr uint16_t prbt_hardware_support::PilzModbusServerMock::TERMINATE_SIGNAL { 1 } |
|
staticprivate |
◆ thread_
std::thread prbt_hardware_support::PilzModbusServerMock::thread_ |
|
private |
The documentation for this class was generated from the following files: