5 #include <rokubimini_msgs/FirmwareUpdateEthercat.h> 6 #include <rokubimini_msgs/ResetWrench.h> 319 rokubimini_msgs::FirmwareUpdateEthercat::Response& response);
332 rokubimini_msgs::ResetWrench::Response& response);
364 template <
typename Value>
380 bool sendSdoReadGeneric(
const std::string& indexString,
const std::string& subindexString,
381 const std::string& valueTypeString, std::string& valueString);
396 template <
typename Value>
413 bool sendSdoWriteGeneric(
const std::string& indexString,
const std::string& subindexString,
414 const std::string& valueTypeString,
const std::string& valueString);
void shutdownWithCommunication() override
Shuts down a Rokubimini Ethercat device before communication has been closed.
std::shared_ptr< ros::Publisher > RosPublisherPtr
The Rokubimini Ethercat class.
void setState(const uint16_t state)
Sets the desired EtherCAT state machine state of the device in the bus.
std::atomic< uint32_t > wrenchMessageCount_
The counter that is used for the computation of the mean of the wrench measurements. Used for the "reset service" callback.
void createRosPublishers() override
Adds ROS publishers related to the device.
RokubiminiEthercatSlavePtr slavePtr_
The pointer to implementation.
bool saveConfigParameter() override
Saves the current configuration to the device.
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.
void signalShutdown()
Signals shutdown for the ROS node. It's used if a firmware update was successful. ...
bool setAccelerationRange(const unsigned int range) override
Sets an acceleration range to the device.
bool resetWrenchCallback(rokubimini_msgs::ResetWrench::Request &request, rokubimini_msgs::ResetWrench::Response &response)
The callback for the reset wrench ROS service.
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) override
Sets a force torque offset to the device.
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter) override
Sets a force torque filter to the device.
~RokubiminiEthercat() override=default
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
RosPublisherPtr readingPublisher_
The rokubimini_msgs::Reading publisher.
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration) override
Sets a sensor calibration to the device.
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration) override
Sets a sensor configuration to the device.
bool firmwareUpdateCallback(rokubimini_msgs::FirmwareUpdateEthercat::Request &request, rokubimini_msgs::FirmwareUpdateEthercat::Response &response)
The callback for the firmware update ROS service.
void updateProcessReading() override
Updates the RokubiminiEthercat object with new measurements.
bool setAngularRateFilter(const unsigned int filter) override
Sets an angular rate filter to the device.
bool setAccelerationFilter(const unsigned int filter) override
Sets an acceleration filter to the device.
RosPublisherPtr imuPublisher_
The sensor_msgs::Imu publisher.
bool getForceTorqueSamplingRate(int &samplingRate) override
Gets the force torque sampling rate of the device.
ros::ServiceServer resetWrenchService_
The service for resetting the sensor wrench measurements.
bool waitForState(const uint16_t state)
Wait for an EtherCAT state machine state to be reached.
unsigned __int64 uint64_t
RokubiminiEthercat()=default
Default constructor.
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.
static const uint32_t TOTAL_NUMBER_OF_WRENCH_MESSAGES
void createRosServices() override
Adds ROS services related to the device.
std::shared_ptr< RokubiminiEthercatSlave > RokubiminiEthercatSlavePtr
bool setConfigMode()
Sets the device in config mode.
bool setRunMode()
Sets the device in run mode.
void setSlavePointer(const RokubiminiEthercatSlavePtr &slavePtr)
Sets a pointer to the implementation.
std::atomic< bool > computeMeanWrenchFlag_
The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset...
void doStartupWithCommunication() override
std::recursive_mutex meanWrenchOffsetMutex_
The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback...
RosPublisherPtr wrenchPublisher_
The sensor_msgs::Wrench publisher.
ros::ServiceServer firmwareUpdateService_
The service for firmware updates.
bool deviceIsMissing() const override
Checks if the device is missing.
bool getSerialNumber(unsigned int &samplingRate) override
Gets the serial number of the device.
RosPublisherPtr temperaturePublisher_
The sensor_msgs::Temperature publisher.
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
geometry_msgs::Wrench meanWrenchOffset_
The computed mean wrench offset. Used for the "reset service" callback.
void publishRosMessages() override
Publishes ROS messages with data from the rokubimini device.
bool setAngularRateRange(const unsigned int range) override
Sets an angular rate range to the device.