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::Configuration & | getConfiguration () |
Non-const version of getConfiguration() const. Gets the Configuration of the device. More... | |
const configuration::Configuration & | getConfiguration () 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... | |
Class representing a rokubi mini device.
Definition at line 27 of file Rokubimini.hpp.
using rokubimini::Rokubimini::AnonymousErrorCb = std::function<void(void)> |
Definition at line 44 of file Rokubimini.hpp.
using rokubimini::Rokubimini::AnonymousReadingCb = std::function<void(const Reading&)> |
Definition at line 43 of file Rokubimini.hpp.
using rokubimini::Rokubimini::DeviceDisconnectedCb = std::function<void(const std::string&)> |
Definition at line 39 of file Rokubimini.hpp.
using rokubimini::Rokubimini::DeviceReconnectedCb = std::function<void(const std::string&)> |
Definition at line 40 of file Rokubimini.hpp.
using rokubimini::Rokubimini::DiagnosticsUpdaterPtr = std::shared_ptr<diagnostic_updater::Updater> |
Definition at line 31 of file Rokubimini.hpp.
using rokubimini::Rokubimini::ErrorCb = std::function<void(const std::string&)> |
Definition at line 35 of file Rokubimini.hpp.
using rokubimini::Rokubimini::ErrorRecoveredCb = std::function<void(const std::string&)> |
Definition at line 36 of file Rokubimini.hpp.
using rokubimini::Rokubimini::FatalCb = std::function<void(const std::string&)> |
Definition at line 37 of file Rokubimini.hpp.
using rokubimini::Rokubimini::FatalRecoveredCb = std::function<void(const std::string&)> |
Definition at line 38 of file Rokubimini.hpp.
using rokubimini::Rokubimini::NodeHandlePtr = std::shared_ptr<ros::NodeHandle> |
Definition at line 30 of file Rokubimini.hpp.
using rokubimini::Rokubimini::ReadingCb = std::function<void(const std::string&, const Reading&)> |
Definition at line 34 of file Rokubimini.hpp.
using rokubimini::Rokubimini::RosPublisherPtr = std::shared_ptr<ros::Publisher> |
Definition at line 32 of file Rokubimini.hpp.
using rokubimini::Rokubimini::TimerPtr = std::shared_ptr<ros::Timer> |
Definition at line 33 of file Rokubimini.hpp.
|
default |
Default constructor.
|
inline |
Definition at line 60 of file Rokubimini.hpp.
|
virtualdefault |
|
inline |
Adds a device disconnencted callback to a list.
DeviceDisconnectedCb | The device disconnencted callback. |
priority | The priority of the callback. |
Definition at line 172 of file Rokubimini.hpp.
|
inline |
Adds a device reconnected callback to a list.
DeviceReconnectedCb | The device reconnected callback. |
priority | The priority of the callback. |
Definition at line 185 of file Rokubimini.hpp.
|
inline |
Adds an error callback to a list.
errorCb | The error callback. |
priority | The priority of the callback. |
Definition at line 120 of file Rokubimini.hpp.
|
inline |
Adds an error recovered callback to a list.
errorRecoveredCb | The error recovered callback. |
priority | The priority of the callback. |
Definition at line 133 of file Rokubimini.hpp.
|
inline |
Adds an fatal callback to a list.
fatalCb | The fatal callback. |
priority | The priority of the callback. |
Definition at line 146 of file Rokubimini.hpp.
|
inline |
Adds an fatal recovered callback to a list.
fatalRecoveredCb | The fatal recovered callback. |
priority | The priority of the callback. |
Definition at line 159 of file Rokubimini.hpp.
|
inline |
Adds a reading callback to a list.
readingCb | The reading callback. |
priority | The priority of the callback. |
Definition at line 107 of file Rokubimini.hpp.
void rokubimini::Rokubimini::clearGoalStateEnum | ( | ) |
|
pure virtual |
Creates ROS diagnostics for the rokubimini device. It's virtual because it's implementation specific.
|
pure virtual |
Creates ROS publishers for the rokubimini device. It's virtual because it's implementation specific.
|
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 126 of file Rokubimini.cpp.
bool rokubimini::Rokubimini::deviceIsInErrorState | ( | ) |
Checks if the device is in error state.
Definition at line 97 of file Rokubimini.cpp.
bool rokubimini::Rokubimini::deviceIsInFatalState | ( | ) |
Checks if the device is in fatal state.
Definition at line 120 of file Rokubimini.cpp.
|
pure virtual |
Checks if the device is missing.
void rokubimini::Rokubimini::deviceReconnectedCb | ( | ) |
Calls the callbacks in the device reconnected callbacks list.
Definition at line 170 of file Rokubimini.cpp.
void rokubimini::Rokubimini::errorCb | ( | ) |
Calls the callbacks in the error callbacks list.
Definition at line 80 of file Rokubimini.cpp.
void rokubimini::Rokubimini::errorRecoveredCb | ( | ) |
Calls the callbacks in the error recovered callbacks list.
Definition at line 88 of file Rokubimini.cpp.
void rokubimini::Rokubimini::fatalCb | ( | ) |
Calls the callbacks in the fatal callbacks list.
Definition at line 103 of file Rokubimini.cpp.
void rokubimini::Rokubimini::fatalRecoveredCb | ( | ) |
Calls the callbacks in the fatal recovered callbacks list.
Definition at line 111 of file Rokubimini.cpp.
|
inline |
Non-const version of getConfiguration() const. Gets the Configuration of the device.
Gets the Configuration of the device.
Definition at line 82 of file Rokubimini.hpp.
|
inline |
Definition at line 94 of file Rokubimini.hpp.
|
pure virtual |
Gets the force torque sampling rate of the device. It's virtual since it's implementation-specific.
samplingRate | The force torque sampling rate to be fetched. |
|
inline |
|
inline |
Gets the product name of the device.
Definition at line 554 of file Rokubimini.hpp.
Reading rokubimini::Rokubimini::getReading | ( | ) | const |
Gets the reading from the Rokubimini device.
Definition at line 179 of file Rokubimini.cpp.
void rokubimini::Rokubimini::getReading | ( | Reading & | reading | ) | const |
Gets the internal variable reading into the provided parameter.
reading | The reading to assign the internal reading variable. |
Definition at line 185 of file Rokubimini.cpp.
|
pure virtual |
Gets the serial number of the device. It's virtual since it's implementation-specific.
serialNumber | The serial number to be fetched. |
|
inline |
Gets the statusword of the device.
Definition at line 336 of file Rokubimini.hpp.
|
virtual |
Loads the rokubimini configuration from the parameter server.
Definition at line 8 of file Rokubimini.cpp.
|
protectedpure virtual |
Post-setup configuration hook.
This method is virtual because it's implementation-specific.
|
protectedpure virtual |
Pre-setup configuration hook.
This method is virtual because it's implementation-specific.
|
pure virtual |
Publishes ROS diagnostics from the rokubimini device. It's virtual because it's implementation specific.
|
pure virtual |
Publishes ROS messages with data from the rokubimini device. It's virtual because it's implementation specific.
|
pure virtual |
Saves the current configuration to the device. It's virtual since it's implementation-specific.
|
pure virtual |
Sets an acceleration filter to the device. It's virtual since it's implementation-specific.
filter | The filter to be set. |
|
pure virtual |
Sets an acceleration range to the device. It's virtual since it's implementation-specific.
range | The range to be set. |
|
pure virtual |
Sets an angular rate filter to the device. It's virtual since it's implementation-specific.
filter | The filter to be set. |
|
pure virtual |
Sets an angular rate range to the device. It's virtual since it's implementation-specific.
range | The range to be set. |
|
pure virtual |
Sets a force torque filter to the device. It's virtual since it's implementation-specific.
filter | The filter to be set. |
|
pure virtual |
Sets a force torque offset to the device. It's virtual since it's implementation-specific.
forceTorqueOffset | The offset to be set. |
|
inline |
Sets the nodeHandle of the device.
nh | The nodeHanlde of the device. |
Definition at line 506 of file Rokubimini.hpp.
|
pure virtual |
Sets a sensor calibration to the device. It's virtual since it's implementation-specific.
sensorCalibration | The calibration to be set. |
|
pure virtual |
Sets a sensor configuration to the device. It's virtual since it's implementation-specific.
sensorConfiguration | The configuration to be set. |
|
protected |
Sets the statusword of the device.
statusword | The statusword to set. |
Definition at line 191 of file Rokubimini.cpp.
|
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.
|
inlinevirtual |
Definition at line 242 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 24 of file Rokubimini.cpp.
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.
|
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.
|
protected |
The Configuration of the device.
Definition at line 633 of file Rokubimini.hpp.
|
protected |
The Connection Status diagnostics updater.
Definition at line 745 of file Rokubimini.hpp.
|
protected |
The Publisher for publishing Data Flags Diagnostics.
Definition at line 761 of file Rokubimini.hpp.
|
protected |
A timer for running the Data Flags Diagnostics update callback.
Definition at line 753 of file Rokubimini.hpp.
|
protected |
Definition at line 729 of file Rokubimini.hpp.
|
protected |
Definition at line 737 of file Rokubimini.hpp.
|
protected |
Definition at line 697 of file Rokubimini.hpp.
|
protected |
Definition at line 705 of file Rokubimini.hpp.
|
protected |
Definition at line 713 of file Rokubimini.hpp.
|
protected |
Definition at line 721 of file Rokubimini.hpp.
|
protected |
The name of the device.
Definition at line 625 of file Rokubimini.hpp.
|
staticconstexprprotected |
NaN abbreviation for convenience.
Definition at line 617 of file Rokubimini.hpp.
|
protected |
The node handle of the ROS node, used by the publishers.
Definition at line 673 of file Rokubimini.hpp.
|
protected |
The product name of the rokubimini.
Definition at line 681 of file Rokubimini.hpp.
|
protected |
The reading of the device.
Definition at line 665 of file Rokubimini.hpp.
|
protected |
Definition at line 689 of file Rokubimini.hpp.
|
mutableprotected |
The mutex for accessing the reading.
Definition at line 657 of file Rokubimini.hpp.
|
protected |
The current statusword.
Definition at line 641 of file Rokubimini.hpp.
|
protected |
Flag indicating if a statusword has been actively requested.
Definition at line 649 of file Rokubimini.hpp.