Public Member Functions | Protected Types | Protected Attributes | Static Protected Attributes | List of all members
rokubimini::serial::RokubiminiSerial Class Reference

The Rokubimini Serial class. More...

#include <RokubiminiSerial.hpp>

Inheritance diagram for rokubimini::serial::RokubiminiSerial:
Inheritance graph
[legend]

Public Member Functions

void createRosPublishers () override
 Adds ROS publishers related to the device. More...
 
void createRosServices () override
 Adds ROS services related to the device. More...
 
bool deviceIsMissing () const override
 Checks if the device is missing. More...
 
void doStartupWithCommunication () override
 Starts up a Rokubimini Serial device after communication has been established. More...
 
bool firmwareUpdateCallback (rokubimini_msgs::FirmwareUpdateSerial::Request &request, rokubimini_msgs::FirmwareUpdateSerial::Response &response)
 The callback for the firmware update ROS service. More...
 
bool getForceTorqueSamplingRate (int &samplingRate) override
 Gets the force torque sampling rate of the device. More...
 
bool getSerialNumber (unsigned int &serialNumber) override
 Gets the serial number of the device. More...
 
bool init ()
 Initializes communication with a Rokubimini Serial device. More...
 
bool loadConfig ()
 Loads the configuration of the device. More...
 
bool printUserConfig ()
 Prints all the user configurable parameters. More...
 
void publishRosMessages () override
 Publishes ROS messages with data from the rokubimini device. More...
 
bool resetWrenchCallback (rokubimini_msgs::ResetWrench::Request &request, rokubimini_msgs::ResetWrench::Response &response)
 The callback for the reset wrench ROS service. More...
 
 RokubiminiSerial ()=default
 Default constructor. More...
 
bool saveConfigParameter () override
 Saves the current configuration to the device. More...
 
bool setAccelerationFilter (const unsigned int filter) override
 Sets an acceleration filter to the device. More...
 
bool setAccelerationRange (const unsigned int range) override
 Sets an acceleration range to the device. More...
 
bool setAngularRateFilter (const unsigned int filter) override
 Sets an angular rate filter to the device. More...
 
bool setAngularRateRange (const unsigned int range) override
 Sets an angular rate range to the device. More...
 
bool setConfigMode ()
 Sets the device in config mode. More...
 
bool setForceTorqueFilter (const configuration::ForceTorqueFilter &filter) override
 Sets a force torque filter to the device. More...
 
bool setForceTorqueOffset (const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) override
 Sets a force torque offset to the device. More...
 
bool setHardwareReset ()
 Triggers a hardware reset of the sensor. More...
 
void setImplPointer (const RokubiminiSerialImplPtr &implPtr)
 Sets a pointer to the implementation. More...
 
bool setInitMode ()
 Triggers a software reset of the sensor bringing it to a known state. More...
 
bool setRunMode ()
 Sets the device in run mode. More...
 
bool setSensorCalibration (const calibration::SensorCalibration &sensorCalibration) override
 Sets a sensor calibration to the device. More...
 
bool setSensorConfiguration (const configuration::SensorConfiguration &sensorConfiguration) override
 Sets a sensor configuration to the device. More...
 
void setState (const uint16_t state)
 Sets the state of the device in the bus (unused). More...
 
void shutdownWithCommunication () override
 Shuts down a Rokubimini Serial device before communication has been closed. More...
 
void signalShutdown ()
 Signals shutdown for the ROS node. It's used if a firmware update was successful. More...
 
void updateProcessReading () override
 Updates the RokubiminiSerial object with new measurements. More...
 
bool waitForState (const uint16_t state)
 Wait for a state to be reached (unused). More...
 
 ~RokubiminiSerial () override=default
 
- Public Member Functions inherited from rokubimini::Rokubimini
void addDeviceDisconnectedCb (const DeviceDisconnectedCb &deviceDisconnectedCb, const int priority=0)
 
void addDeviceReconnectedCb (const DeviceReconnectedCb &deviceReconnectedCb, const int priority=0)
 
void addErrorCb (const ErrorCb &errorCb, const int priority=0)
 
void addErrorRecoveredCb (const ErrorRecoveredCb &errorRecoveredCb, const int priority=0)
 
void addFatalCb (const FatalCb &fatalCb, const int priority=0)
 
void addFatalRecoveredCb (const FatalRecoveredCb &fatalRecoveredCb, const int priority=0)
 
void addReadingCb (const ReadingCb &readingCb, const int priority=0)
 
void clearGoalStateEnum ()
 
void deviceDisconnectedCb ()
 
bool deviceIsInErrorState ()
 
bool deviceIsInFatalState ()
 
void deviceReconnectedCb ()
 
void errorCb ()
 
void errorRecoveredCb ()
 
void fatalCb ()
 
void fatalRecoveredCb ()
 
configuration::ConfigurationgetConfiguration ()
 
const configuration::ConfigurationgetConfiguration () const
 
std::string getName () const
 
Reading getReading () const
 
void getReading (Reading &reading) const
 
Statusword getStatusword () const
 
bool loadRokubiminiSetup (std::shared_ptr< rokubimini::setup::Rokubimini > setup)
 
 Rokubimini ()=default
 
void setNodeHandle (const NodeHandlePtr &nh)
 
virtual void shutdownWithoutCommunication ()
 
void startupWithCommunication ()
 
void startupWithoutCommunication ()
 
virtual ~Rokubimini ()=default
 

Protected Types

using RosPublisherPtr = std::shared_ptr< ros::Publisher >
 

Protected Attributes

std::atomic< bool > computeMeanWrenchFlag_ { false }
 The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset service" callback. More...
 
ros::ServiceServer firmwareUpdateService_
 The service for firmware updates. More...
 
RokubiminiSerialImplPtr implPtr_ { nullptr }
 The pointer to implementation. More...
 
geometry_msgs::Wrench meanWrenchOffset_
 The computed mean wrench offset. Used for the "reset service" callback. More...
 
std::recursive_mutex meanWrenchOffsetMutex_
 The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback. More...
 
uint64_t noFrameSyncCounter_ { 0 }
 The counter for measuring failed frame synchronizations. More...
 
RosPublisherPtr readingPublisher_
 The rokubimini_msgs::Reading publisher. More...
 
ros::ServiceServer resetWrenchService_
 The service for resetting the sensor wrench measurements. More...
 
RosPublisherPtr temperaturePublisher_
 The sensor_msgs::Temperature publisher. More...
 
std::atomic< uint32_t > wrenchMessageCount_ { 0 }
 The counter that is used for the computation of the mean of the wrench measurements. Used for the "reset service" callback. More...
 
RosPublisherPtr wrenchPublisher_
 The sensor_msgs::Wrench publisher. More...
 
- Protected Attributes inherited from rokubimini::Rokubimini
configuration::Configuration configuration_
 
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_
 
NodeHandlePtr nh_
 
Reading reading_
 
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
 
std::recursive_mutex readingMutex_
 
Statusword statusword_
 
std::atomic< bool > statuswordRequested_
 

Static Protected Attributes

static const uint32_t TOTAL_NUMBER_OF_WRENCH_MESSAGES = 200
 
- Static Protected Attributes inherited from rokubimini::Rokubimini
static constexpr double NAN_VALUE
 

Additional Inherited Members

- Public Types inherited from rokubimini::Rokubimini
typedef std::function< void(void)> AnonymousErrorCb
 
typedef std::function< void(const Reading &)> AnonymousReadingCb
 
typedef std::function< void(const std::string &)> DeviceDisconnectedCb
 
typedef std::function< void(const std::string &)> DeviceReconnectedCb
 
typedef std::function< void(const std::string &)> ErrorCb
 
typedef std::function< void(const std::string &)> ErrorRecoveredCb
 
typedef std::function< void(const std::string &)> FatalCb
 
typedef std::function< void(const std::string &)> FatalRecoveredCb
 
typedef std::shared_ptr< ros::NodeHandleNodeHandlePtr
 
typedef std::function< void(const std::string &, const Reading &)> ReadingCb
 
- Protected Member Functions inherited from rokubimini::Rokubimini
void setStatusword (Statusword &statusword)
 

Detailed Description

The Rokubimini Serial class.

Inherits from the Rokubimini class. It's the interface in the BRIDGE pattern used. It provides the API to be called by client code and is used for interfacing with the implementation class called RokubiminiSerialImpl.

Definition at line 25 of file RokubiminiSerial.hpp.

Member Typedef Documentation

Definition at line 409 of file RokubiminiSerial.hpp.

Constructor & Destructor Documentation

rokubimini::serial::RokubiminiSerial::RokubiminiSerial ( )
default

Default constructor.

The default constructor of the RokubiminiSerial class.

rokubimini::serial::RokubiminiSerial::~RokubiminiSerial ( )
overridedefault

Member Function Documentation

void rokubimini::serial::RokubiminiSerial::createRosPublishers ( )
overridevirtual

Adds ROS publishers related to the device.

Implements rokubimini::Rokubimini.

Definition at line 196 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::createRosServices ( )
overridevirtual

Adds ROS services related to the device.

Implements rokubimini::Rokubimini.

Definition at line 338 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::deviceIsMissing ( ) const
overridevirtual

Checks if the device is missing.

Implements rokubimini::Rokubimini.

Definition at line 93 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::doStartupWithCommunication ( )
overridevirtual

Starts up a Rokubimini Serial device after communication has been established.

This method starts up a Rokubimini Serial device after the SerialBusManager has established communication with the device.

Implements rokubimini::Rokubimini.

Definition at line 10 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::firmwareUpdateCallback ( rokubimini_msgs::FirmwareUpdateSerial::Request &  request,
rokubimini_msgs::FirmwareUpdateSerial::Response &  response 
)

The callback for the firmware update ROS service.

Parameters
requestThe request of the ROS service.
responseThe response of the ROS service.
Returns
True always.

Definition at line 262 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::getForceTorqueSamplingRate ( int &  samplingRate)
overridevirtual

Gets the force torque sampling rate of the device.

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

Implements rokubimini::Rokubimini.

Definition at line 103 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::getSerialNumber ( unsigned int &  serialNumber)
overridevirtual

Gets the serial number of the device.

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

Implements rokubimini::Rokubimini.

Definition at line 98 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::init ( )

Initializes communication with a Rokubimini Serial device.

This method is called by the SerialBusManager to establish communication with the device.

Definition at line 22 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::loadConfig ( )

Loads the configuration of the device.

Returns
True if the operation was successful.

Definition at line 173 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::printUserConfig ( )

Prints all the user configurable parameters.

Returns
True if the operation was successful.

Definition at line 178 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::publishRosMessages ( )
overridevirtual

Publishes ROS messages with data from the rokubimini device.

Implements rokubimini::Rokubimini.

Definition at line 208 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::resetWrenchCallback ( rokubimini_msgs::ResetWrench::Request &  request,
rokubimini_msgs::ResetWrench::Response &  response 
)

The callback for the reset wrench ROS service.

Parameters
requestThe request of the ROS service.
responseThe response of the ROS service.
Returns
True always.

Definition at line 275 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::saveConfigParameter ( )
overridevirtual

Saves the current configuration to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 168 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setAccelerationFilter ( const unsigned int  filter)
overridevirtual

Sets an acceleration filter to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 113 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setAccelerationRange ( const unsigned int  range)
overridevirtual

Sets an acceleration range to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 123 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setAngularRateFilter ( const unsigned int  filter)
overridevirtual

Sets an angular rate filter to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 118 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setAngularRateRange ( const unsigned int  range)
overridevirtual

Sets an angular rate range to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 128 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setConfigMode ( )

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 158 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setForceTorqueFilter ( const configuration::ForceTorqueFilter filter)
overridevirtual

Sets a force torque filter to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 108 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setForceTorqueOffset ( const Eigen::Matrix< double, 6, 1 > &  forceTorqueOffset)
overridevirtual

Sets a force torque offset to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 133 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setHardwareReset ( )

Triggers a hardware reset of the sensor.

Returns
True if the operation was successful.

Definition at line 183 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::setImplPointer ( const RokubiminiSerialImplPtr implPtr)
inline

Sets a pointer to the implementation.

This method realizes the pimpl paradigm. Through it, the RokubiminiSerial object holds a pointer to its implementation, a RokubiminiSerialImpl object.

Parameters
implPtrThe pointer to the RokubiminiSerialImpl implementation.

Definition at line 107 of file RokubiminiSerial.hpp.

bool rokubimini::serial::RokubiminiSerial::setInitMode ( )

Triggers a software reset of the sensor bringing it to a known state.

Returns
True if the operation was successful.

Definition at line 188 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setRunMode ( )

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 163 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setSensorCalibration ( const calibration::SensorCalibration sensorCalibration)
overridevirtual

Sets a sensor calibration to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 148 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::setSensorConfiguration ( const configuration::SensorConfiguration sensorConfiguration)
overridevirtual

Sets a sensor configuration to the device.

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

Implements rokubimini::Rokubimini.

Definition at line 138 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::setState ( const uint16_t  state)
inline

Sets the state of the device in the bus (unused).

Parameters
stateDesired state.

Definition at line 121 of file RokubiminiSerial.hpp.

void rokubimini::serial::RokubiminiSerial::shutdownWithCommunication ( )
overridevirtual

Shuts down a Rokubimini Serial device before communication has been closed.

This method shuts down a Rokubimini Serial device before the SerialBusManager has terminated communication with the device.

Implements rokubimini::Rokubimini.

Definition at line 88 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::signalShutdown ( )

Signals shutdown for the ROS node. It's used if a firmware update was successful.

Definition at line 255 of file RokubiminiSerial.cpp.

void rokubimini::serial::RokubiminiSerial::updateProcessReading ( )
overridevirtual

Updates the RokubiminiSerial object with new measurements.

This method updates the internal Reading variable of RokubiminiSerial, by getting the new values from its implementation RokubiminiSerialImpl.

Implements rokubimini::Rokubimini.

Definition at line 34 of file RokubiminiSerial.cpp.

bool rokubimini::serial::RokubiminiSerial::waitForState ( const uint16_t  state)
inline

Wait for a state to be reached (unused).

Parameters
stateDesired state.
Returns
True if the state has been reached within the timeout.

Definition at line 136 of file RokubiminiSerial.hpp.

Member Data Documentation

std::atomic< bool > rokubimini::serial::RokubiminiSerial::computeMeanWrenchFlag_ { false }
protected

The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset service" callback.

Definition at line 466 of file RokubiminiSerial.hpp.

ros::ServiceServer rokubimini::serial::RokubiminiSerial::firmwareUpdateService_
protected

The service for firmware updates.

Definition at line 441 of file RokubiminiSerial.hpp.

RokubiminiSerialImplPtr rokubimini::serial::RokubiminiSerial::implPtr_ { nullptr }
protected

The pointer to implementation.

Definition at line 407 of file RokubiminiSerial.hpp.

geometry_msgs::Wrench rokubimini::serial::RokubiminiSerial::meanWrenchOffset_
protected

The computed mean wrench offset. Used for the "reset service" callback.

Definition at line 500 of file RokubiminiSerial.hpp.

std::recursive_mutex rokubimini::serial::RokubiminiSerial::meanWrenchOffsetMutex_
mutableprotected

The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback.

Definition at line 483 of file RokubiminiSerial.hpp.

uint64_t rokubimini::serial::RokubiminiSerial::noFrameSyncCounter_ { 0 }
protected

The counter for measuring failed frame synchronizations.

Definition at line 457 of file RokubiminiSerial.hpp.

RosPublisherPtr rokubimini::serial::RokubiminiSerial::readingPublisher_
protected

The rokubimini_msgs::Reading publisher.

Definition at line 417 of file RokubiminiSerial.hpp.

ros::ServiceServer rokubimini::serial::RokubiminiSerial::resetWrenchService_
protected

The service for resetting the sensor wrench measurements.

Definition at line 449 of file RokubiminiSerial.hpp.

RosPublisherPtr rokubimini::serial::RokubiminiSerial::temperaturePublisher_
protected

The sensor_msgs::Temperature publisher.

Definition at line 433 of file RokubiminiSerial.hpp.

const uint32_t rokubimini::serial::RokubiminiSerial::TOTAL_NUMBER_OF_WRENCH_MESSAGES = 200
staticprotected

Definition at line 492 of file RokubiminiSerial.hpp.

std::atomic< uint32_t > rokubimini::serial::RokubiminiSerial::wrenchMessageCount_ { 0 }
protected

The counter that is used for the computation of the mean of the wrench measurements. Used for the "reset service" callback.

Definition at line 475 of file RokubiminiSerial.hpp.

RosPublisherPtr rokubimini::serial::RokubiminiSerial::wrenchPublisher_
protected

The sensor_msgs::Wrench publisher.

Definition at line 425 of file RokubiminiSerial.hpp.


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


rokubimini_serial
Author(s):
autogenerated on Wed Mar 3 2021 03:09:18