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

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 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
 Gets the Configuration of the device. More...
 
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...
 
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...
 
bool loadRokubiminiSetup (std::shared_ptr< rokubimini::setup::Rokubimini > setup)
 Loads the configuration of the device from the {Rokubimini Setup} provided. 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...
 
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 doStartupWithCommunication ()=0
 
void setStatusword (Statusword &statusword)
 Sets the statusword of the device. More...
 

Protected Attributes

configuration::Configuration configuration_
 The Configuration of the device. 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...
 
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 25 of file Rokubimini.hpp.

Member Typedef Documentation

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

Definition at line 39 of file Rokubimini.hpp.

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

Definition at line 38 of file Rokubimini.hpp.

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

Definition at line 34 of file Rokubimini.hpp.

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

Definition at line 35 of file Rokubimini.hpp.

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

Definition at line 30 of file Rokubimini.hpp.

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

Definition at line 31 of file Rokubimini.hpp.

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

Definition at line 32 of file Rokubimini.hpp.

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

Definition at line 33 of file Rokubimini.hpp.

Definition at line 28 of file Rokubimini.hpp.

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

Definition at line 29 of file Rokubimini.hpp.

Constructor & Destructor Documentation

rokubimini::Rokubimini::Rokubimini ( )
default

Default constructor.

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

Member Function Documentation

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 169 of file Rokubimini.hpp.

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 182 of file Rokubimini.hpp.

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 117 of file Rokubimini.hpp.

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 130 of file Rokubimini.hpp.

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 143 of file Rokubimini.hpp.

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 156 of file Rokubimini.hpp.

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 104 of file Rokubimini.hpp.

void rokubimini::Rokubimini::clearGoalStateEnum ( )

Clears the goal state enumeration.

Todo:
Fix me.

Definition at line 239 of file Rokubimini.hpp.

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

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

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

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

void rokubimini::Rokubimini::deviceDisconnectedCb ( )

Calls the callbacks in the device disconnected callbacks list.

Definition at line 116 of file Rokubimini.cpp.

bool rokubimini::Rokubimini::deviceIsInErrorState ( )

Checks if the device is in error state.

Returns
True if the device is in error state.

Definition at line 87 of file Rokubimini.cpp.

bool rokubimini::Rokubimini::deviceIsInFatalState ( )

Checks if the device is in fatal state.

Returns
True if the device is in fatal state.

Definition at line 110 of file Rokubimini.cpp.

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

Checks if the device is missing.

Returns
True if the device is missing.
void rokubimini::Rokubimini::deviceReconnectedCb ( )

Calls the callbacks in the device reconnected callbacks list.

Definition at line 160 of file Rokubimini.cpp.

virtual void rokubimini::Rokubimini::doStartupWithCommunication ( )
protectedpure virtual
void rokubimini::Rokubimini::errorCb ( )

Calls the callbacks in the error callbacks list.

Definition at line 70 of file Rokubimini.cpp.

void rokubimini::Rokubimini::errorRecoveredCb ( )

Calls the callbacks in the error recovered callbacks list.

Definition at line 78 of file Rokubimini.cpp.

void rokubimini::Rokubimini::fatalCb ( )

Calls the callbacks in the fatal callbacks list.

Definition at line 93 of file Rokubimini.cpp.

void rokubimini::Rokubimini::fatalRecoveredCb ( )

Calls the callbacks in the fatal recovered callbacks list.

Definition at line 101 of file Rokubimini.cpp.

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

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

Returns
The Configuration value.

Definition at line 69 of file Rokubimini.hpp.

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

Gets the Configuration of the device.

Returns
The Configuration value.

Definition at line 81 of file Rokubimini.hpp.

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.
std::string rokubimini::Rokubimini::getName ( ) const
inline

Gets the name of the device.

Returns
The name value.

Definition at line 57 of file Rokubimini.hpp.

Reading rokubimini::Rokubimini::getReading ( ) const

Gets the reading from the Rokubimini device.

Returns
The reading value.

Definition at line 169 of file Rokubimini.cpp.

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 175 of file Rokubimini.cpp.

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.
Statusword rokubimini::Rokubimini::getStatusword ( ) const
inline

Gets the statusword of the device.

Returns
The statusword of the device.

Definition at line 333 of file Rokubimini.hpp.

bool rokubimini::Rokubimini::loadRokubiminiSetup ( std::shared_ptr< rokubimini::setup::Rokubimini setup)

Loads the configuration of the device from the {Rokubimini Setup} provided.

Parameters
setupThe {Rokubimini Setup} to load.
Returns
True if the load was successful.

Definition at line 8 of file Rokubimini.cpp.

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

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

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.
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.
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.
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.
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.
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.
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.
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 503 of file Rokubimini.hpp.

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.
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.
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 181 of file Rokubimini.cpp.

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.

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

Definition at line 239 of file Rokubimini.hpp.

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 15 of file Rokubimini.cpp.

void rokubimini::Rokubimini::startupWithoutCommunication ( )

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

Definition at line 61 of file Rokubimini.cpp.

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 rokubimini::Rokubimini::configuration_
protected

The Configuration of the device.

Definition at line 580 of file Rokubimini.hpp.

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

Definition at line 668 of file Rokubimini.hpp.

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

Definition at line 676 of file Rokubimini.hpp.

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

Definition at line 636 of file Rokubimini.hpp.

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

Definition at line 644 of file Rokubimini.hpp.

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

Definition at line 652 of file Rokubimini.hpp.

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

Definition at line 660 of file Rokubimini.hpp.

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

The name of the device.

Definition at line 572 of file Rokubimini.hpp.

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

NaN abbreviation for convenience.

Definition at line 564 of file Rokubimini.hpp.

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

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

Definition at line 620 of file Rokubimini.hpp.

Reading rokubimini::Rokubimini::reading_
protected

The reading of the device.

Definition at line 612 of file Rokubimini.hpp.

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

Definition at line 628 of file Rokubimini.hpp.

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

The mutex for accessing the reading.

Definition at line 604 of file Rokubimini.hpp.

Statusword rokubimini::Rokubimini::statusword_
protected

The current statusword.

Definition at line 588 of file Rokubimini.hpp.

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

Flag indicating if a statusword has been actively requested.

Definition at line 596 of file Rokubimini.hpp.


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


rokubimini
Author(s):
autogenerated on Wed Mar 3 2021 03:09:12