Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
rokubimini::Rokubimini Class Referenceabstract

Class representing a rokubi mini device. More...

#include <Rokubimini.hpp>

Public Types

using AnonymousErrorCb = std::function< void(void)>
 
using AnonymousReadingCb = std::function< void(const Reading &)>
 
using DeviceDisconnectedCb = std::function< void(const std::string &)>
 
using DeviceReconnectedCb = std::function< void(const std::string &)>
 
using DiagnosticsUpdaterPtr = std::shared_ptr< diagnostic_updater::Updater >
 
using ErrorCb = std::function< void(const std::string &)>
 
using ErrorRecoveredCb = std::function< void(const std::string &)>
 
using FatalCb = std::function< void(const std::string &)>
 
using FatalRecoveredCb = std::function< void(const std::string &)>
 
using NodeHandlePtr = std::shared_ptr< ros::NodeHandle >
 
using ReadingCb = std::function< void(const std::string &, const Reading &)>
 
using RosPublisherPtr = std::shared_ptr< ros::Publisher >
 
using TimerPtr = std::shared_ptr< ros::Timer >
 

Public Member Functions

void addDeviceDisconnectedCb (const DeviceDisconnectedCb &deviceDisconnectedCb, const int priority=0)
 Adds a device disconnencted callback to a list. More...
 
void addDeviceReconnectedCb (const DeviceReconnectedCb &deviceReconnectedCb, const int priority=0)
 Adds a device reconnected callback to a list. More...
 
void addErrorCb (const ErrorCb &errorCb, const int priority=0)
 Adds an error callback to a list. More...
 
void addErrorRecoveredCb (const ErrorRecoveredCb &errorRecoveredCb, const int priority=0)
 Adds an error recovered callback to a list. More...
 
void addFatalCb (const FatalCb &fatalCb, const int priority=0)
 Adds an fatal callback to a list. More...
 
void addFatalRecoveredCb (const FatalRecoveredCb &fatalRecoveredCb, const int priority=0)
 Adds an fatal recovered callback to a list. More...
 
void addReadingCb (const ReadingCb &readingCb, const int priority=0)
 Adds a reading callback to a list. More...
 
void clearGoalStateEnum ()
 Clears the goal state enumeration. More...
 
virtual void createRosDiagnostics ()=0
 Creates ROS diagnostics for the rokubimini device. It's virtual because it's implementation specific. More...
 
virtual void createRosPublishers ()=0
 Creates ROS publishers for the rokubimini device. It's virtual because it's implementation specific. More...
 
virtual void createRosServices ()=0
 Creates ROS services for the rokubimini device. It's virtual because it's implementation specific. More...
 
void deviceDisconnectedCb ()
 Calls the callbacks in the device disconnected callbacks list. More...
 
bool deviceIsInErrorState ()
 Checks if the device is in error state. More...
 
bool deviceIsInFatalState ()
 Checks if the device is in fatal state. More...
 
virtual bool deviceIsMissing () const =0
 Checks if the device is missing. More...
 
void deviceReconnectedCb ()
 Calls the callbacks in the device reconnected callbacks list. More...
 
void errorCb ()
 Calls the callbacks in the error callbacks list. More...
 
void errorRecoveredCb ()
 Calls the callbacks in the error recovered callbacks list. More...
 
void fatalCb ()
 Calls the callbacks in the fatal callbacks list. More...
 
void fatalRecoveredCb ()
 Calls the callbacks in the fatal recovered callbacks list. More...
 
configuration::ConfigurationgetConfiguration ()
 Non-const version of getConfiguration() const. Gets the Configuration of the device. More...
 
const configuration::ConfigurationgetConfiguration () const
 
virtual bool getForceTorqueSamplingRate (int &samplingRate)=0
 Gets the force torque sampling rate of the device. It's virtual since it's implementation-specific. More...
 
std::string getName () const
 Gets the name of the device. More...
 
std::string getProductName () const
 Gets the product name of the device. More...
 
Reading getReading () const
 Gets the reading from the Rokubimini device. More...
 
void getReading (Reading &reading) const
 Gets the internal variable reading into the provided parameter. More...
 
virtual bool getSerialNumber (unsigned int &serialNumber)=0
 Gets the serial number of the device. It's virtual since it's implementation-specific. More...
 
Statusword getStatusword () const
 Gets the statusword of the device. More...
 
virtual void load ()
 Loads the rokubimini configuration from the parameter server. More...
 
virtual void publishRosDiagnostics ()=0
 Publishes ROS diagnostics from the rokubimini device. It's virtual because it's implementation specific. More...
 
virtual void publishRosMessages ()=0
 Publishes ROS messages with data from the rokubimini device. It's virtual because it's implementation specific. More...
 
 Rokubimini ()=default
 Default constructor. More...
 
 Rokubimini (const std::string &name, NodeHandlePtr nh)
 
virtual bool saveConfigParameter ()=0
 Saves the current configuration to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setAccelerationFilter (const unsigned int filter)=0
 Sets an acceleration filter to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setAccelerationRange (const unsigned int range)=0
 Sets an acceleration range to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setAngularRateFilter (const unsigned int filter)=0
 Sets an angular rate filter to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setAngularRateRange (const unsigned int range)=0
 Sets an angular rate range to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setForceTorqueFilter (const configuration::ForceTorqueFilter &filter)=0
 Sets a force torque filter to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setForceTorqueOffset (const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)=0
 Sets a force torque offset to the device. It's virtual since it's implementation-specific. More...
 
void setNodeHandle (const NodeHandlePtr &nh)
 Sets the nodeHandle of the device. More...
 
virtual bool setSensorCalibration (const calibration::SensorCalibration &sensorCalibration)=0
 Sets a sensor calibration to the device. It's virtual since it's implementation-specific. More...
 
virtual bool setSensorConfiguration (const configuration::SensorConfiguration &sensorConfiguration)=0
 Sets a sensor configuration to the device. It's virtual since it's implementation-specific. More...
 
virtual void shutdownWithCommunication ()=0
 Shuts down a Rokubimini device before communication has been closed. More...
 
virtual void shutdownWithoutCommunication ()
 
void startupWithCommunication ()
 Starts up a Rokubimini device after communication has been established. More...
 
void startupWithoutCommunication ()
 Starts up a Rokubimini device before communication has been established by the BusManager. More...
 
virtual void updateProcessReading ()=0
 Updates the Rokubimini object with new measurements. More...
 
virtual ~Rokubimini ()=default
 

Protected Member Functions

virtual void postSetupConfiguration ()=0
 Post-setup configuration hook. More...
 
virtual void preSetupConfiguration ()=0
 Pre-setup configuration hook. More...
 
void setStatusword (Statusword &statusword)
 Sets the statusword of the device. More...
 

Protected Attributes

configuration::Configuration configuration_
 The Configuration of the device. More...
 
DiagnosticsUpdaterPtr connectionStatusUpdater_
 The Connection Status diagnostics updater. More...
 
RosPublisherPtr dataFlagsDiagnosticsPublisher_
 The Publisher for publishing Data Flags Diagnostics. More...
 
TimerPtr dataFlagsDiagnosticsTimer_
 A timer for running the Data Flags Diagnostics update callback. More...
 
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
 
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
 
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
 
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
 
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
 
std::multimap< int, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
 
std::string name_
 The name of the device. More...
 
NodeHandlePtr nh_
 The node handle of the ROS node, used by the publishers. More...
 
std::string productName_
 The product name of the rokubimini. More...
 
Reading reading_
 The reading of the device. More...
 
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
 
std::recursive_mutex readingMutex_
 The mutex for accessing the reading. More...
 
Statusword statusword_
 The current statusword. More...
 
std::atomic< bool > statuswordRequested_ { false }
 Flag indicating if a statusword has been actively requested. More...
 

Static Protected Attributes

static constexpr double NAN_VALUE = std::numeric_limits<double>::quiet_NaN()
 NaN abbreviation for convenience. More...
 

Detailed Description

Class representing a rokubi mini device.

Definition at line 27 of file Rokubimini.hpp.

Member Typedef Documentation

◆ AnonymousErrorCb

using rokubimini::Rokubimini::AnonymousErrorCb = std::function<void(void)>

Definition at line 44 of file Rokubimini.hpp.

◆ AnonymousReadingCb

using rokubimini::Rokubimini::AnonymousReadingCb = std::function<void(const Reading&)>

Definition at line 43 of file Rokubimini.hpp.

◆ DeviceDisconnectedCb

using rokubimini::Rokubimini::DeviceDisconnectedCb = std::function<void(const std::string&)>

Definition at line 39 of file Rokubimini.hpp.

◆ DeviceReconnectedCb

using rokubimini::Rokubimini::DeviceReconnectedCb = std::function<void(const std::string&)>

Definition at line 40 of file Rokubimini.hpp.

◆ DiagnosticsUpdaterPtr

Definition at line 31 of file Rokubimini.hpp.

◆ ErrorCb

using rokubimini::Rokubimini::ErrorCb = std::function<void(const std::string&)>

Definition at line 35 of file Rokubimini.hpp.

◆ ErrorRecoveredCb

using rokubimini::Rokubimini::ErrorRecoveredCb = std::function<void(const std::string&)>

Definition at line 36 of file Rokubimini.hpp.

◆ FatalCb

using rokubimini::Rokubimini::FatalCb = std::function<void(const std::string&)>

Definition at line 37 of file Rokubimini.hpp.

◆ FatalRecoveredCb

using rokubimini::Rokubimini::FatalRecoveredCb = std::function<void(const std::string&)>

Definition at line 38 of file Rokubimini.hpp.

◆ NodeHandlePtr

Definition at line 30 of file Rokubimini.hpp.

◆ ReadingCb

using rokubimini::Rokubimini::ReadingCb = std::function<void(const std::string&, const Reading&)>

Definition at line 34 of file Rokubimini.hpp.

◆ RosPublisherPtr

Definition at line 32 of file Rokubimini.hpp.

◆ TimerPtr

using rokubimini::Rokubimini::TimerPtr = std::shared_ptr<ros::Timer>

Definition at line 33 of file Rokubimini.hpp.

Constructor & Destructor Documentation

◆ Rokubimini() [1/2]

rokubimini::Rokubimini::Rokubimini ( )
default

Default constructor.

◆ Rokubimini() [2/2]

rokubimini::Rokubimini::Rokubimini ( const std::string &  name,
NodeHandlePtr  nh 
)
inline

Definition at line 60 of file Rokubimini.hpp.

◆ ~Rokubimini()

virtual rokubimini::Rokubimini::~Rokubimini ( )
virtualdefault

Member Function Documentation

◆ addDeviceDisconnectedCb()

void rokubimini::Rokubimini::addDeviceDisconnectedCb ( const DeviceDisconnectedCb deviceDisconnectedCb,
const int  priority = 0 
)
inline

Adds a device disconnencted callback to a list.

Parameters
DeviceDisconnectedCbThe device disconnencted callback.
priorityThe priority of the callback.

Definition at line 172 of file Rokubimini.hpp.

◆ addDeviceReconnectedCb()

void rokubimini::Rokubimini::addDeviceReconnectedCb ( const DeviceReconnectedCb deviceReconnectedCb,
const int  priority = 0 
)
inline

Adds a device reconnected callback to a list.

Parameters
DeviceReconnectedCbThe device reconnected callback.
priorityThe priority of the callback.

Definition at line 185 of file Rokubimini.hpp.

◆ addErrorCb()

void rokubimini::Rokubimini::addErrorCb ( const ErrorCb errorCb,
const int  priority = 0 
)
inline

Adds an error callback to a list.

Parameters
errorCbThe error callback.
priorityThe priority of the callback.

Definition at line 120 of file Rokubimini.hpp.

◆ addErrorRecoveredCb()

void rokubimini::Rokubimini::addErrorRecoveredCb ( const ErrorRecoveredCb errorRecoveredCb,
const int  priority = 0 
)
inline

Adds an error recovered callback to a list.

Parameters
errorRecoveredCbThe error recovered callback.
priorityThe priority of the callback.

Definition at line 133 of file Rokubimini.hpp.

◆ addFatalCb()

void rokubimini::Rokubimini::addFatalCb ( const FatalCb fatalCb,
const int  priority = 0 
)
inline

Adds an fatal callback to a list.

Parameters
fatalCbThe fatal callback.
priorityThe priority of the callback.

Definition at line 146 of file Rokubimini.hpp.

◆ addFatalRecoveredCb()

void rokubimini::Rokubimini::addFatalRecoveredCb ( const FatalRecoveredCb fatalRecoveredCb,
const int  priority = 0 
)
inline

Adds an fatal recovered callback to a list.

Parameters
fatalRecoveredCbThe fatal recovered callback.
priorityThe priority of the callback.

Definition at line 159 of file Rokubimini.hpp.

◆ addReadingCb()

void rokubimini::Rokubimini::addReadingCb ( const ReadingCb readingCb,
const int  priority = 0 
)
inline

Adds a reading callback to a list.

Parameters
readingCbThe reading callback.
priorityThe priority of the callback.

Definition at line 107 of file Rokubimini.hpp.

◆ clearGoalStateEnum()

void rokubimini::Rokubimini::clearGoalStateEnum ( )

Clears the goal state enumeration.

Todo:
Fix me.

Definition at line 242 of file Rokubimini.hpp.

◆ createRosDiagnostics()

void rokubimini::Rokubimini::createRosDiagnostics ( )
pure virtual

Creates ROS diagnostics for the rokubimini device. It's virtual because it's implementation specific.

◆ createRosPublishers()

void rokubimini::Rokubimini::createRosPublishers ( )
pure virtual

Creates ROS publishers for the rokubimini device. It's virtual because it's implementation specific.

◆ createRosServices()

void rokubimini::Rokubimini::createRosServices ( )
pure virtual

Creates ROS services for the rokubimini device. It's virtual because it's implementation specific.

◆ deviceDisconnectedCb()

void rokubimini::Rokubimini::deviceDisconnectedCb ( )

Calls the callbacks in the device disconnected callbacks list.

Definition at line 126 of file Rokubimini.cpp.

◆ deviceIsInErrorState()

bool rokubimini::Rokubimini::deviceIsInErrorState ( )

Checks if the device is in error state.

Returns
True if the device is in error state.

Definition at line 97 of file Rokubimini.cpp.

◆ deviceIsInFatalState()

bool rokubimini::Rokubimini::deviceIsInFatalState ( )

Checks if the device is in fatal state.

Returns
True if the device is in fatal state.

Definition at line 120 of file Rokubimini.cpp.

◆ deviceIsMissing()

bool rokubimini::Rokubimini::deviceIsMissing ( ) const
pure virtual

Checks if the device is missing.

Returns
True if the device is missing.

◆ deviceReconnectedCb()

void rokubimini::Rokubimini::deviceReconnectedCb ( )

Calls the callbacks in the device reconnected callbacks list.

Definition at line 170 of file Rokubimini.cpp.

◆ errorCb()

void rokubimini::Rokubimini::errorCb ( )

Calls the callbacks in the error callbacks list.

Definition at line 80 of file Rokubimini.cpp.

◆ errorRecoveredCb()

void rokubimini::Rokubimini::errorRecoveredCb ( )

Calls the callbacks in the error recovered callbacks list.

Definition at line 88 of file Rokubimini.cpp.

◆ fatalCb()

void rokubimini::Rokubimini::fatalCb ( )

Calls the callbacks in the fatal callbacks list.

Definition at line 103 of file Rokubimini.cpp.

◆ fatalRecoveredCb()

void rokubimini::Rokubimini::fatalRecoveredCb ( )

Calls the callbacks in the fatal recovered callbacks list.

Definition at line 111 of file Rokubimini.cpp.

◆ getConfiguration() [1/2]

const configuration::Configuration & rokubimini::Rokubimini::getConfiguration ( )
inline

Non-const version of getConfiguration() const. Gets the Configuration of the device.

Gets the Configuration of the device.

Returns
The Configuration value.

Definition at line 82 of file Rokubimini.hpp.

◆ getConfiguration() [2/2]

const configuration::Configuration& rokubimini::Rokubimini::getConfiguration ( ) const
inline

Definition at line 94 of file Rokubimini.hpp.

◆ getForceTorqueSamplingRate()

bool rokubimini::Rokubimini::getForceTorqueSamplingRate ( int &  samplingRate)
pure virtual

Gets the force torque sampling rate of the device. It's virtual since it's implementation-specific.

Parameters
samplingRateThe force torque sampling rate to be fetched.
Returns
True if the force torque sampling rate was successfully fetched.

◆ getName()

std::string rokubimini::Rokubimini::getName ( ) const
inline

Gets the name of the device.

Returns
The name value.

Definition at line 70 of file Rokubimini.hpp.

◆ getProductName()

std::string rokubimini::Rokubimini::getProductName ( ) const
inline

Gets the product name of the device.

Returns
The product name.

Definition at line 554 of file Rokubimini.hpp.

◆ getReading() [1/2]

Reading rokubimini::Rokubimini::getReading ( ) const

Gets the reading from the Rokubimini device.

Returns
The reading value.

Definition at line 179 of file Rokubimini.cpp.

◆ getReading() [2/2]

void rokubimini::Rokubimini::getReading ( Reading reading) const

Gets the internal variable reading into the provided parameter.

Parameters
readingThe reading to assign the internal reading variable.

Definition at line 185 of file Rokubimini.cpp.

◆ getSerialNumber()

bool rokubimini::Rokubimini::getSerialNumber ( unsigned int &  serialNumber)
pure virtual

Gets the serial number of the device. It's virtual since it's implementation-specific.

Parameters
serialNumberThe serial number to be fetched.
Returns
True if the serial number was successfully fetched.

◆ getStatusword()

Statusword rokubimini::Rokubimini::getStatusword ( ) const
inline

Gets the statusword of the device.

Returns
The statusword of the device.

Definition at line 336 of file Rokubimini.hpp.

◆ load()

void rokubimini::Rokubimini::load ( )
virtual

Loads the rokubimini configuration from the parameter server.

Definition at line 8 of file Rokubimini.cpp.

◆ postSetupConfiguration()

void rokubimini::Rokubimini::postSetupConfiguration ( )
protectedpure virtual

Post-setup configuration hook.

This method is virtual because it's implementation-specific.

◆ preSetupConfiguration()

void rokubimini::Rokubimini::preSetupConfiguration ( )
protectedpure virtual

Pre-setup configuration hook.

This method is virtual because it's implementation-specific.

◆ publishRosDiagnostics()

void rokubimini::Rokubimini::publishRosDiagnostics ( )
pure virtual

Publishes ROS diagnostics from the rokubimini device. It's virtual because it's implementation specific.

◆ publishRosMessages()

void rokubimini::Rokubimini::publishRosMessages ( )
pure virtual

Publishes ROS messages with data from the rokubimini device. It's virtual because it's implementation specific.

◆ saveConfigParameter()

bool rokubimini::Rokubimini::saveConfigParameter ( )
pure virtual

Saves the current configuration to the device. It's virtual since it's implementation-specific.

Returns
True if the configuration was successfully saved in the device.

◆ setAccelerationFilter()

bool rokubimini::Rokubimini::setAccelerationFilter ( const unsigned int  filter)
pure virtual

Sets an acceleration filter to the device. It's virtual since it's implementation-specific.

Parameters
filterThe filter to be set.
Returns
True if the acceleration torque filter was successfully set.

◆ setAccelerationRange()

bool rokubimini::Rokubimini::setAccelerationRange ( const unsigned int  range)
pure virtual

Sets an acceleration range to the device. It's virtual since it's implementation-specific.

Parameters
rangeThe range to be set.
Returns
True if the acceleration range was successfully set.

◆ setAngularRateFilter()

bool rokubimini::Rokubimini::setAngularRateFilter ( const unsigned int  filter)
pure virtual

Sets an angular rate filter to the device. It's virtual since it's implementation-specific.

Parameters
filterThe filter to be set.
Returns
True if the angular rate filter was successfully set.

◆ setAngularRateRange()

bool rokubimini::Rokubimini::setAngularRateRange ( const unsigned int  range)
pure virtual

Sets an angular rate range to the device. It's virtual since it's implementation-specific.

Parameters
rangeThe range to be set.
Returns
True if the angular rate range was successfully set.

◆ setForceTorqueFilter()

bool rokubimini::Rokubimini::setForceTorqueFilter ( const configuration::ForceTorqueFilter filter)
pure virtual

Sets a force torque filter to the device. It's virtual since it's implementation-specific.

Parameters
filterThe filter to be set.
Returns
True if the force torque filter was successfully set.

◆ setForceTorqueOffset()

bool rokubimini::Rokubimini::setForceTorqueOffset ( const Eigen::Matrix< double, 6, 1 > &  forceTorqueOffset)
pure virtual

Sets a force torque offset to the device. It's virtual since it's implementation-specific.

Parameters
forceTorqueOffsetThe offset to be set.
Returns
True if the offset was successfully set.

◆ setNodeHandle()

void rokubimini::Rokubimini::setNodeHandle ( const NodeHandlePtr nh)
inline

Sets the nodeHandle of the device.

Todo:
Methods for logging.
Parameters
nhThe nodeHanlde of the device.

Definition at line 506 of file Rokubimini.hpp.

◆ setSensorCalibration()

bool rokubimini::Rokubimini::setSensorCalibration ( const calibration::SensorCalibration sensorCalibration)
pure virtual

Sets a sensor calibration to the device. It's virtual since it's implementation-specific.

Parameters
sensorCalibrationThe calibration to be set.
Returns
True if the calibration was successfully set.

◆ setSensorConfiguration()

bool rokubimini::Rokubimini::setSensorConfiguration ( const configuration::SensorConfiguration sensorConfiguration)
pure virtual

Sets a sensor configuration to the device. It's virtual since it's implementation-specific.

Parameters
sensorConfigurationThe configuration to be set.
Returns
True if the configuration was successfully set.

◆ setStatusword()

void rokubimini::Rokubimini::setStatusword ( Statusword statusword)
protected

Sets the statusword of the device.

Todo:
Check if needed.
Parameters
statuswordThe statusword to set.

Definition at line 191 of file Rokubimini.cpp.

◆ shutdownWithCommunication()

void rokubimini::Rokubimini::shutdownWithCommunication ( )
pure virtual

Shuts down a Rokubimini device before communication has been closed.

Shuts down a Rokubimini device after communication has been closed.

This method shuts down a Rokubimini device before the BusManager has terminated communication with the device. It's virtual since it's implementation-specific.

This method shuts down a Rokubimini device after the BusManager has terminated communication with the device. It's virtual since it's implementation-specific.

◆ shutdownWithoutCommunication()

virtual void rokubimini::Rokubimini::shutdownWithoutCommunication ( )
inlinevirtual

Definition at line 242 of file Rokubimini.hpp.

◆ startupWithCommunication()

void rokubimini::Rokubimini::startupWithCommunication ( )

Starts up a Rokubimini device after communication has been established.

This method is virtual because it's implementation-specific.

Definition at line 24 of file Rokubimini.cpp.

◆ startupWithoutCommunication()

void rokubimini::Rokubimini::startupWithoutCommunication ( )

Starts up a Rokubimini device before communication has been established by the BusManager.

Definition at line 71 of file Rokubimini.cpp.

◆ updateProcessReading()

void rokubimini::Rokubimini::updateProcessReading ( )
pure virtual

Updates the Rokubimini object with new measurements.

This method updates the internal Reading variable of Rokubimini, by getting the new values from its implementation. It's virtual since it's implementation-specific.

Member Data Documentation

◆ configuration_

configuration::Configuration rokubimini::Rokubimini::configuration_
protected

The Configuration of the device.

Definition at line 633 of file Rokubimini.hpp.

◆ connectionStatusUpdater_

DiagnosticsUpdaterPtr rokubimini::Rokubimini::connectionStatusUpdater_
protected

The Connection Status diagnostics updater.

Definition at line 745 of file Rokubimini.hpp.

◆ dataFlagsDiagnosticsPublisher_

RosPublisherPtr rokubimini::Rokubimini::dataFlagsDiagnosticsPublisher_
protected

The Publisher for publishing Data Flags Diagnostics.

Definition at line 761 of file Rokubimini.hpp.

◆ dataFlagsDiagnosticsTimer_

TimerPtr rokubimini::Rokubimini::dataFlagsDiagnosticsTimer_
protected

A timer for running the Data Flags Diagnostics update callback.

Definition at line 753 of file Rokubimini.hpp.

◆ deviceDisconnectedCbs_

std::multimap<int, DeviceDisconnectedCb, std::greater<int> > rokubimini::Rokubimini::deviceDisconnectedCbs_
protected

Definition at line 729 of file Rokubimini.hpp.

◆ deviceReconnectedCbs_

std::multimap<int, DeviceReconnectedCb, std::greater<int> > rokubimini::Rokubimini::deviceReconnectedCbs_
protected

Definition at line 737 of file Rokubimini.hpp.

◆ errorCbs_

std::multimap<int, ErrorCb, std::greater<int> > rokubimini::Rokubimini::errorCbs_
protected

Definition at line 697 of file Rokubimini.hpp.

◆ errorRecoveredCbs_

std::multimap<int, ErrorRecoveredCb, std::greater<int> > rokubimini::Rokubimini::errorRecoveredCbs_
protected

Definition at line 705 of file Rokubimini.hpp.

◆ fatalCbs_

std::multimap<int, FatalCb, std::greater<int> > rokubimini::Rokubimini::fatalCbs_
protected

Definition at line 713 of file Rokubimini.hpp.

◆ fatalRecoveredCbs_

std::multimap<int, FatalRecoveredCb, std::greater<int> > rokubimini::Rokubimini::fatalRecoveredCbs_
protected

Definition at line 721 of file Rokubimini.hpp.

◆ name_

std::string rokubimini::Rokubimini::name_
protected

The name of the device.

Definition at line 625 of file Rokubimini.hpp.

◆ NAN_VALUE

static constexpr double rokubimini::Rokubimini::NAN_VALUE = std::numeric_limits<double>::quiet_NaN()
staticconstexprprotected

NaN abbreviation for convenience.

Definition at line 617 of file Rokubimini.hpp.

◆ nh_

std::shared_ptr< ros::NodeHandle > rokubimini::Rokubimini::nh_
protected

The node handle of the ROS node, used by the publishers.

Definition at line 673 of file Rokubimini.hpp.

◆ productName_

std::string rokubimini::Rokubimini::productName_
protected

The product name of the rokubimini.

Definition at line 681 of file Rokubimini.hpp.

◆ reading_

Reading rokubimini::Rokubimini::reading_
protected

The reading of the device.

Definition at line 665 of file Rokubimini.hpp.

◆ readingCbs_

std::multimap<int, ReadingCb, std::greater<int> > rokubimini::Rokubimini::readingCbs_
protected

Definition at line 689 of file Rokubimini.hpp.

◆ readingMutex_

std::recursive_mutex rokubimini::Rokubimini::readingMutex_
mutableprotected

The mutex for accessing the reading.

Definition at line 657 of file Rokubimini.hpp.

◆ statusword_

Statusword rokubimini::Rokubimini::statusword_
protected

The current statusword.

Definition at line 641 of file Rokubimini.hpp.

◆ statuswordRequested_

std::atomic< bool > rokubimini::Rokubimini::statuswordRequested_ { false }
protected

Flag indicating if a statusword has been actively requested.

Definition at line 649 of file Rokubimini.hpp.


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


rokubimini
Author(s):
autogenerated on Sat Apr 15 2023 02:53:52