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 createRosDiagnostics () override
 Adds ROS diagnostics related to the operation of rokubimini. More...
 
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...
 
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 postSetupConfiguration () override
 Post-setup configuration hook. More...
 
void preSetupConfiguration () override
 Pre-setup configuration hook. More...
 
void publishConnectionStatusDiagnostics ()
 Publishes the Connection Status Diagnostics to the "/diagnostics" topic. More...
 
void publishDataFlagsDiagnostics (const ros::TimerEvent &event)
 Publishes the Data Flags Diagnostics to the "/diagnostics" topic. More...
 
void publishRosDiagnostics () override
 Publish ROS diagnostics related to the operation of rokubimini. 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...
 
 RokubiminiEthercat (const std::string &name, NodeHandlePtr nh)
 
bool saveConfigParameter () override
 Saves the current configuration to the device. More...
 
template<>
bool sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, double &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, 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, int8_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, uint8_t &value)
 
template<typename Value >
bool sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &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<>
bool sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const double 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 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 int8_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 uint8_t value)
 
template<typename Value >
bool sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value 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...
 
void setRunsAsync (bool runsAsync)
 
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 updateConnectionStatus (diagnostic_updater::DiagnosticStatusWrapper &stat)
 Shows the Device Status of the rokubimini. 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
 
std::string getProductName () const
 
Reading getReading () const
 
void getReading (Reading &reading) const
 
Statusword getStatusword () const
 
virtual void load ()
 
 Rokubimini ()=default
 
 Rokubimini (const std::string &name, NodeHandlePtr nh)
 
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...
 
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...
 
Eigen::Matrix< double, 6, Eigen::Dynamic > resetServiceWrenchSamples_
 The wrench samples used by the "reset service" callback for calculating the mean wrench offset. 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_
 
DiagnosticsUpdaterPtr connectionStatusUpdater_
 
RosPublisherPtr dataFlagsDiagnosticsPublisher_
 
TimerPtr dataFlagsDiagnosticsTimer_
 
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_
 
std::string productName_
 
Reading reading_
 
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
 
std::recursive_mutex readingMutex_
 
Statusword statusword_
 
std::atomic< bool > statuswordRequested_
 

Static Protected Attributes

const static uint32_t TOTAL_NUMBER_OF_WRENCH_MESSAGES = 50
 
- 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::shared_ptr< diagnostic_updater::UpdaterDiagnosticsUpdaterPtr
 
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
 
typedef std::shared_ptr< ros::PublisherRosPublisherPtr
 
typedef std::shared_ptr< ros::TimerTimerPtr
 
- 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 25 of file RokubiminiEthercat.hpp.

Member Typedef Documentation

◆ RosPublisherPtr

Definition at line 488 of file RokubiminiEthercat.hpp.

Constructor & Destructor Documentation

◆ RokubiminiEthercat() [1/2]

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

Default constructor.

The default constructor of the RokubiminiEthercat class.

◆ RokubiminiEthercat() [2/2]

rokubimini::ethercat::RokubiminiEthercat::RokubiminiEthercat ( const std::string &  name,
NodeHandlePtr  nh 
)
inline

Definition at line 44 of file RokubiminiEthercat.hpp.

◆ ~RokubiminiEthercat()

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

Member Function Documentation

◆ createRosDiagnostics()

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

Adds ROS diagnostics related to the operation of rokubimini.

Implements rokubimini::Rokubimini.

Definition at line 200 of file RokubiminiEthercat.cpp.

◆ createRosPublishers()

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

Adds ROS publishers related to the device.

Implements rokubimini::Rokubimini.

Definition at line 130 of file RokubiminiEthercat.cpp.

◆ createRosServices()

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

Adds ROS services related to the device.

Implements rokubimini::Rokubimini.

Definition at line 360 of file RokubiminiEthercat.cpp.

◆ deviceIsMissing()

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

Checks if the device is missing.

Implements rokubimini::Rokubimini.

Definition at line 46 of file RokubiminiEthercat.cpp.

◆ firmwareUpdateCallback()

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 243 of file RokubiminiEthercat.cpp.

◆ getForceTorqueSamplingRate()

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 56 of file RokubiminiEthercat.cpp.

◆ getSerialNumber()

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 51 of file RokubiminiEthercat.cpp.

◆ postSetupConfiguration()

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

Post-setup configuration hook.

Implements rokubimini::Rokubimini.

Definition at line 12 of file RokubiminiEthercat.cpp.

◆ preSetupConfiguration()

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

Pre-setup configuration hook.

Implements rokubimini::Rokubimini.

Definition at line 15 of file RokubiminiEthercat.cpp.

◆ publishConnectionStatusDiagnostics()

void rokubimini::ethercat::RokubiminiEthercat::publishConnectionStatusDiagnostics ( )

Publishes the Connection Status Diagnostics to the "/diagnostics" topic.

Definition at line 217 of file RokubiminiEthercat.cpp.

◆ publishDataFlagsDiagnostics()

void rokubimini::ethercat::RokubiminiEthercat::publishDataFlagsDiagnostics ( const ros::TimerEvent event)

Publishes the Data Flags Diagnostics to the "/diagnostics" topic.

Definition at line 222 of file RokubiminiEthercat.cpp.

◆ publishRosDiagnostics()

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

Publish ROS diagnostics related to the operation of rokubimini.

Implements rokubimini::Rokubimini.

Definition at line 212 of file RokubiminiEthercat.cpp.

◆ publishRosMessages()

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

Publishes ROS messages with data from the rokubimini device.

Implements rokubimini::Rokubimini.

Definition at line 151 of file RokubiminiEthercat.cpp.

◆ resetWrenchCallback()

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 256 of file RokubiminiEthercat.cpp.

◆ saveConfigParameter()

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 121 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [1/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
double &  value 
)

Definition at line 443 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [2/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
float &  value 
)

Definition at line 436 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [3/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int16_t value 
)

Definition at line 387 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [4/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int32_t value 
)

Definition at line 394 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [5/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int64_t value 
)

Definition at line 401 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [6/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int8_t value 
)

Definition at line 380 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [7/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint16_t value 
)

Definition at line 415 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [8/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint32_t value 
)

Definition at line 422 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [9/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint64_t value 
)

Definition at line 429 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [10/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint8_t value 
)

Definition at line 408 of file RokubiminiEthercat.cpp.

◆ sendSdoRead() [11/11]

template<typename Value >
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoRead ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
Value &  value 
)

◆ sendSdoReadGeneric()

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 367 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [1/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const double  value 
)

Definition at line 513 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [2/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const float  value 
)

Definition at line 506 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [3/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int16_t  value 
)

Definition at line 457 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [4/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int32_t  value 
)

Definition at line 464 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [5/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int64_t  value 
)

Definition at line 471 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [6/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int8_t  value 
)

Definition at line 450 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [7/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint16_t  value 
)

Definition at line 485 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [8/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint32_t  value 
)

Definition at line 492 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [9/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint64_t  value 
)

Definition at line 499 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [10/11]

template<>
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint8_t  value 
)

Definition at line 478 of file RokubiminiEthercat.cpp.

◆ sendSdoWrite() [11/11]

template<typename Value >
bool rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const Value  value 
)

◆ sendSdoWriteGeneric()

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 373 of file RokubiminiEthercat.cpp.

◆ setAccelerationFilter()

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 66 of file RokubiminiEthercat.cpp.

◆ setAccelerationRange()

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 76 of file RokubiminiEthercat.cpp.

◆ setAngularRateFilter()

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 71 of file RokubiminiEthercat.cpp.

◆ setAngularRateRange()

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 81 of file RokubiminiEthercat.cpp.

◆ setConfigMode()

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

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 111 of file RokubiminiEthercat.cpp.

◆ setForceTorqueFilter()

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 61 of file RokubiminiEthercat.cpp.

◆ setForceTorqueOffset()

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 86 of file RokubiminiEthercat.cpp.

◆ setRunMode()

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

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 116 of file RokubiminiEthercat.cpp.

◆ setRunsAsync()

void rokubimini::ethercat::RokubiminiEthercat::setRunsAsync ( bool  runsAsync)

Definition at line 147 of file RokubiminiEthercat.cpp.

◆ setSensorCalibration()

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 101 of file RokubiminiEthercat.cpp.

◆ setSensorConfiguration()

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 91 of file RokubiminiEthercat.cpp.

◆ setSlavePointer()

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 114 of file RokubiminiEthercat.hpp.

◆ setState()

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 129 of file RokubiminiEthercat.hpp.

◆ shutdownWithCommunication()

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 39 of file RokubiminiEthercat.cpp.

◆ signalShutdown()

void rokubimini::ethercat::RokubiminiEthercat::signalShutdown ( )

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

Definition at line 188 of file RokubiminiEthercat.cpp.

◆ updateConnectionStatus()

void rokubimini::ethercat::RokubiminiEthercat::updateConnectionStatus ( diagnostic_updater::DiagnosticStatusWrapper stat)

Shows the Device Status of the rokubimini.

Definition at line 195 of file RokubiminiEthercat.cpp.

◆ updateProcessReading()

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 20 of file RokubiminiEthercat.cpp.

◆ waitForState()

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 144 of file RokubiminiEthercat.hpp.

Member Data Documentation

◆ computeMeanWrenchFlag_

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 546 of file RokubiminiEthercat.hpp.

◆ firmwareUpdateService_

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

The service for firmware updates.

Definition at line 529 of file RokubiminiEthercat.hpp.

◆ imuPublisher_

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

The sensor_msgs::Imu publisher.

Definition at line 513 of file RokubiminiEthercat.hpp.

◆ meanWrenchOffsetMutex_

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 563 of file RokubiminiEthercat.hpp.

◆ readingPublisher_

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

The rokubimini_msgs::Reading publisher.

Definition at line 497 of file RokubiminiEthercat.hpp.

◆ resetServiceWrenchSamples_

eigen::Matrix< double, 6, Dynamic > rokubimini::ethercat::RokubiminiEthercat::resetServiceWrenchSamples_
protected

The wrench samples used by the "reset service" callback for calculating the mean wrench offset.

Definition at line 580 of file RokubiminiEthercat.hpp.

◆ resetWrenchService_

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

The service for resetting the sensor wrench measurements.

Definition at line 537 of file RokubiminiEthercat.hpp.

◆ slavePtr_

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

The pointer to implementation.

Definition at line 486 of file RokubiminiEthercat.hpp.

◆ temperaturePublisher_

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

The sensor_msgs::Temperature publisher.

Definition at line 521 of file RokubiminiEthercat.hpp.

◆ TOTAL_NUMBER_OF_WRENCH_MESSAGES

const static uint32_t rokubimini::ethercat::RokubiminiEthercat::TOTAL_NUMBER_OF_WRENCH_MESSAGES = 50
staticprotected

Definition at line 572 of file RokubiminiEthercat.hpp.

◆ wrenchMessageCount_

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 555 of file RokubiminiEthercat.hpp.

◆ wrenchPublisher_

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

The sensor_msgs::Wrench publisher.

Definition at line 505 of file RokubiminiEthercat.hpp.


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


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:53:56