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

The Rokubimini Ethercat class. More...

#include <RokubiminiEthercat.hpp>

Inheritance diagram for rokubimini::ethercat::RokubiminiEthercat:
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
 
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::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...
 
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_twrenchMessageCount_ { 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 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.

Member Typedef Documentation

Definition at line 426 of file RokubiminiEthercat.hpp.

Constructor & Destructor Documentation

rokubimini::ethercat::RokubiminiEthercat::RokubiminiEthercat ( )
default

Default constructor.

The default constructor of the RokubiminiEthercat class.

rokubimini::ethercat::RokubiminiEthercat::~RokubiminiEthercat ( )
overridedefault

Member Function Documentation

void rokubimini::ethercat::RokubiminiEthercat::createRosPublishers ( )
overridevirtual

Adds ROS publishers related to the device.

Implements rokubimini::Rokubimini.

Definition at line 152 of file RokubiminiEthercat.cpp.

void rokubimini::ethercat::RokubiminiEthercat::createRosServices ( )
overridevirtual

Adds ROS services related to the device.

Implements rokubimini::Rokubimini.

Definition at line 285 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::deviceIsMissing ( ) const
overridevirtual

Checks if the device is missing.

Implements rokubimini::Rokubimini.

Definition at line 68 of file RokubiminiEthercat.cpp.

void rokubimini::ethercat::RokubiminiEthercat::doStartupWithCommunication ( )
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.

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

Definition at line 211 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 78 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 73 of file RokubiminiEthercat.cpp.

void rokubimini::ethercat::RokubiminiEthercat::publishRosMessages ( )
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.

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

Definition at line 224 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 143 of file RokubiminiEthercat.cpp.

template<typename Value >
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.

Parameters
indexStringA string containing the index of the SDO.
subindexStringA string containing the sub-index of the SDO.
valueTypeStringA string containing the type of the value to read.
valueStringA string containing the value to read.
Returns
True if the SDO read was sent successfully.

Definition at line 292 of file RokubiminiEthercat.cpp.

template<typename Value >
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.

Parameters
indexStringA string containing the index of the SDO.
subindexStringA string containing the sub-index of the SDO.
valueTypeStringA string containing the type of the value to write.
valueStringA string containing the value to write.
Returns
True if the SDO write was sent successfully.

Definition at line 298 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 88 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 98 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 93 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 103 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::setConfigMode ( )

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 133 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 83 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 108 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::setRunMode ( )

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 138 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 123 of file RokubiminiEthercat.cpp.

bool rokubimini::ethercat::RokubiminiEthercat::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 113 of file RokubiminiEthercat.cpp.

void rokubimini::ethercat::RokubiminiEthercat::setSlavePointer ( const RokubiminiEthercatSlavePtr slavePtr)
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.

Parameters
slavePtrThe pointer to the RokubiminiEthercatSlave implementation.

Definition at line 97 of file RokubiminiEthercat.hpp.

void rokubimini::ethercat::RokubiminiEthercat::setState ( const uint16_t  state)
inline

Sets the desired EtherCAT state machine state of the device in the bus.

Parameters
stateDesired state.

Definition at line 112 of file RokubiminiEthercat.hpp.

void rokubimini::ethercat::RokubiminiEthercat::shutdownWithCommunication ( )
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.

void rokubimini::ethercat::RokubiminiEthercat::updateProcessReading ( )
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.

bool rokubimini::ethercat::RokubiminiEthercat::waitForState ( const uint16_t  state)
inline

Wait for an EtherCAT state machine state to be reached.

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

Definition at line 127 of file RokubiminiEthercat.hpp.

Member Data Documentation

std::atomic< bool > rokubimini::ethercat::RokubiminiEthercat::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 484 of file RokubiminiEthercat.hpp.

ros::ServiceServer rokubimini::ethercat::RokubiminiEthercat::firmwareUpdateService_
protected

The service for firmware updates.

Definition at line 467 of file RokubiminiEthercat.hpp.

RosPublisherPtr rokubimini::ethercat::RokubiminiEthercat::imuPublisher_
protected

The sensor_msgs::Imu publisher.

Definition at line 451 of file RokubiminiEthercat.hpp.

geometry_msgs::Wrench rokubimini::ethercat::RokubiminiEthercat::meanWrenchOffset_
protected

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

Definition at line 518 of file RokubiminiEthercat.hpp.

std::recursive_mutex rokubimini::ethercat::RokubiminiEthercat::meanWrenchOffsetMutex_
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.

RosPublisherPtr rokubimini::ethercat::RokubiminiEthercat::readingPublisher_
protected

The rokubimini_msgs::Reading publisher.

Definition at line 435 of file RokubiminiEthercat.hpp.

ros::ServiceServer rokubimini::ethercat::RokubiminiEthercat::resetWrenchService_
protected

The service for resetting the sensor wrench measurements.

Definition at line 475 of file RokubiminiEthercat.hpp.

RokubiminiEthercatSlavePtr rokubimini::ethercat::RokubiminiEthercat::slavePtr_ { nullptr }
protected

The pointer to implementation.

Definition at line 424 of file RokubiminiEthercat.hpp.

RosPublisherPtr rokubimini::ethercat::RokubiminiEthercat::temperaturePublisher_
protected

The sensor_msgs::Temperature publisher.

Definition at line 459 of file RokubiminiEthercat.hpp.

const uint32_t rokubimini::ethercat::RokubiminiEthercat::TOTAL_NUMBER_OF_WRENCH_MESSAGES = 200
staticprotected

Definition at line 510 of file RokubiminiEthercat.hpp.

std::atomic< uint32_t > rokubimini::ethercat::RokubiminiEthercat::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 493 of file RokubiminiEthercat.hpp.

RosPublisherPtr rokubimini::ethercat::RokubiminiEthercat::wrenchPublisher_
protected

The sensor_msgs::Wrench publisher.

Definition at line 443 of file RokubiminiEthercat.hpp.


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


rokubimini_ethercat
Author(s):
autogenerated on Wed Mar 3 2021 03:09:16