The Rokubimini Ethercat class. More...
#include <RokubiminiEthercat.hpp>
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 |
bool | firmwareUpdateCallback (rokubimini_msgs::FirmwareUpdateEthercat::Request &request, rokubimini_msgs::FirmwareUpdateEthercat::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 &samplingRate) override |
Gets the serial number of the device. 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... | |
RokubiminiEthercat ()=default | |
Default constructor. More... | |
bool | saveConfigParameter () override |
Saves the current configuration to the device. More... | |
template<typename Value > | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, int8_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, int16_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, int32_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, int64_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint8_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint16_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint32_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint64_t &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, float &value) |
template<> | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, double &value) |
bool | sendSdoReadGeneric (const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, std::string &valueString) |
Sends a generic reading SDO to the Ethercat device. More... | |
template<typename Value > | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int8_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int16_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int32_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int64_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint8_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint16_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint32_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint64_t value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const float value) |
template<> | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const double value) |
bool | sendSdoWriteGeneric (const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, const std::string &valueString) |
Sends a generic write SDO to the Ethercat 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 | 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 | setSlavePointer (const RokubiminiEthercatSlavePtr &slavePtr) |
Sets a pointer to the implementation. More... | |
void | setState (const uint16_t state) |
Sets the desired EtherCAT state machine state of the device in the bus. More... | |
void | shutdownWithCommunication () override |
Shuts down a Rokubimini Ethercat 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 RokubiminiEthercat object with new measurements. More... | |
bool | waitForState (const uint16_t state) |
Wait for an EtherCAT state machine state to be reached. More... | |
~RokubiminiEthercat () 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::Configuration & | getConfiguration () |
const configuration::Configuration & | getConfiguration () 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... | |
RosPublisherPtr | imuPublisher_ |
The sensor_msgs::Imu publisher. 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... | |
RosPublisherPtr | readingPublisher_ |
The rokubimini_msgs::Reading publisher. More... | |
ros::ServiceServer | resetWrenchService_ |
The service for resetting the sensor wrench measurements. More... | |
RokubiminiEthercatSlavePtr | slavePtr_ { nullptr } |
The pointer to implementation. 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::NodeHandle > | NodeHandlePtr |
typedef std::function< void(const std::string &, const Reading &)> | ReadingCb |
Protected Member Functions inherited from rokubimini::Rokubimini | |
void | setStatusword (Statusword &statusword) |
The Rokubimini Ethercat 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 RokubiminiEthercatSlave.
Definition at line 24 of file RokubiminiEthercat.hpp.
|
protected |
Definition at line 426 of file RokubiminiEthercat.hpp.
|
default |
Default constructor.
The default constructor of the RokubiminiEthercat class.
|
overridedefault |
|
overridevirtual |
Adds ROS publishers related to the device.
Implements rokubimini::Rokubimini.
Definition at line 152 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Adds ROS services related to the device.
Implements rokubimini::Rokubimini.
Definition at line 285 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Checks if the device is missing.
Implements rokubimini::Rokubimini.
Definition at line 68 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Implements rokubimini::Rokubimini.
Definition at line 10 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::firmwareUpdateCallback | ( | rokubimini_msgs::FirmwareUpdateEthercat::Request & | request, |
rokubimini_msgs::FirmwareUpdateEthercat::Response & | response | ||
) |
The callback for the firmware update ROS service.
request | The request of the ROS service. |
response | The response of the ROS service. |
Definition at line 211 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Gets the force torque sampling rate of the device.
samplingRate | The force torque sampling rate to be fetched. |
Implements rokubimini::Rokubimini.
Definition at line 78 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Gets the serial number of the device.
serialNumber | The serial number to be fetched. |
Implements rokubimini::Rokubimini.
Definition at line 73 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Publishes ROS messages with data from the rokubimini device.
Implements rokubimini::Rokubimini.
Definition at line 167 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::resetWrenchCallback | ( | rokubimini_msgs::ResetWrench::Request & | request, |
rokubimini_msgs::ResetWrench::Response & | response | ||
) |
The callback for the reset wrench ROS service.
request | The request of the ROS service. |
response | The response of the ROS service. |
Definition at line 224 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Saves the current configuration to the device.
Implements rokubimini::Rokubimini.
Definition at line 143 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
Value & | value | ||
) |
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
int8_t & | value | ||
) |
Definition at line 305 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
int16_t & | value | ||
) |
Definition at line 312 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
int32_t & | value | ||
) |
Definition at line 319 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
int64_t & | value | ||
) |
Definition at line 326 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
uint8_t & | value | ||
) |
Definition at line 333 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
uint16_t & | value | ||
) |
Definition at line 340 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
uint32_t & | value | ||
) |
Definition at line 347 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
uint64_t & | value | ||
) |
Definition at line 354 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
float & | value | ||
) |
Definition at line 361 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
double & | value | ||
) |
Definition at line 368 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoReadGeneric | ( | const std::string & | indexString, |
const std::string & | subindexString, | ||
const std::string & | valueTypeString, | ||
std::string & | valueString | ||
) |
Sends a generic reading SDO to the Ethercat device.
indexString | A string containing the index of the SDO. |
subindexString | A string containing the sub-index of the SDO. |
valueTypeString | A string containing the type of the value to read. |
valueString | A string containing the value to read. |
Definition at line 292 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const Value | value | ||
) |
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const int8_t | value | ||
) |
Definition at line 375 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const int16_t | value | ||
) |
Definition at line 382 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const int32_t | value | ||
) |
Definition at line 389 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const int64_t | value | ||
) |
Definition at line 396 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const uint8_t | value | ||
) |
Definition at line 403 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const uint16_t | value | ||
) |
Definition at line 410 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const uint32_t | value | ||
) |
Definition at line 417 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const uint64_t | value | ||
) |
Definition at line 424 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const float | value | ||
) |
Definition at line 431 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite | ( | const uint16_t | index, |
const uint8_t | subindex, | ||
const bool | completeAccess, | ||
const double | value | ||
) |
Definition at line 438 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWriteGeneric | ( | const std::string & | indexString, |
const std::string & | subindexString, | ||
const std::string & | valueTypeString, | ||
const std::string & | valueString | ||
) |
Sends a generic write SDO to the Ethercat device.
indexString | A string containing the index of the SDO. |
subindexString | A string containing the sub-index of the SDO. |
valueTypeString | A string containing the type of the value to write. |
valueString | A string containing the value to write. |
Definition at line 298 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets an acceleration filter to the device.
filter | The filter to be set. |
Implements rokubimini::Rokubimini.
Definition at line 88 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets an acceleration range to the device.
range | The range to be set. |
Implements rokubimini::Rokubimini.
Definition at line 98 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets an angular rate filter to the device.
filter | The filter to be set. |
Implements rokubimini::Rokubimini.
Definition at line 93 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets an angular rate range to the device.
range | The range to be set. |
Implements rokubimini::Rokubimini.
Definition at line 103 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::setConfigMode | ( | ) |
Sets the device in config mode.
Definition at line 133 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets a force torque filter to the device.
filter | The filter to be set. |
Implements rokubimini::Rokubimini.
Definition at line 83 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets a force torque offset to the device.
forceTorqueOffset | The offset to be set. |
Implements rokubimini::Rokubimini.
Definition at line 108 of file RokubiminiEthercat.cpp.
bool rokubimini::ethercat::RokubiminiEthercat::setRunMode | ( | ) |
Sets the device in run mode.
Definition at line 138 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets a sensor calibration to the device.
sensorCalibration | The calibration to be set. |
Implements rokubimini::Rokubimini.
Definition at line 123 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Sets a sensor configuration to the device.
sensorConfiguration | The configuration to be set. |
Implements rokubimini::Rokubimini.
Definition at line 113 of file RokubiminiEthercat.cpp.
|
inline |
Sets a pointer to the implementation.
This method realizes the pimpl paradigm. Through it, the RokubiminiEthercat object holds a pointer to its implementation, a RokubiminiEthercatSlave object.
slavePtr | The pointer to the RokubiminiEthercatSlave implementation. |
Definition at line 97 of file RokubiminiEthercat.hpp.
|
inline |
Sets the desired EtherCAT state machine state of the device in the bus.
state | Desired state. |
Definition at line 112 of file RokubiminiEthercat.hpp.
|
overridevirtual |
Shuts down a Rokubimini Ethercat device before communication has been closed.
This method shuts down a Rokubimini Ethercat device before the EthercatBusManager has terminated communication with the device.
Implements rokubimini::Rokubimini.
Definition at line 63 of file RokubiminiEthercat.cpp.
void rokubimini::ethercat::RokubiminiEthercat::signalShutdown | ( | ) |
Signals shutdown for the ROS node. It's used if a firmware update was successful.
Definition at line 204 of file RokubiminiEthercat.cpp.
|
overridevirtual |
Updates the RokubiminiEthercat object with new measurements.
This method updates the internal Reading variable of RokubiminiEthercat, by getting the new values from its implementation RokubiminiEthercatSlave.
Implements rokubimini::Rokubimini.
Definition at line 14 of file RokubiminiEthercat.cpp.
|
inline |
Wait for an EtherCAT state machine state to be reached.
state | Desired state. |
Definition at line 127 of file RokubiminiEthercat.hpp.
|
protected |
The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset service" callback.
Definition at line 484 of file RokubiminiEthercat.hpp.
|
protected |
The service for firmware updates.
Definition at line 467 of file RokubiminiEthercat.hpp.
|
protected |
The sensor_msgs::Imu publisher.
Definition at line 451 of file RokubiminiEthercat.hpp.
|
protected |
The computed mean wrench offset. Used for the "reset service" callback.
Definition at line 518 of file RokubiminiEthercat.hpp.
|
mutableprotected |
The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback.
Definition at line 501 of file RokubiminiEthercat.hpp.
|
protected |
The rokubimini_msgs::Reading publisher.
Definition at line 435 of file RokubiminiEthercat.hpp.
|
protected |
The service for resetting the sensor wrench measurements.
Definition at line 475 of file RokubiminiEthercat.hpp.
|
protected |
The pointer to implementation.
Definition at line 424 of file RokubiminiEthercat.hpp.
|
protected |
The sensor_msgs::Temperature publisher.
Definition at line 459 of file RokubiminiEthercat.hpp.
|
staticprotected |
Definition at line 510 of file RokubiminiEthercat.hpp.
|
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 493 of file RokubiminiEthercat.hpp.
|
protected |
The sensor_msgs::Wrench publisher.
Definition at line 443 of file RokubiminiEthercat.hpp.