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

Offers a modbus server and read/write functionality via subscription/publication. More...

#include <pilz_modbus_server_mock.h>

Public Member Functions

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

Private Member Functions

bool shutdownSignalReceived ()
 

Private Attributes

const unsigned int holding_register_size_
 
modbus_mapping_t * mb_mapping_ { nullptr }
 
modbus_t * modbus_connection_ { nullptr }
 
std::mutex modbus_register_access_mutex
 
std::condition_variable running_cv_
 
std::mutex running_mutex_
 
int socket_ { -1 }
 Modbus. More...
 
std::atomic_bool terminate_ { false }
 
const unsigned int terminate_register_idx_
 Index of register for server shutdown signal. More...
 
std::thread thread_
 

Static Private Attributes

static constexpr uint32_t DISCONNECT_TIMEOUT_IN_SEC { 1 }
 
static constexpr uint32_t DISCONNECT_TIMEOUT_IN_USEC { 0 }
 
static constexpr uint32_t RESPONSE_TIMEOUT_IN_SEC { 0 }
 
static constexpr uint32_t RESPONSE_TIMEOUT_IN_USEC { 10000 }
 
static constexpr uint16_t TERMINATE_SIGNAL { 1 }
 Register value which indicates that server has to shutdown. More...
 

Detailed Description

Offers a modbus server and read/write functionality via subscription/publication.

Definition at line 40 of file pilz_modbus_server_mock.h.

Constructor & Destructor Documentation

◆ PilzModbusServerMock()

prbt_hardware_support::PilzModbusServerMock::PilzModbusServerMock ( const unsigned int &  holding_register_size)

Definition at line 27 of file pilz_modbus_server_mock.cpp.

◆ ~PilzModbusServerMock()

prbt_hardware_support::PilzModbusServerMock::~PilzModbusServerMock ( )

Definition at line 45 of file pilz_modbus_server_mock.cpp.

Member Function Documentation

◆ 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
ipThe ip the server attaches to
portThe 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_indexIndex of first register to read.
num_reg_to_readNumber 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)

Definition at line 70 of file pilz_modbus_server_mock.cpp.

◆ setHoldingRegister() [2/2]

void prbt_hardware_support::PilzModbusServerMock::setHoldingRegister ( const RegCont data,
unsigned int  start_index 
)

Set the values in the holding register.

Parameters
dataThe values in the holding register
start_indexThe 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

Definition at line 152 of file pilz_modbus_server_mock.h.

◆ shutdownSignalReceived()

bool prbt_hardware_support::PilzModbusServerMock::shutdownSignalReceived ( )
inlineprivate
Returns
True if the server is told to shutdown via Modbus msg, false otherwise.

Definition at line 171 of file pilz_modbus_server_mock.h.

◆ 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
ipThe ip the server attaches to
portThe 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
ipThe ip the server attaches to
portThe 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

Terminate the Server. Reading or connecting to it will fail.

Definition at line 158 of file pilz_modbus_server_mock.h.

Member Data Documentation

◆ DISCONNECT_TIMEOUT_IN_SEC

constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::DISCONNECT_TIMEOUT_IN_SEC { 1 }
staticprivate

Definition at line 142 of file pilz_modbus_server_mock.h.

◆ DISCONNECT_TIMEOUT_IN_USEC

constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::DISCONNECT_TIMEOUT_IN_USEC { 0 }
staticprivate

Definition at line 143 of file pilz_modbus_server_mock.h.

◆ holding_register_size_

const unsigned int prbt_hardware_support::PilzModbusServerMock::holding_register_size_
private

Definition at line 122 of file pilz_modbus_server_mock.h.

◆ mb_mapping_

modbus_mapping_t* prbt_hardware_support::PilzModbusServerMock::mb_mapping_ { nullptr }
private

Definition at line 130 of file pilz_modbus_server_mock.h.

◆ modbus_connection_

modbus_t* prbt_hardware_support::PilzModbusServerMock::modbus_connection_ { nullptr }
private

Definition at line 129 of file pilz_modbus_server_mock.h.

◆ modbus_register_access_mutex

std::mutex prbt_hardware_support::PilzModbusServerMock::modbus_register_access_mutex
private

Definition at line 134 of file pilz_modbus_server_mock.h.

◆ RESPONSE_TIMEOUT_IN_SEC

constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::RESPONSE_TIMEOUT_IN_SEC { 0 }
staticprivate

Definition at line 145 of file pilz_modbus_server_mock.h.

◆ RESPONSE_TIMEOUT_IN_USEC

constexpr uint32_t prbt_hardware_support::PilzModbusServerMock::RESPONSE_TIMEOUT_IN_USEC { 10000 }
staticprivate

Definition at line 146 of file pilz_modbus_server_mock.h.

◆ running_cv_

std::condition_variable prbt_hardware_support::PilzModbusServerMock::running_cv_
private

Definition at line 137 of file pilz_modbus_server_mock.h.

◆ running_mutex_

std::mutex prbt_hardware_support::PilzModbusServerMock::running_mutex_
private

Definition at line 136 of file pilz_modbus_server_mock.h.

◆ socket_

int prbt_hardware_support::PilzModbusServerMock::socket_ { -1 }
private

Modbus.

Definition at line 128 of file pilz_modbus_server_mock.h.

◆ terminate_

std::atomic_bool prbt_hardware_support::PilzModbusServerMock::terminate_ { false }
private

Definition at line 132 of file pilz_modbus_server_mock.h.

◆ terminate_register_idx_

const unsigned int prbt_hardware_support::PilzModbusServerMock::terminate_register_idx_
private

Index of register for server shutdown signal.

Definition at line 124 of file pilz_modbus_server_mock.h.

◆ TERMINATE_SIGNAL

constexpr uint16_t prbt_hardware_support::PilzModbusServerMock::TERMINATE_SIGNAL { 1 }
staticprivate

Register value which indicates that server has to shutdown.

Definition at line 149 of file pilz_modbus_server_mock.h.

◆ thread_

std::thread prbt_hardware_support::PilzModbusServerMock::thread_
private

Definition at line 139 of file pilz_modbus_server_mock.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