RokubiminiEthercat.cpp
Go to the documentation of this file.
2 #include <rokubimini_msgs/Reading.h>
3 #include <csignal>
4 #include <thread>
6 #include <diagnostic_msgs/DiagnosticArray.h>
7 
8 namespace rokubimini
9 {
10 namespace ethercat
11 {
13 {
14 }
16 {
17  slavePtr_->preSetupConfiguration();
18 }
19 
21 {
22  {
23  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
24  slavePtr_->getReading(reading_);
25 
26  // Update statusword.
27  auto statusword(reading_.getStatusword());
28  setStatusword(statusword);
29  statuswordRequested_ = false;
30  }
31 
32  if (deviceIsMissing())
33  {
34  Statusword statusword;
35  setStatusword(statusword);
36  }
37 }
38 
40 {
41  slavePtr_->shutdown();
42  // publish the last diagnostics before shutdown
43  connectionStatusUpdater_->force_update();
44 }
45 
47 {
48  return false;
49 }
50 
51 bool RokubiminiEthercat::getSerialNumber(unsigned int& serialNumber)
52 {
53  return slavePtr_->getSerialNumber(serialNumber);
54 }
55 
57 {
58  return slavePtr_->getForceTorqueSamplingRate(samplingRate);
59 }
60 
62 {
63  return slavePtr_->setForceTorqueFilter(filter);
64 }
65 
66 bool RokubiminiEthercat::setAccelerationFilter(const unsigned int filter)
67 {
68  return slavePtr_->setAccelerationFilter(filter);
69 }
70 
71 bool RokubiminiEthercat::setAngularRateFilter(const unsigned int filter)
72 {
73  return slavePtr_->setAngularRateFilter(filter);
74 }
75 
76 bool RokubiminiEthercat::setAccelerationRange(const unsigned int range)
77 {
78  return slavePtr_->setAccelerationRange(range);
79 }
80 
81 bool RokubiminiEthercat::setAngularRateRange(const unsigned int range)
82 {
83  return slavePtr_->setAngularRateRange(range);
84 }
85 
86 bool RokubiminiEthercat::setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset)
87 {
88  return slavePtr_->setForceTorqueOffset(forceTorqueOffset);
89 }
90 
92 {
93  if (!slavePtr_->setSensorConfiguration(sensorConfiguration))
94  {
95  return false;
96  }
97  getConfiguration().setSensorConfiguration(sensorConfiguration);
98  return true;
99 }
100 
102 {
103  if (!slavePtr_->setSensorCalibration(sensorCalibration))
104  {
105  return false;
106  }
107  getConfiguration().setSensorCalibration(sensorCalibration);
108  return true;
109 }
110 
112 {
113  return slavePtr_->setConfigMode();
114 }
115 
117 {
118  return slavePtr_->setRunMode();
119 }
120 
122 {
123  return slavePtr_->saveConfigParameter();
124 }
125 
126 using RokubiminiReadingRos = rokubimini_msgs::Reading;
127 using RokubiminiWrenchRos = geometry_msgs::WrenchStamped;
128 using RokubiminiImuRos = sensor_msgs::Imu;
129 using RokubiminiTemperatureRos = sensor_msgs::Temperature;
131 {
132  readingPublisher_ = std::make_shared<ros::Publisher>(nh_->advertise<RokubiminiReadingRos>(
133  nh_->getNamespace() + "/" + getName() + "/ft_sensor_readings/reading", 10, false));
134 
135  wrenchPublisher_ = std::make_shared<ros::Publisher>(nh_->advertise<RokubiminiWrenchRos>(
136  nh_->getNamespace() + "/" + getName() + "/ft_sensor_readings/wrench", 10, false));
137 
138  imuPublisher_ = std::make_shared<ros::Publisher>(
139  nh_->advertise<RokubiminiImuRos>(nh_->getNamespace() + "/" + getName() + "/ft_sensor_readings/imu", 10, false));
140 
141  temperaturePublisher_ = std::make_shared<ros::Publisher>(nh_->advertise<RokubiminiTemperatureRos>(
142  nh_->getNamespace() + "/" + getName() + "/ft_sensor_readings/temperature", 10, false));
144  std::make_shared<ros::Publisher>(nh_->advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 10, false));
145 }
146 
148 {
149  slavePtr_->setRunsAsync(runsAsync);
150 }
152 {
153  auto reading = getReading();
154  rokubimini_msgs::Reading reading_msg;
155  reading_msg.header.stamp = reading.getWrench().header.stamp;
156  // reading_msg.header.frame_id = reading.getWrench().header.frame_id;
157  reading_msg.statusword = reading.getStatusword().getData();
158  reading_msg.imu = reading.getImu();
159  reading_msg.wrench = reading.getWrench();
160  reading_msg.externalImu = reading.getExternalImu();
161  reading_msg.isForceTorqueSaturated = reading.isForceTorqueSaturated();
162  reading_msg.temperature = reading.getTemperature();
163 
164  // if reset wrench is triggered take the mean of the measurements
166  {
167  std::lock_guard<std::recursive_mutex> lock(meanWrenchOffsetMutex_);
168  std::uint32_t lpos = wrenchMessageCount_;
170  // increase the rows of the dynamic array
171  resetServiceWrenchSamples_.conservativeResize(6, wrenchMessageCount_);
172  // assign new values to the array
173  resetServiceWrenchSamples_(0, lpos) = reading.getWrench().wrench.force.x;
174  resetServiceWrenchSamples_(1, lpos) = reading.getWrench().wrench.force.y;
175  resetServiceWrenchSamples_(2, lpos) = reading.getWrench().wrench.force.z;
176  resetServiceWrenchSamples_(3, lpos) = reading.getWrench().wrench.torque.x;
177  resetServiceWrenchSamples_(4, lpos) = reading.getWrench().wrench.torque.y;
178  resetServiceWrenchSamples_(5, lpos) = reading.getWrench().wrench.torque.z;
179  }
180  readingPublisher_->publish(reading_msg);
181  wrenchPublisher_->publish(reading.getWrench());
182  imuPublisher_->publish(reading.getImu());
183  temperaturePublisher_->publish(reading.getTemperature());
184  // update the data flags to be used by diagnostics
185  slavePtr_->updateDataFlags();
186 }
187 
189 {
190  // wait a small amount of time so that the callback can return the result to the user.
191  std::this_thread::sleep_for(std::chrono::microseconds(500));
192  kill(getpid(), SIGINT);
193 }
194 
196 {
197  slavePtr_->updateConnectionStatus(stat);
198 }
199 
201 {
202  connectionStatusUpdater_ = std::make_shared<diagnostic_updater::Updater>();
203  unsigned int serial_number;
204  getSerialNumber(serial_number);
205  connectionStatusUpdater_->setHardwareID(std::to_string(serial_number));
207  // create the timer for the data flags diagnostics
208  dataFlagsDiagnosticsTimer_ = std::make_shared<ros::Timer>(
210 }
211 
213 {
215 }
216 
218 {
219  connectionStatusUpdater_->update();
220 }
221 
223 {
224  // publish the Data Status Diagnostics
226  slavePtr_->createDataFlagsDiagnostics(stat);
227  // reset the data flags
228  slavePtr_->resetDataFlags();
229  // set the namespace of the diagnostics status
230  stat.name = nh_->getNamespace().substr(1) + ": " + getName() + ": Data Flags";
231  // set the hardware ID
232  unsigned int serial_number;
233  getSerialNumber(serial_number);
234  stat.hardware_id = std::to_string(serial_number);
235  // create the diagnostics array and fill it with the Diagnostics Status message
236  diagnostic_msgs::DiagnosticArray diagnostics_array;
237  diagnostics_array.status.emplace_back(stat);
238  // fill the Header
239  diagnostics_array.header.stamp = ros::Time::now();
240  dataFlagsDiagnosticsPublisher_->publish(diagnostics_array);
241 }
242 
243 bool RokubiminiEthercat::firmwareUpdateCallback(rokubimini_msgs::FirmwareUpdateEthercat::Request& request,
244  rokubimini_msgs::FirmwareUpdateEthercat::Response& response)
245 {
246  response.result = slavePtr_->firmwareUpdate(request.file_path, request.file_name, request.password);
247  if (!slavePtr_->isRunning())
248  {
249  // time to shut down the ROS node.
250  std::thread shutdown_thread(&RokubiminiEthercat::signalShutdown, this);
251  shutdown_thread.detach();
252  }
253  return true;
254 }
255 
256 bool RokubiminiEthercat::resetWrenchCallback(rokubimini_msgs::ResetWrench::Request& request,
257  rokubimini_msgs::ResetWrench::Response& response)
258 {
259  ROS_INFO("[%s] Reseting sensor measurements...", name_.c_str());
260 
261  bool success = false;
262  unsigned int count = 0;
263  Eigen::Matrix<double, 6, 1> new_offset;
264 
265  while (!success and count < 8)
266  {
267  // initialize all variables to zero
269  // enable the computation of the mean wrench
270  computeMeanWrenchFlag_ = true;
271  // wait for computing the mean of wrench measurements
273  ;
274  // disable the computation of the mean wrench
275  computeMeanWrenchFlag_ = false;
276  if (!setConfigMode())
277  {
278  ROS_ERROR("[%s] Device could not switch to config mode", name_.c_str());
279  response.success = false;
280  return true;
281  }
282  geometry_msgs::Wrench wrench;
283  Eigen::Matrix<double, 6, 1> mean_wrench;
284  // lock to get the mean wrench offset value
285  {
286  std::lock_guard<std::recursive_mutex> lock(meanWrenchOffsetMutex_);
287  mean_wrench = resetServiceWrenchSamples_.rowwise().mean();
288  wrench.force.x = mean_wrench(0, 0);
289  wrench.force.y = mean_wrench(1, 0);
290  wrench.force.z = mean_wrench(2, 0);
291  wrench.torque.x = mean_wrench(3, 0);
292  wrench.torque.y = mean_wrench(4, 0);
293  wrench.torque.z = mean_wrench(5, 0);
294  }
295  geometry_msgs::Wrench desired_wrench = request.desired_wrench;
296  auto current_offset = configuration_.getForceTorqueOffset();
297  // new offset = current wrench measurements + current offset - desired offset
298  new_offset(0, 0) = desired_wrench.force.x - wrench.force.x + current_offset(0, 0);
299  new_offset(1, 0) = desired_wrench.force.y - wrench.force.y + current_offset(1, 0);
300  new_offset(2, 0) = desired_wrench.force.z - wrench.force.z + current_offset(2, 0);
301  new_offset(3, 0) = desired_wrench.torque.x - wrench.torque.x + current_offset(3, 0);
302  new_offset(4, 0) = desired_wrench.torque.y - wrench.torque.y + current_offset(4, 0);
303  new_offset(5, 0) = desired_wrench.torque.z - wrench.torque.z + current_offset(5, 0);
304  ROS_DEBUG_STREAM("[" << getName() << "] "
305  << "New offset is: " << new_offset);
306  if (!setForceTorqueOffset(new_offset))
307  {
308  ROS_ERROR("[%s] Could not write new offset to device", name_.c_str());
309  response.success = false;
310  return true;
311  }
312  if (!setRunMode())
313  {
314  ROS_ERROR("[%s] Device could not switch to run mode", name_.c_str());
315  response.success = false;
316  return true;
317  }
319 
320  // initialize all variables to zero
322  // enable the computation of the mean wrench
323  computeMeanWrenchFlag_ = true;
324  // wait for computing the mean of wrench measurements
326  ;
327  // disable the computation of the mean wrench
328  computeMeanWrenchFlag_ = false;
329 
330  // lock to get the mean wrench offset value
331  {
332  std::lock_guard<std::recursive_mutex> lock(meanWrenchOffsetMutex_);
333  mean_wrench = resetServiceWrenchSamples_.rowwise().mean();
334  }
335  success = true;
336  Eigen::Vector3d forceError;
337  forceError << mean_wrench(0, 0) - desired_wrench.force.x, mean_wrench(1, 0) - desired_wrench.force.y,
338  mean_wrench(2, 0) - desired_wrench.force.z;
339  if (forceError.norm() > 0.2)
340  {
341  ROS_DEBUG_STREAM("Could not reset wrench. Force error" << forceError);
342  success = false;
343  }
344 
345  Eigen::Vector3d torqueError;
346  torqueError << mean_wrench(3, 0) - desired_wrench.torque.x, mean_wrench(4, 0) - desired_wrench.torque.y,
347  mean_wrench(5, 0) - desired_wrench.torque.z;
348  if (torqueError.norm() > 0.01)
349  {
350  ROS_DEBUG_STREAM("Could not reset wrench. Torque error" << torqueError);
351  success = false;
352  }
353  count++;
354  }
355 
356  response.success = success;
357  ROS_INFO("[%s] Sensor measurements are reset successfully", name_.c_str());
358  return true;
359 }
361 {
362  firmwareUpdateService_ = nh_->advertiseService(nh_->getNamespace() + "/" + getName() + "/firmware_update",
364  resetWrenchService_ = nh_->advertiseService(nh_->getNamespace() + "/" + getName() + "/reset_wrench",
366 }
367 bool RokubiminiEthercat::sendSdoReadGeneric(const std::string& indexString, const std::string& subindexString,
368  const std::string& valueTypeString, std::string& valueString)
369 {
370  return slavePtr_->sendSdoReadGeneric(indexString, subindexString, valueTypeString, valueString);
371 }
372 
373 bool RokubiminiEthercat::sendSdoWriteGeneric(const std::string& indexString, const std::string& subindexString,
374  const std::string& valueTypeString, const std::string& valueString)
375 {
376  return slavePtr_->sendSdoWriteGeneric(indexString, subindexString, valueTypeString, valueString);
377 }
378 
379 template <>
380 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
381  int8_t& value)
382 {
383  return slavePtr_->sendSdoReadInt8(index, subindex, completeAccess, value);
384 }
385 
386 template <>
387 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
388  int16_t& value)
389 {
390  return slavePtr_->sendSdoReadInt16(index, subindex, completeAccess, value);
391 }
392 
393 template <>
394 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
395  int32_t& value)
396 {
397  return slavePtr_->sendSdoReadInt32(index, subindex, completeAccess, value);
398 }
399 
400 template <>
401 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
402  int64_t& value)
403 {
404  return slavePtr_->sendSdoReadInt64(index, subindex, completeAccess, value);
405 }
406 
407 template <>
408 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
409  uint8_t& value)
410 {
411  return slavePtr_->sendSdoReadUInt8(index, subindex, completeAccess, value);
412 }
413 
414 template <>
415 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
416  uint16_t& value)
417 {
418  return slavePtr_->sendSdoReadUInt16(index, subindex, completeAccess, value);
419 }
420 
421 template <>
422 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
423  uint32_t& value)
424 {
425  return slavePtr_->sendSdoReadUInt32(index, subindex, completeAccess, value);
426 }
427 
428 template <>
429 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
430  uint64_t& value)
431 {
432  return slavePtr_->sendSdoReadUInt64(index, subindex, completeAccess, value);
433 }
434 
435 template <>
436 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
437  float& value)
438 {
439  return slavePtr_->sendSdoReadFloat(index, subindex, completeAccess, value);
440 }
441 
442 template <>
443 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
444  double& value)
445 {
446  return slavePtr_->sendSdoReadDouble(index, subindex, completeAccess, value);
447 }
448 
449 template <>
450 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
451  const int8_t value)
452 {
453  return slavePtr_->sendSdoWriteInt8(index, subindex, completeAccess, value);
454 }
455 
456 template <>
457 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
458  const int16_t value)
459 {
460  return slavePtr_->sendSdoWriteInt16(index, subindex, completeAccess, value);
461 }
462 
463 template <>
464 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
465  const int32_t value)
466 {
467  return slavePtr_->sendSdoWriteInt32(index, subindex, completeAccess, value);
468 }
469 
470 template <>
471 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
472  const int64_t value)
473 {
474  return slavePtr_->sendSdoWriteInt64(index, subindex, completeAccess, value);
475 }
476 
477 template <>
478 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
479  const uint8_t value)
480 {
481  return slavePtr_->sendSdoWriteUInt8(index, subindex, completeAccess, value);
482 }
483 
484 template <>
485 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
486  const uint16_t value)
487 {
488  return slavePtr_->sendSdoWriteUInt16(index, subindex, completeAccess, value);
489 }
490 
491 template <>
492 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
493  const uint32_t value)
494 {
495  return slavePtr_->sendSdoWriteUInt32(index, subindex, completeAccess, value);
496 }
497 
498 template <>
499 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
500  const uint64_t value)
501 {
502  return slavePtr_->sendSdoWriteUInt64(index, subindex, completeAccess, value);
503 }
504 
505 template <>
506 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
507  const float value)
508 {
509  return slavePtr_->sendSdoWriteFloat(index, subindex, completeAccess, value);
510 }
511 
512 template <>
513 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
514  const double value)
515 {
516  return slavePtr_->sendSdoWriteDouble(index, subindex, completeAccess, value);
517 }
518 
519 } // namespace ethercat
520 } // namespace rokubimini
response
const std::string response
rokubimini::ethercat::RokubiminiEthercat::setAngularRateRange
bool setAngularRateRange(const unsigned int range) override
Sets an angular rate range to the device.
Definition: RokubiminiEthercat.cpp:81
rokubimini::ethercat::RokubiminiEthercat::firmwareUpdateService_
ros::ServiceServer firmwareUpdateService_
The service for firmware updates.
Definition: RokubiminiEthercat.hpp:529
uint8_t
unsigned char uint8_t
int8_t
signed char int8_t
rokubimini::ethercat::RokubiminiTemperatureRos
sensor_msgs::Temperature RokubiminiTemperatureRos
Definition: RokubiminiEthercat.cpp:129
rokubimini::ethercat::RokubiminiEthercat::sendSdoRead
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
rokubimini::ethercat::RokubiminiEthercat::shutdownWithCommunication
void shutdownWithCommunication() override
Shuts down a Rokubimini Ethercat device before communication has been closed.
Definition: RokubiminiEthercat.cpp:39
rokubimini::ethercat::RokubiminiEthercat::signalShutdown
void signalShutdown()
Signals shutdown for the ROS node. It's used if a firmware update was successful.
Definition: RokubiminiEthercat.cpp:188
rokubimini::ethercat::RokubiminiEthercat::setForceTorqueOffset
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) override
Sets a force torque offset to the device.
Definition: RokubiminiEthercat.cpp:86
rokubimini::Rokubimini::statuswordRequested_
std::atomic< bool > statuswordRequested_
rokubimini::ethercat::RokubiminiImuRos
sensor_msgs::Imu RokubiminiImuRos
Definition: RokubiminiEthercat.cpp:128
rokubimini::Rokubimini::dataFlagsDiagnosticsPublisher_
RosPublisherPtr dataFlagsDiagnosticsPublisher_
rokubimini::ethercat::RokubiminiEthercat::preSetupConfiguration
void preSetupConfiguration() override
Pre-setup configuration hook.
Definition: RokubiminiEthercat.cpp:15
rokubimini::ethercat::RokubiminiEthercat::resetServiceWrenchSamples_
Eigen::Matrix< double, 6, Eigen::Dynamic > resetServiceWrenchSamples_
The wrench samples used by the "reset service" callback for calculating the mean wrench offset.
Definition: RokubiminiEthercat.hpp:580
uint16_t
unsigned short uint16_t
rokubimini::ethercat::RokubiminiEthercat::setAngularRateFilter
bool setAngularRateFilter(const unsigned int filter) override
Sets an angular rate filter to the device.
Definition: RokubiminiEthercat.cpp:71
rokubimini::Rokubimini::getConfiguration
configuration::Configuration & getConfiguration()
rokubimini::ethercat::RokubiminiEthercat::postSetupConfiguration
void postSetupConfiguration() override
Post-setup configuration hook.
Definition: RokubiminiEthercat.cpp:12
rokubimini::ethercat::RokubiminiEthercat::sendSdoReadGeneric
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.
Definition: RokubiminiEthercat.cpp:367
rokubimini::ethercat::RokubiminiEthercat::wrenchMessageCount_
std::atomic< uint32_t > wrenchMessageCount_
The counter that is used for the computation of the mean of the wrench measurements....
Definition: RokubiminiEthercat.hpp:555
rokubimini::ethercat::RokubiminiEthercat::getForceTorqueSamplingRate
bool getForceTorqueSamplingRate(int &samplingRate) override
Gets the force torque sampling rate of the device.
Definition: RokubiminiEthercat.cpp:56
rokubimini::ethercat::RokubiminiEthercat::publishRosMessages
void publishRosMessages() override
Publishes ROS messages with data from the rokubimini device.
Definition: RokubiminiEthercat.cpp:151
rokubimini::Rokubimini::reading_
Reading reading_
rokubimini::ethercat::RokubiminiEthercat::getSerialNumber
bool getSerialNumber(unsigned int &samplingRate) override
Gets the serial number of the device.
Definition: RokubiminiEthercat.cpp:51
rokubimini::ethercat::RokubiminiEthercat::publishDataFlagsDiagnostics
void publishDataFlagsDiagnostics(const ros::TimerEvent &event)
Publishes the Data Flags Diagnostics to the "/diagnostics" topic.
Definition: RokubiminiEthercat.cpp:222
rokubimini::Rokubimini::getName
std::string getName() const
rokubimini::ethercat::RokubiminiEthercat::saveConfigParameter
bool saveConfigParameter() override
Saves the current configuration to the device.
Definition: RokubiminiEthercat.cpp:121
rokubimini::Rokubimini::dataFlagsDiagnosticsTimer_
TimerPtr dataFlagsDiagnosticsTimer_
rokubimini::ethercat::RokubiminiEthercat::setForceTorqueFilter
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter) override
Sets a force torque filter to the device.
Definition: RokubiminiEthercat.cpp:61
rokubimini::Rokubimini::getReading
Reading getReading() const
rokubimini::ethercat::RokubiminiEthercat::temperaturePublisher_
RosPublisherPtr temperaturePublisher_
The sensor_msgs::Temperature publisher.
Definition: RokubiminiEthercat.hpp:521
rokubimini::configuration::Configuration::setSensorConfiguration
void setSensorConfiguration(const SensorConfiguration &sensorConfiguration)
rokubimini::Reading::getStatusword
const Statusword & getStatusword() const
rokubimini::ethercat::RokubiminiEthercat::setRunMode
bool setRunMode()
Sets the device in run mode.
Definition: RokubiminiEthercat.cpp:116
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
rokubimini::ethercat::RokubiminiEthercat::sendSdoWrite
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
int16_t
signed short int16_t
rokubimini::ethercat::RokubiminiEthercat::updateConnectionStatus
void updateConnectionStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Shows the Device Status of the rokubimini.
Definition: RokubiminiEthercat.cpp:195
rokubimini::ethercat::RokubiminiEthercat::firmwareUpdateCallback
bool firmwareUpdateCallback(rokubimini_msgs::FirmwareUpdateEthercat::Request &request, rokubimini_msgs::FirmwareUpdateEthercat::Response &response)
The callback for the firmware update ROS service.
Definition: RokubiminiEthercat.cpp:243
uint32_t
unsigned int uint32_t
rokubimini::Rokubimini::name_
std::string name_
rokubimini::ethercat::RokubiminiEthercat::setConfigMode
bool setConfigMode()
Sets the device in config mode.
Definition: RokubiminiEthercat.cpp:111
rokubimini::configuration::ForceTorqueFilter
rokubimini::ethercat::RokubiminiEthercat::readingPublisher_
RosPublisherPtr readingPublisher_
The rokubimini_msgs::Reading publisher.
Definition: RokubiminiEthercat.hpp:497
rokubimini::ethercat::RokubiminiEthercat::setSensorCalibration
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration) override
Sets a sensor calibration to the device.
Definition: RokubiminiEthercat.cpp:101
uint64_t
unsigned __int64 uint64_t
rokubimini::configuration::Configuration::getForceTorqueOffset
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
rokubimini::ethercat::RokubiminiEthercat::setSensorConfiguration
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration) override
Sets a sensor configuration to the device.
Definition: RokubiminiEthercat.cpp:91
rokubimini::ethercat::RokubiminiEthercat::TOTAL_NUMBER_OF_WRENCH_MESSAGES
const static uint32_t TOTAL_NUMBER_OF_WRENCH_MESSAGES
Definition: RokubiminiEthercat.hpp:572
rokubimini::ethercat::RokubiminiEthercat::setAccelerationFilter
bool setAccelerationFilter(const unsigned int filter) override
Sets an acceleration filter to the device.
Definition: RokubiminiEthercat.cpp:66
rokubimini::ethercat::RokubiminiEthercat::updateProcessReading
void updateProcessReading() override
Updates the RokubiminiEthercat object with new measurements.
Definition: RokubiminiEthercat.cpp:20
rokubimini::ethercat::RokubiminiWrenchRos
geometry_msgs::WrenchStamped RokubiminiWrenchRos
Definition: RokubiminiEthercat.cpp:127
rokubimini::configuration::Configuration::setSensorCalibration
void setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
rokubimini
DiagnosticStatusWrapper.h
rokubimini::ethercat::RokubiminiEthercat::meanWrenchOffsetMutex_
std::recursive_mutex meanWrenchOffsetMutex_
The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback.
Definition: RokubiminiEthercat.hpp:563
rokubimini::ethercat::RokubiminiEthercat::resetWrenchCallback
bool resetWrenchCallback(rokubimini_msgs::ResetWrench::Request &request, rokubimini_msgs::ResetWrench::Response &response)
The callback for the reset wrench ROS service.
Definition: RokubiminiEthercat.cpp:256
ros::TimerEvent
rokubimini::ethercat::RokubiminiEthercat::publishRosDiagnostics
void publishRosDiagnostics() override
Publish ROS diagnostics related to the operation of rokubimini.
Definition: RokubiminiEthercat.cpp:212
rokubimini::ethercat::RokubiminiEthercat::imuPublisher_
RosPublisherPtr imuPublisher_
The sensor_msgs::Imu publisher.
Definition: RokubiminiEthercat.hpp:513
rokubimini::ethercat::RokubiminiEthercat::publishConnectionStatusDiagnostics
void publishConnectionStatusDiagnostics()
Publishes the Connection Status Diagnostics to the "/diagnostics" topic.
Definition: RokubiminiEthercat.cpp:217
rokubimini::Rokubimini::connectionStatusUpdater_
DiagnosticsUpdaterPtr connectionStatusUpdater_
int64_t
signed __int64 int64_t
rokubimini::Rokubimini::nh_
NodeHandlePtr nh_
rokubimini::ethercat::RokubiminiEthercat::resetWrenchService_
ros::ServiceServer resetWrenchService_
The service for resetting the sensor wrench measurements.
Definition: RokubiminiEthercat.hpp:537
rokubimini::ethercat::RokubiminiEthercat::computeMeanWrenchFlag_
std::atomic< bool > computeMeanWrenchFlag_
The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset...
Definition: RokubiminiEthercat.hpp:546
rokubimini::ethercat::RokubiminiEthercat::wrenchPublisher_
RosPublisherPtr wrenchPublisher_
The sensor_msgs::Wrench publisher.
Definition: RokubiminiEthercat.hpp:505
int32_t
signed int int32_t
rokubimini::Rokubimini::setStatusword
void setStatusword(Statusword &statusword)
rokubimini::ethercat::RokubiminiEthercat::deviceIsMissing
bool deviceIsMissing() const override
Checks if the device is missing.
Definition: RokubiminiEthercat.cpp:46
ROS_ERROR
#define ROS_ERROR(...)
rokubimini::ethercat::RokubiminiEthercat::createRosPublishers
void createRosPublishers() override
Adds ROS publishers related to the device.
Definition: RokubiminiEthercat.cpp:130
diagnostic_updater::DiagnosticStatusWrapper
rokubimini::ethercat::RokubiminiEthercat::createRosServices
void createRosServices() override
Adds ROS services related to the device.
Definition: RokubiminiEthercat.cpp:360
rokubimini::ethercat::RokubiminiEthercat::slavePtr_
RokubiminiEthercatSlavePtr slavePtr_
The pointer to implementation.
Definition: RokubiminiEthercat.hpp:486
rokubimini::configuration::SensorConfiguration
rokubimini::Rokubimini::configuration_
configuration::Configuration configuration_
rokubimini::calibration::SensorCalibration
rokubimini::Rokubimini::readingMutex_
std::recursive_mutex readingMutex_
rokubimini::ethercat::RokubiminiEthercat::sendSdoWriteGeneric
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.
Definition: RokubiminiEthercat.cpp:373
rokubimini::ethercat::RokubiminiReadingRos
rokubimini_msgs::Reading RokubiminiReadingRos
Definition: RokubiminiEthercat.cpp:126
rokubimini::configuration::Configuration::setForceTorqueOffset
void setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
ROS_INFO
#define ROS_INFO(...)
rokubimini::ethercat::RokubiminiEthercat::setRunsAsync
void setRunsAsync(bool runsAsync)
Definition: RokubiminiEthercat.cpp:147
rokubimini::ethercat::RokubiminiEthercat::createRosDiagnostics
void createRosDiagnostics() override
Adds ROS diagnostics related to the operation of rokubimini.
Definition: RokubiminiEthercat.cpp:200
ros::Duration
rokubimini::Statusword
RokubiminiEthercat.hpp
rokubimini::ethercat::RokubiminiEthercat::setAccelerationRange
bool setAccelerationRange(const unsigned int range) override
Sets an acceleration range to the device.
Definition: RokubiminiEthercat.cpp:76
ros::Time::now
static Time now()


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