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::Configuration & | getConfiguration () |
| Non-const version of getConfiguration() const. Gets the Configuration of the device. More... | |
| const configuration::Configuration & | getConfiguration () 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... | |
Class representing a rokubi mini device.
Definition at line 25 of file Rokubimini.hpp.
| 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.
| using rokubimini::Rokubimini::NodeHandlePtr = std::shared_ptr<ros::NodeHandle> |
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.
|
default |
Default constructor.
|
virtualdefault |
|
inline |
Adds a device disconnencted callback to a list.
| DeviceDisconnectedCb | The device disconnencted callback. |
| priority | The priority of the callback. |
Definition at line 169 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 182 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 117 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 130 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 143 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 156 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 104 of file Rokubimini.hpp.
| void rokubimini::Rokubimini::clearGoalStateEnum | ( | ) |
|
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 116 of file Rokubimini.cpp.
| bool rokubimini::Rokubimini::deviceIsInErrorState | ( | ) |
Checks 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.
Definition at line 110 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 160 of file Rokubimini.cpp.
|
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.
|
inline |
Non-const version of getConfiguration() const. Gets the Configuration of the device.
Definition at line 69 of file Rokubimini.hpp.
|
inline |
Gets the Configuration of the device.
Definition at line 81 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 |
| Reading rokubimini::Rokubimini::getReading | ( | ) | const |
Gets the reading from the Rokubimini device.
Definition at line 169 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 175 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 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.
| setup | The {Rokubimini Setup} to load. |
Definition at line 8 of file Rokubimini.cpp.
|
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 503 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 181 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 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.
|
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 580 of file Rokubimini.hpp.
|
protected |
Definition at line 668 of file Rokubimini.hpp.
|
protected |
Definition at line 676 of file Rokubimini.hpp.
|
protected |
Definition at line 636 of file Rokubimini.hpp.
|
protected |
Definition at line 644 of file Rokubimini.hpp.
|
protected |
Definition at line 652 of file Rokubimini.hpp.
|
protected |
Definition at line 660 of file Rokubimini.hpp.
|
protected |
The name of the device.
Definition at line 572 of file Rokubimini.hpp.
|
staticprotected |
NaN abbreviation for convenience.
Definition at line 564 of file Rokubimini.hpp.
|
protected |
The node handle of the ROS node, used by the publishers.
Definition at line 620 of file Rokubimini.hpp.
|
protected |
The reading of the device.
Definition at line 612 of file Rokubimini.hpp.
|
protected |
Definition at line 628 of file Rokubimini.hpp.
|
mutableprotected |
The mutex for accessing the reading.
Definition at line 604 of file Rokubimini.hpp.
|
protected |
The current statusword.
Definition at line 588 of file Rokubimini.hpp.
|
protected |
Flag indicating if a statusword has been actively requested.
Definition at line 596 of file Rokubimini.hpp.