Public Member Functions | Private Attributes | List of all members
prbt_hardware_support::ModbusApiSpecTemplated< T > Class Template Reference

Specifies the meaning of the holding registers. More...

#include <modbus_api_spec.h>

Public Member Functions

void getAllDefinedRegisters (std::vector< unsigned short > &registers)
 
unsigned short getMaxRegisterDefinition () const
 
unsigned short getMinRegisterDefinition () const
 
unsigned short getRegisterDefinition (const std::string &key) const
 
bool hasRegisterDefinition (const std::string &key) const
 
 ModbusApiSpecTemplated (std::initializer_list< std::pair< std::string, unsigned short > > reg_list)
 
 ModbusApiSpecTemplated (T &nh)
 Construct a new Modbus Api Spec Templated object. More...
 
 ModbusApiSpecTemplated (T &nh, const std::string &param_name)
 Construct a new Modbus Api Spec Templated object. More...
 
void setRegisterDefinition (const std::string &key, unsigned short value)
 
std::map< std::string, unsigned short >::size_type size () const
 

Private Attributes

std::map< std::string, unsigned short > register_mapping_
 

Detailed Description

template<class T = ros::NodeHandle>
class prbt_hardware_support::ModbusApiSpecTemplated< T >

Specifies the meaning of the holding registers.

Remarks
this class is templated for easier mocking. However for usability it can be used by ModbusApiSpec

Definition at line 63 of file modbus_api_spec.h.

Constructor & Destructor Documentation

template<class T = ros::NodeHandle>
prbt_hardware_support::ModbusApiSpecTemplated< T >::ModbusApiSpecTemplated ( std::initializer_list< std::pair< std::string, unsigned short > >  reg_list)
inline

Definition at line 67 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
prbt_hardware_support::ModbusApiSpecTemplated< T >::ModbusApiSpecTemplated ( T &  nh)
inline

Construct a new Modbus Api Spec Templated object.

The parameters are expected to be provided as

/[nodehandle_namespace]/read_api_spec/[key1]
/[nodehandle_namespace]/read_api_spec/[key2]
...

with the values beeing of type int.

Parameters
nhNodeHandle to read the parameters from

Definition at line 87 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
prbt_hardware_support::ModbusApiSpecTemplated< T >::ModbusApiSpecTemplated ( T &  nh,
const std::string &  param_name 
)
inline

Construct a new Modbus Api Spec Templated object.

The parameters are expected to be provided as

/[nodehandle_namespace]/[param_name]/[key1]
/[nodehandle_namespace]/[param_name]/[key2]
...

with the values beeing of type int.

Parameters
nhNodeHandle to read the parameters from
param_namethe name on the rosparam server to read from

Definition at line 103 of file modbus_api_spec.h.

Member Function Documentation

template<class T = ros::NodeHandle>
void prbt_hardware_support::ModbusApiSpecTemplated< T >::getAllDefinedRegisters ( std::vector< unsigned short > &  registers)
inline

Definition at line 176 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
unsigned short prbt_hardware_support::ModbusApiSpecTemplated< T >::getMaxRegisterDefinition ( ) const
inline

Definition at line 158 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
unsigned short prbt_hardware_support::ModbusApiSpecTemplated< T >::getMinRegisterDefinition ( ) const
inline

Definition at line 140 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
unsigned short prbt_hardware_support::ModbusApiSpecTemplated< T >::getRegisterDefinition ( const std::string &  key) const
inline

Definition at line 129 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
bool prbt_hardware_support::ModbusApiSpecTemplated< T >::hasRegisterDefinition ( const std::string &  key) const
inline

Definition at line 119 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
void prbt_hardware_support::ModbusApiSpecTemplated< T >::setRegisterDefinition ( const std::string &  key,
unsigned short  value 
)
inline

Definition at line 124 of file modbus_api_spec.h.

template<class T = ros::NodeHandle>
std::map<std::string, unsigned short>::size_type prbt_hardware_support::ModbusApiSpecTemplated< T >::size ( ) const
inline

Definition at line 183 of file modbus_api_spec.h.

Member Data Documentation

template<class T = ros::NodeHandle>
std::map<std::string, unsigned short> prbt_hardware_support::ModbusApiSpecTemplated< T >::register_mapping_
private

Definition at line 189 of file modbus_api_spec.h.


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


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:18