sdh.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 // ##################
19 // #### includes ####
20 // standard includes
21 #include <unistd.h>
22 #include <map>
23 #include <string>
24 #include <vector>
25 
26 // ROS includes
27 #include <ros/ros.h>
28 #include <urdf/model.h>
30 
31 // ROS message includes
32 #include <std_msgs/Float64MultiArray.h>
33 #include <trajectory_msgs/JointTrajectory.h>
34 #include <sensor_msgs/JointState.h>
35 #include <control_msgs/FollowJointTrajectoryAction.h>
36 #include <control_msgs/JointTrajectoryControllerState.h>
37 #include <schunk_sdh/TactileSensor.h>
38 #include <schunk_sdh/TactileMatrix.h>
39 #include <schunk_sdh/TemperatureArray.h>
40 #include <schunk_sdh/PressureArrayList.h>
41 
42 // ROS service includes
43 #include <std_srvs/Trigger.h>
44 #include <cob_srvs/SetString.h>
45 
46 // ROS diagnostic msgs
47 #include <diagnostic_msgs/DiagnosticArray.h>
48 
49 // external includes
50 #include <schunk_sdh/sdh.h>
51 #include <schunk_sdh/dsa.h>
52 
58 class SdhNode
59 {
60 public:
63 private:
64  // declaration of topics to publish
71 
72  // topic subscribers
74 
75  // service servers
84 
85  // actionlib server
87  std::string action_name_;
88 
89  // service clients
90  // --
91 
92  // other variables
93  SDH::cSDH *sdh_;
94  SDH::cDSA *dsa_;
95  std::vector<SDH::cSDH::eAxisState> state_;
96 
97  std::string sdhdevicetype_;
98  std::string sdhdevicestring_;
100  std::string dsadevicestring_;
107  double timeout_;
108 
111  bool isError_;
112  int DOF_;
113  double pi_;
114 
115  trajectory_msgs::JointTrajectory traj_;
116 
117  std::vector<std::string> joint_names_;
118  std::vector<int> axes_;
119  std::vector<double> targetAngles_; // in degrees
120  std::vector<double> velocities_; // in rad/s
122  std::string operationMode_;
123 
124  static const std::vector<std::string> temperature_names_;
125  static const std::vector<std::string> finger_names_;
126 
127 public:
133  SdhNode(std::string name) :
134  as_(nh_, name, boost::bind(&SdhNode::executeCB, this, _1), true), action_name_(name)
135  {
136  pi_ = 3.1415926;
137 
138  nh_ = ros::NodeHandle("~");
139  isError_ = false;
140  // diagnostics
141  topicPub_Diagnostics_ = nh_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
142  }
143 
148  {
149  if (isDSAInitialized_)
150  dsa_->Close();
151  if (isInitialized_)
152  sdh_->Close();
153  delete sdh_;
154  }
155 
159  bool init()
160  {
161  // initialize member variables
162  isInitialized_ = false;
163  isDSAInitialized_ = false;
164  hasNewGoal_ = false;
165 
166  // implementation of topics to publish
167  topicPub_JointState_ = nh_.advertise<sensor_msgs::JointState>("joint_states", 1);
168  topicPub_ControllerState_ = nh_.advertise<control_msgs::JointTrajectoryControllerState>(
169  "joint_trajectory_controller/state", 1);
170  topicPub_TactileSensor_ = nh_.advertise<schunk_sdh::TactileSensor>("tactile_data", 1);
171  topicPub_Temperature_ = nh_.advertise<schunk_sdh::TemperatureArray>("temperature", 1);
172  topicPub_Pressure_ = nh_.advertise<schunk_sdh::PressureArrayList>("pressure", 1);
173 
174  // pointer to sdh
175  sdh_ = new SDH::cSDH(false, false, 0); // (_use_radians=false, bool _use_fahrenheit=false, int _debug_level=0)
176 
177  // implementation of service servers
178  srvServer_Init_ = nh_.advertiseService("init", &SdhNode::srvCallback_Init, this);
179  srvServer_Stop_ = nh_.advertiseService("stop", &SdhNode::srvCallback_Stop, this);
180  srvServer_Recover_ = nh_.advertiseService("recover", &SdhNode::srvCallback_Init, this); // HACK: There is no recover implemented yet, so we execute a init
181  srvServer_SetOperationMode_ = nh_.advertiseService("set_operation_mode", &SdhNode::srvCallback_SetOperationMode,
182  this);
183  srvServer_EmergencyStop_ = nh_.advertiseService("emergency_stop", &SdhNode::srvCallback_EmergencyStop, this);
184  srvServer_Disconnect_ = nh_.advertiseService("shutdown", &SdhNode::srvCallback_Disconnect, this);
185 
186  srvServer_MotorOn_ = nh_.advertiseService("motor_on", &SdhNode::srvCallback_MotorPowerOn, this);
187  srvServer_MotorOff_ = nh_.advertiseService("motor_off", &SdhNode::srvCallback_MotorPowerOff, this);
188 
189  subSetVelocitiesRaw_ = nh_.subscribe("joint_group_velocity_controller/command", 1,
191 
192  // getting hardware parameters from parameter server
193  nh_.param("sdhdevicetype", sdhdevicetype_, std::string("PCAN"));
194  nh_.param("sdhdevicestring", sdhdevicestring_, std::string("/dev/pcan0"));
195  nh_.param("sdhdevicenum", sdhdevicenum_, 0);
196 
197  nh_.param("dsadevicestring", dsadevicestring_, std::string(""));
198  nh_.param("dsadevicenum", dsadevicenum_, 0);
199  nh_.param("dsa_dbg_level", dsa_dbg_level_, 0);
200  nh_.param("dsa_sensitivity", dsa_sensitivity_, 0.5);
201  nh_.param("dsa_calib_pressure", dsa_calib_pressure_, 0.000473); // unit: N/(mm*mm)
202  nh_.param("dsa_calib_voltage", dsa_calib_voltage_, 592.1); // unit: mV
203 
204  nh_.param("baudrate", baudrate_, 1000000);
205  nh_.param("timeout", timeout_, static_cast<double>(0.04));
206  nh_.param("id_read", id_read_, 43);
207  nh_.param("id_write", id_write_, 42);
208 
209  // get joint_names from parameter server
210  ROS_INFO("getting joint_names from parameter server");
211  XmlRpc::XmlRpcValue joint_names_param;
212  if (nh_.hasParam("joint_names"))
213  {
214  nh_.getParam("joint_names", joint_names_param);
215  }
216  else
217  {
218  ROS_ERROR("Parameter joint_names not set, shutting down node...");
219  nh_.shutdown();
220  return false;
221  }
222  DOF_ = joint_names_param.size();
223  joint_names_.resize(DOF_);
224  for (int i = 0; i < DOF_; i++)
225  {
226  joint_names_[i] = (std::string)joint_names_param[i];
227  }
228  std::cout << "joint_names = " << joint_names_param << std::endl;
229 
230  // define axes to send to sdh
231  axes_.resize(DOF_);
232  velocities_.resize(DOF_);
233  for (int i = 0; i < DOF_; i++)
234  {
235  axes_[i] = i;
236  }
237  ROS_INFO("DOF = %d", DOF_);
238 
239  state_.resize(axes_.size());
240 
241  nh_.param("OperationMode", operationMode_, std::string("position"));
242  return true;
243  }
249  bool switchOperationMode(const std::string &mode)
250  {
251  hasNewGoal_ = false;
252  sdh_->Stop();
253 
254  try
255  {
256  if (mode == "position")
257  {
258  sdh_->SetController(SDH::cSDH::eCT_POSE);
259  }
260  else if (mode == "velocity")
261  {
262  sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
263  }
264  else
265  {
266  ROS_ERROR_STREAM("Operation mode '" << mode << "' not supported");
267  return false;
268  }
269  sdh_->SetAxisEnable(sdh_->All, 1.0); // TODO: check if necessary
270  }
271  catch (SDH::cSDHLibraryException* e)
272  {
273  ROS_ERROR("An exception was caught: %s", e->what());
274  delete e;
275  return false;
276  }
277 
278  operationMode_ = mode;
279  return true;
280  }
281 
288  void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
289  {
290  ROS_INFO("sdh: executeCB");
291  if (operationMode_ != "position")
292  {
293  ROS_ERROR("%s: Rejected, sdh not in position mode", action_name_.c_str());
294  as_.setAborted();
295  return;
296  }
297  if (!isInitialized_)
298  {
299  ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
300  as_.setAborted();
301  return;
302  }
303 
304  if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() != size_t(DOF_))
305  {
306  ROS_ERROR("%s: Rejected, malformed FollowJointTrajectoryGoal", action_name_.c_str());
307  as_.setAborted();
308  return;
309  }
310  while (hasNewGoal_ == true)
311  usleep(10000);
312 
313  std::map<std::string, int> dict;
314  for (int idx = 0; idx < goal->trajectory.joint_names.size(); idx++)
315  {
316  dict[goal->trajectory.joint_names[idx]] = idx;
317  }
318 
319  targetAngles_.resize(DOF_);
320  targetAngles_[0] = goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]] * 180.0 / pi_; // sdh_knuckle_joint
321  targetAngles_[1] = goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]] * 180.0 / pi_; // sdh_finger22_joint
322  targetAngles_[2] = goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]] * 180.0 / pi_; // sdh_finger23_joint
323  targetAngles_[3] = goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]] * 180.0 / pi_; // sdh_thumb2_joint
324  targetAngles_[4] = goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]] * 180.0 / pi_; // sdh_thumb3_joint
325  targetAngles_[5] = goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]] * 180.0 / pi_; // sdh_finger12_joint
326  targetAngles_[6] = goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]] * 180.0 / pi_; // sdh_finger13_joint
327  ROS_INFO(
328  "received position goal: [['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']] = [%f,%f,%f,%f,%f,%f,%f]",
329  goal->trajectory.points[0].positions[dict["sdh_knuckle_joint"]],
330  goal->trajectory.points[0].positions[dict["sdh_thumb_2_joint"]],
331  goal->trajectory.points[0].positions[dict["sdh_thumb_3_joint"]],
332  goal->trajectory.points[0].positions[dict["sdh_finger_12_joint"]],
333  goal->trajectory.points[0].positions[dict["sdh_finger_13_joint"]],
334  goal->trajectory.points[0].positions[dict["sdh_finger_22_joint"]],
335  goal->trajectory.points[0].positions[dict["sdh_finger_23_joint"]]);
336 
337  hasNewGoal_ = true;
338 
339  usleep(500000); // needed sleep until sdh starts to change status from idle to moving
340 
341  bool finished = false;
342  while (finished == false)
343  {
344  if (as_.isNewGoalAvailable())
345  {
346  ROS_WARN("%s: Aborted", action_name_.c_str());
347  as_.setAborted();
348  return;
349  }
350  for (unsigned int i = 0; i < state_.size(); i++)
351  {
352  ROS_DEBUG("state[%d] = %d", i, state_[i]);
353  if (state_[i] == 0)
354  {
355  finished = true;
356  }
357  else
358  {
359  finished = false;
360  }
361  }
362  usleep(10000);
363  // feedback_ =
364  // as_.send feedback_
365  }
366 
367  // set the action state to succeeded
368  ROS_INFO("%s: Succeeded", action_name_.c_str());
369  // result_.result.data = "succesfully received new goal";
370  // result_.success = 1;
371  // as_.setSucceeded(result_);
372  as_.setSucceeded();
373  }
374 
375  void topicCallback_setVelocitiesRaw(const std_msgs::Float64MultiArrayPtr& velocities)
376  {
377  if (!isInitialized_)
378  {
379  ROS_ERROR("%s: Rejected, sdh not initialized", action_name_.c_str());
380  return;
381  }
382  if (velocities->data.size() != velocities_.size())
383  {
384  ROS_ERROR("Velocity array dimension mismatch");
385  return;
386  }
387  if (operationMode_ != "velocity")
388  {
389  ROS_ERROR("%s: Rejected, sdh not in velocity mode", action_name_.c_str());
390  return;
391  }
392 
393  // TODO: write proper lock!
394  while (hasNewGoal_ == true)
395  usleep(10000);
396 
397  velocities_[0] = velocities->data[0] * 180.0 / pi_; // sdh_knuckle_joint
398  velocities_[1] = velocities->data[5] * 180.0 / pi_; // sdh_finger22_joint
399  velocities_[2] = velocities->data[6] * 180.0 / pi_; // sdh_finger23_joint
400  velocities_[3] = velocities->data[1] * 180.0 / pi_; // sdh_thumb2_joint
401  velocities_[4] = velocities->data[2] * 180.0 / pi_; // sdh_thumb3_joint
402  velocities_[5] = velocities->data[3] * 180.0 / pi_; // sdh_finger12_joint
403  velocities_[6] = velocities->data[4] * 180.0 / pi_; // sdh_finger13_joint
404 
405  hasNewGoal_ = true;
406  }
407 
415  bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
416  {
417  if (isInitialized_ == false)
418  {
419  // Init Hand connection
420 
421  try
422  {
423  if (sdhdevicetype_.compare("RS232") == 0)
424  {
425  sdh_->OpenRS232(sdhdevicenum_, 115200, 1, sdhdevicestring_.c_str());
426  ROS_INFO("Initialized RS232 for SDH");
427  isInitialized_ = true;
428  }
429  else if (sdhdevicetype_.compare("PCAN") == 0)
430  {
431  ROS_INFO("Starting initializing PEAKCAN");
432  sdh_->OpenCAN_PEAK(baudrate_, timeout_, id_read_, id_write_, sdhdevicestring_.c_str());
433  ROS_INFO("Initialized PEAK CAN for SDH");
434  isInitialized_ = true;
435  }
436  else if (sdhdevicetype_.compare("ESD") == 0)
437  {
438  ROS_INFO("Starting initializing ESD");
439  if (strcmp(sdhdevicestring_.c_str(), "/dev/can0") == 0)
440  {
441  ROS_INFO("Initializing ESD on device %s", sdhdevicestring_.c_str());
442  sdh_->OpenCAN_ESD(0, baudrate_, timeout_, id_read_, id_write_);
443  }
444  else if (strcmp(sdhdevicestring_.c_str(), "/dev/can1") == 0)
445  {
446  ROS_INFO("Initializin ESD on device %s", sdhdevicestring_.c_str());
447  sdh_->OpenCAN_ESD(1, baudrate_, timeout_, id_read_, id_write_);
448  }
449  else
450  {
451  ROS_ERROR("Currently only support for /dev/can0 and /dev/can1");
452  res.success = false;
453  res.message = "Currently only support for /dev/can0 and /dev/can1";
454  return true;
455  }
456  ROS_INFO("Initialized ESDCAN for SDH");
457  isInitialized_ = true;
458  }
459  else
460  {
461  ROS_ERROR("Unknown SDH device type: %s", sdhdevicetype_.c_str());
462  res.success = false;
463  res.message = "Unknown SDH device type: " + sdhdevicetype_;
464  }
465  }
466  catch (SDH::cSDHLibraryException* e)
467  {
468  ROS_ERROR("An exception was caught: %s", e->what());
469  res.success = false;
470  res.message = e->what();
471  delete e;
472  return true;
473  }
474 
475  // Init tactile data
476  if (!dsadevicestring_.empty())
477  {
478  try
479  {
480  dsa_ = new SDH::cDSA(dsa_dbg_level_, dsadevicenum_, dsadevicestring_.c_str());
481  // dsa_->SetFramerate( 0, true, false );
482  dsa_->SetFramerate(1, true);
483  ROS_INFO("Initialized RS232 for DSA Tactile Sensors on device %s", dsadevicestring_.c_str());
484  for(int imat=0; imat<dsa_->GetSensorInfo().nb_matrices; imat++) {
485  dsa_->SetMatrixSensitivity(imat, dsa_sensitivity_);
486  }
487  isDSAInitialized_ = true;
488  }
489  catch (SDH::cSDHLibraryException* e)
490  {
491  isDSAInitialized_ = false;
492  ROS_ERROR("An exception was caught: %s", e->what());
493  res.success = false;
494  res.message = e->what();
495  delete e;
496  return true;
497  }
498  }
499  if (!switchOperationMode(operationMode_))
500  {
501  res.success = false;
502  res.message = "Could not set operation mode to '" + operationMode_ + "'";
503  return true;
504  }
505  }
506  else
507  {
508  ROS_WARN("...sdh already initialized...");
509  res.success = true;
510  res.message = "sdh already initialized";
511  }
512 
513  res.success = true;
514  res.message = "SDH initialised";
515  return true;
516  }
517 
525  bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
526  {
527  ROS_INFO("Stopping sdh");
528 
529  // stopping all arm movements
530  try
531  {
532  sdh_->Stop();
533  }
534  catch (SDH::cSDHLibraryException* e)
535  {
536  ROS_ERROR("An exception was caught: %s", e->what());
537  delete e;
538  }
539 
540  ROS_INFO("Stopping sdh succesfull");
541  res.success = true;
542  res.message = "stopped SDH";
543  return true;
544  }
545 
553  bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
554  {
555  hasNewGoal_ = false;
556  sdh_->Stop();
557  ROS_INFO("Set operation mode to [%s]", req.data.c_str());
558  operationMode_ = req.data;
559  res.success = true;
560  res.message = "Set operation mode to "+req.data;
561  if (operationMode_ == "position")
562  {
563  sdh_->SetController(SDH::cSDH::eCT_POSE);
564  }
565  else if (operationMode_ == "velocity")
566  {
567  try
568  {
569  sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
570  sdh_->SetAxisEnable(sdh_->All, 1.0);
571  }
572  catch (SDH::cSDHLibraryException* e)
573  {
574  ROS_ERROR("An exception was caught: %s", e->what());
575  delete e;
576  }
577  }
578  else
579  {
580  ROS_ERROR_STREAM("Operation mode '" << req.data << "' not supported");
581  }
582  return true;
583  }
584 
592  bool srvCallback_EmergencyStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {
593  try {
594  isInitialized_ = false;
595  sdh_->EmergencyStop();
596  sdh_->SetAxisEnable(sdh_->All, 0.0);
597  sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
598  }
599  catch(const SDH::cSDHLibraryException* e) {
600  ROS_ERROR("An exception was caught: %s", e->what());
601  res.success = false;
602  res.message = e->what();
603  return true;
604  }
605 
606  res.success = true;
607  res.message = "EMERGENCY stop";
608  return true;
609  }
610 
618  bool srvCallback_Disconnect(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {
619  try {
620  isInitialized_ = false;
621  isDSAInitialized_ = false;
622 
623  sdh_->SetAxisEnable(sdh_->All, 0.0);
624  sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
625 
626  sdh_->Close();
627  dsa_->Close();
628  }
629  catch(const SDH::cSDHLibraryException* e) {
630  ROS_ERROR("An exception was caught: %s", e->what());
631  res.success = false;
632  res.message = e->what();
633  return true;
634  }
635 
636  ROS_INFO("Disconnected");
637  res.success = true;
638  res.message = "disconnected from SDH";
639  return true;
640  }
641 
647  bool srvCallback_MotorPowerOn(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {
648  try {
649  sdh_->SetAxisEnable(sdh_->All, 1.0);
650  sdh_->SetAxisMotorCurrent(sdh_->All, 0.5);
651  }
652  catch (const SDH::cSDHLibraryException* e) {
653  ROS_ERROR("An exception was caught: %s", e->what());
654  res.success = false;
655  res.message = e->what();
656  return true;
657  }
658  ROS_INFO("Motor power ON");
659  res.success = true;
660  res.message = "Motor ON";
661  return true;
662  }
663 
669  bool srvCallback_MotorPowerOff(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {
670  try {
671  sdh_->SetAxisEnable(sdh_->All, 0.0);
672  sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
673  }
674  catch (const SDH::cSDHLibraryException* e) {
675  ROS_ERROR("An exception was caught: %s", e->what());
676  res.success = false;
677  res.message = e->what();
678  return true;
679  }
680  ROS_INFO("Motor power OFF");
681  res.success = true;
682  res.message = "Motor OFF";
683  return true;
684  }
685 
691  void updateSdh()
692  {
693  const ros::Time time = ros::Time::now();
694  ROS_DEBUG("updateJointState");
695  if (isInitialized_ == true)
696  {
697  if (hasNewGoal_ == true)
698  {
699  // stop sdh first when new goal arrived
700  try
701  {
702  sdh_->Stop();
703  }
704  catch (SDH::cSDHLibraryException* e)
705  {
706  ROS_ERROR("An exception was caught: %s", e->what());
707  delete e;
708  }
709 
710  if (operationMode_ == "position")
711  {
712  ROS_DEBUG("moving sdh in position mode");
713 
714  try
715  {
716  sdh_->SetAxisTargetAngle(axes_, targetAngles_);
717  sdh_->MoveHand(false);
718  }
719  catch (SDH::cSDHLibraryException* e)
720  {
721  ROS_ERROR("An exception was caught: %s", e->what());
722  delete e;
723  }
724  }
725  else if (operationMode_ == "velocity")
726  {
727  ROS_DEBUG("moving sdh in velocity mode");
728  try
729  {
730  sdh_->SetAxisTargetVelocity(axes_, velocities_);
731  // ROS_DEBUG_STREAM("velocities: " << velocities_[0] << " "<< velocities_[1] << " "<< velocities_[2] << " "<< velocities_[3] << " "<< velocities_[4] << " "<< velocities_[5] << " "<< velocities_[6]);
732  }
733  catch (SDH::cSDHLibraryException* e)
734  {
735  ROS_ERROR("An exception was caught: %s", e->what());
736  delete e;
737  }
738  }
739  else if (operationMode_ == "effort")
740  {
741  ROS_DEBUG("moving sdh in effort mode");
742  // sdh_->MoveVel(goal->trajectory.points[0].velocities);
743  ROS_WARN("Moving in effort mode currently disabled");
744  }
745  else
746  {
747  ROS_ERROR("sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]",
748  operationMode_.c_str());
749  }
750 
751  hasNewGoal_ = false;
752  }
753 
754  // read and publish joint angles and velocities
755  std::vector<double> actualAngles;
756  try
757  {
758  actualAngles = sdh_->GetAxisActualAngle(axes_);
759  }
760  catch (SDH::cSDHLibraryException* e)
761  {
762  ROS_ERROR("An exception was caught: %s", e->what());
763  delete e;
764  }
765  std::vector<double> actualVelocities;
766  try
767  {
768  actualVelocities = sdh_->GetAxisActualVelocity(axes_);
769  }
770  catch (SDH::cSDHLibraryException* e)
771  {
772  ROS_ERROR("An exception was caught: %s", e->what());
773  delete e;
774  }
775 
776  ROS_DEBUG("received %d angles from sdh", static_cast<int>(actualAngles.size()));
777 
778  // create joint_state message
779  sensor_msgs::JointState msg;
780  msg.header.stamp = time;
781  msg.name.resize(DOF_);
782  msg.position.resize(DOF_);
783  msg.velocity.resize(DOF_);
784  msg.effort.resize(DOF_);
785  // set joint names and map them to angles
786  msg.name = joint_names_;
787  // ['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']
788  // pos
789  msg.position[0] = actualAngles[0] * pi_ / 180.0; // sdh_knuckle_joint
790  msg.position[1] = actualAngles[3] * pi_ / 180.0; // sdh_thumb_2_joint
791  msg.position[2] = actualAngles[4] * pi_ / 180.0; // sdh_thumb_3_joint
792  msg.position[3] = actualAngles[5] * pi_ / 180.0; // sdh_finger_12_joint
793  msg.position[4] = actualAngles[6] * pi_ / 180.0; // sdh_finger_13_joint
794  msg.position[5] = actualAngles[1] * pi_ / 180.0; // sdh_finger_22_joint
795  msg.position[6] = actualAngles[2] * pi_ / 180.0; // sdh_finger_23_joint
796  // vel
797  msg.velocity[0] = actualVelocities[0] * pi_ / 180.0; // sdh_knuckle_joint
798  msg.velocity[1] = actualVelocities[3] * pi_ / 180.0; // sdh_thumb_2_joint
799  msg.velocity[2] = actualVelocities[4] * pi_ / 180.0; // sdh_thumb_3_joint
800  msg.velocity[3] = actualVelocities[5] * pi_ / 180.0; // sdh_finger_12_joint
801  msg.velocity[4] = actualVelocities[6] * pi_ / 180.0; // sdh_finger_13_joint
802  msg.velocity[5] = actualVelocities[1] * pi_ / 180.0; // sdh_finger_22_joint
803  msg.velocity[6] = actualVelocities[2] * pi_ / 180.0; // sdh_finger_23_joint
804  // publish message
805  topicPub_JointState_.publish(msg);
806 
807  // because the robot_state_publisher doen't know about the mimic joint, we have to publish the coupled joint separately
808  sensor_msgs::JointState mimicjointmsg;
809  mimicjointmsg.header.stamp = time;
810  mimicjointmsg.name.resize(1);
811  mimicjointmsg.position.resize(1);
812  mimicjointmsg.velocity.resize(1);
813  mimicjointmsg.name[0] = "sdh_finger_21_joint";
814  mimicjointmsg.position[0] = msg.position[0]; // sdh_knuckle_joint = sdh_finger_21_joint
815  mimicjointmsg.velocity[0] = msg.velocity[0]; // sdh_knuckle_joint = sdh_finger_21_joint
816  topicPub_JointState_.publish(mimicjointmsg);
817 
818  // publish controller state message
819  control_msgs::JointTrajectoryControllerState controllermsg;
820  controllermsg.header.stamp = time;
821  controllermsg.joint_names.resize(DOF_);
822  controllermsg.desired.positions.resize(DOF_);
823  controllermsg.desired.velocities.resize(DOF_);
824  controllermsg.actual.positions.resize(DOF_);
825  controllermsg.actual.velocities.resize(DOF_);
826  controllermsg.error.positions.resize(DOF_);
827  controllermsg.error.velocities.resize(DOF_);
828  // set joint names and map them to angles
829  controllermsg.joint_names = joint_names_;
830  // ['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']
831  // desired pos
832  if (targetAngles_.size() != 0)
833  {
834  controllermsg.desired.positions[0] = targetAngles_[0] * pi_ / 180.0; // sdh_knuckle_joint
835  controllermsg.desired.positions[1] = targetAngles_[3] * pi_ / 180.0; // sdh_thumb_2_joint
836  controllermsg.desired.positions[2] = targetAngles_[4] * pi_ / 180.0; // sdh_thumb_3_joint
837  controllermsg.desired.positions[3] = targetAngles_[5] * pi_ / 180.0; // sdh_finger_12_joint
838  controllermsg.desired.positions[4] = targetAngles_[6] * pi_ / 180.0; // sdh_finger_13_joint
839  controllermsg.desired.positions[5] = targetAngles_[1] * pi_ / 180.0; // sdh_finger_22_joint
840  controllermsg.desired.positions[6] = targetAngles_[2] * pi_ / 180.0; // sdh_finger_23_joint
841  }
842  // desired vel
843  // they are all zero
844  // actual pos
845  controllermsg.actual.positions = msg.position;
846  // actual vel
847  controllermsg.actual.velocities = msg.velocity;
848  // error, calculated out of desired and actual values
849  for (int i = 0; i < DOF_; i++)
850  {
851  controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
852  controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
853  }
854  // publish controller message
855  topicPub_ControllerState_.publish(controllermsg);
856 
857  // read sdh status
858  state_ = sdh_->GetAxisActualState(axes_);
859 
860  // publish temperature
861  schunk_sdh::TemperatureArray temp_array;
862  temp_array.header.stamp = time;
863  const std::vector<double> temp_value = sdh_->GetTemperature(sdh_->all_temperature_sensors);
864  if(temp_value.size()==temperature_names_.size()) {
865  temp_array.name = temperature_names_;
866  temp_array.temperature = temp_value;
867  }
868  else {
869  ROS_ERROR("amount of temperatures mismatch with stored names");
870  }
871  topicPub_Temperature_.publish(temp_array);
872  }
873  else
874  {
875  ROS_DEBUG("sdh not initialized");
876  }
877  // publishing diagnotic messages
878  diagnostic_msgs::DiagnosticArray diagnostics;
879  diagnostics.status.resize(1);
880  // set data to diagnostics
881  if (isError_)
882  {
883  diagnostics.status[0].level = 2;
884  diagnostics.status[0].name = "schunk_powercube_chain";
885  diagnostics.status[0].message = "one or more drives are in Error mode";
886  }
887  else
888  {
889  if (isInitialized_)
890  {
891  diagnostics.status[0].level = 0;
892  diagnostics.status[0].name = nh_.getNamespace(); // "schunk_powercube_chain";
893  if (isDSAInitialized_)
894  diagnostics.status[0].message = "sdh with tactile sensing initialized and running";
895  else
896  diagnostics.status[0].message = "sdh initialized and running, tactile sensors not connected";
897  }
898  else
899  {
900  diagnostics.status[0].level = 1;
901  diagnostics.status[0].name = nh_.getNamespace(); // "schunk_powercube_chain";
902  diagnostics.status[0].message = "sdh not initialized";
903  }
904  }
905  // publish diagnostic message
906  topicPub_Diagnostics_.publish(diagnostics);
907  }
908 
914  void updateDsa()
915  {
916  static const int dsa_reorder[6] = {2, 3, 4, 5, 0, 1}; // t1,t2,f11,f12,f21,f22
917  ROS_DEBUG("updateTactileData");
918 
919  if (isDSAInitialized_)
920  {
921  // read tactile data
922  for (int i = 0; i < 7; i++)
923  {
924  try
925  {
926  // dsa_->SetFramerate( 0, true, true );
927  dsa_->UpdateFrame();
928  }
929  catch (SDH::cSDHLibraryException* e)
930  {
931  ROS_ERROR("An exception was caught: %s", e->what());
932  delete e;
933  }
934  }
935 
936  schunk_sdh::TactileSensor msg;
937  msg.header.stamp = ros::Time::now();
938  msg.tactile_matrix.resize(dsa_->GetSensorInfo().nb_matrices);
939  for (int i = 0; i < dsa_->GetSensorInfo().nb_matrices; i++)
940  {
941  const int m = dsa_reorder[i];
942  schunk_sdh::TactileMatrix &tm = msg.tactile_matrix[i];
943  tm.matrix_id = i;
944  tm.cells_x = dsa_->GetMatrixInfo(m).cells_x;
945  tm.cells_y = dsa_->GetMatrixInfo(m).cells_y;
946  tm.tactile_array.resize(tm.cells_x * tm.cells_y);
947  for (uint y = 0; y < tm.cells_y; y++)
948  {
949  for (uint x = 0; x < tm.cells_x; x++)
950  tm.tactile_array[tm.cells_x * y + x] = dsa_->GetTexel(m, x, y);
951  }
952  }
953  // publish matrix
954  topicPub_TactileSensor_.publish(msg);
955 
956  // read tactile matrices and convert to pressure units
957  schunk_sdh::PressureArrayList msg_pressure_list;
958  msg_pressure_list.header.stamp = ros::Time::now();
959  const SDH::cDSA::sSensorInfo &sensor_info = dsa_->GetSensorInfo();
960  msg_pressure_list.pressure_list.resize(sensor_info.nb_matrices);
961  for(const uint &fi : {0,1,2}) {
962  for(const uint &part : {0,1}) {
963  // get internal ID and name for each finger tactile matrix
964  const int mid = dsa_->GetMatrixIndex(fi, part);
965  msg_pressure_list.pressure_list[mid].sensor_name = "sdh_"+finger_names_[fi]+std::to_string(part+2)+"_link";
966 
967  // read texel values and convert to pressure
968  const SDH::cDSA::sMatrixInfo &matrix_info = dsa_->GetMatrixInfo(mid);
969  msg_pressure_list.pressure_list[mid].cells_x = matrix_info.cells_x;
970  msg_pressure_list.pressure_list[mid].cells_y = matrix_info.cells_y;
971  msg_pressure_list.pressure_list[mid].pressure.resize(matrix_info.cells_x * matrix_info.cells_y);
972 
973  for (uint y(0); y < matrix_info.cells_y; y++) {
974  for (uint x(0); x < matrix_info.cells_x; x++) {
975  // convert voltage to pressure in Pascal
976  msg_pressure_list.pressure_list[mid].pressure[matrix_info.cells_x * y + x] =
977  dsa_->GetTexel(mid, x, y) * dsa_calib_pressure_ / dsa_calib_voltage_ * 1e6;
978  }
979  }
980  } // part
981  } // finger
982  topicPub_Pressure_.publish(msg_pressure_list);
983  }
984  }
985 };
986 
987 const std::vector<std::string> SdhNode::temperature_names_ = {
988  "root",
989  "proximal_finger_1", "distal_finger_1",
990  "proximal_finger_2", "distal_finger_2",
991  "proximal_finger_3", "distal_finger_3",
992  "controller", "pcb"
993 };
994 
995 const std::vector<std::string> SdhNode::finger_names_ = {
996  "finger_2", "thumb_", "finger_1"
997 };
998 // SdhNode
999 
1005 int main(int argc, char** argv)
1006 {
1007  // initialize ROS, spezify name of node
1008  ros::init(argc, argv, "schunk_sdh");
1009 
1010  // SdhNode sdh_node(ros::this_node::getName() + "/joint_trajectory_action");
1011  SdhNode sdh_node(ros::this_node::getName() + "/follow_joint_trajectory");
1012  if (!sdh_node.init())
1013  return 0;
1014 
1015  ROS_INFO("...sdh node running...");
1016 
1017  double frequency;
1018  if (sdh_node.nh_.hasParam("frequency"))
1019  {
1020  sdh_node.nh_.getParam("frequency", frequency);
1021  }
1022  else
1023  {
1024  frequency = 5; // Hz
1025  ROS_WARN("Parameter frequency not available, setting to default value: %f Hz", frequency);
1026  }
1027 
1028  // sleep(1);
1029  ros::Rate loop_rate(frequency); // Hz
1030  while (sdh_node.nh_.ok())
1031  {
1032  // publish JointState
1033  sdh_node.updateSdh();
1034 
1035  // publish TactileData
1036  sdh_node.updateDsa();
1037 
1038  // sleep and waiting for messages, callbacks
1039  ros::spinOnce();
1040  loop_rate.sleep();
1041  }
1042 
1043  return 0;
1044 }
std::string sdhdevicetype_
Definition: sdh.cpp:97
std::vector< int > axes_
Definition: sdh.cpp:118
static const std::vector< std::string > finger_names_
Definition: sdh.cpp:125
double pi_
Definition: sdh.cpp:113
ros::ServiceServer srvServer_Init_
Definition: sdh.cpp:76
ros::Publisher topicPub_Pressure_
Definition: sdh.cpp:70
ros::Publisher topicPub_Temperature_
Definition: sdh.cpp:69
trajectory_msgs::JointTrajectory traj_
Definition: sdh.cpp:115
std::vector< SDH::cSDH::eAxisState > state_
Definition: sdh.cpp:95
double dsa_sensitivity_
Definition: sdh.cpp:102
void publish(const boost::shared_ptr< M > &message) const
bool srvCallback_EmergencyStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for emergency_stop.
Definition: sdh.cpp:592
bool isDSAInitialized_
Definition: sdh.cpp:110
ros::ServiceServer srvServer_MotorOff_
Definition: sdh.cpp:83
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int size() const
SDH::cSDH * sdh_
Definition: sdh.cpp:93
double dsa_calib_voltage_
Definition: sdh.cpp:104
bool isInitialized_
Definition: sdh.cpp:109
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int id_read_
Definition: sdh.cpp:106
bool srvCallback_Disconnect(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for disconnect.
Definition: sdh.cpp:618
bool switchOperationMode(const std::string &mode)
Switches operation mode if possible.
Definition: sdh.cpp:249
ros::ServiceServer srvServer_EmergencyStop_
Definition: sdh.cpp:80
ROSCPP_DECL const std::string & getName()
std::string sdhdevicestring_
Definition: sdh.cpp:98
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::string dsadevicestring_
Definition: sdh.cpp:100
ros::Publisher topicPub_JointState_
Definition: sdh.cpp:65
int baudrate_
Definition: sdh.cpp:106
void updateDsa()
Main routine to update dsa.
Definition: sdh.cpp:914
#define ROS_WARN(...)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
int main(int argc, char **argv)
Main loop of ROS node.
Definition: sdh.cpp:1005
ros::ServiceServer srvServer_SetOperationMode_
Definition: sdh.cpp:79
int id_write_
Definition: sdh.cpp:106
ros::ServiceServer srvServer_Disconnect_
Definition: sdh.cpp:81
SdhNode(std::string name)
Constructor for SdhNode class.
Definition: sdh.cpp:133
SDH::cDSA * dsa_
Definition: sdh.cpp:94
ros::ServiceServer srvServer_MotorOn_
Definition: sdh.cpp:82
bool srvCallback_MotorPowerOn(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Enable motor power.
Definition: sdh.cpp:647
int DOF_
Definition: sdh.cpp:112
std::string operationMode_
Definition: sdh.cpp:122
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::ServiceServer srvServer_Recover_
Definition: sdh.cpp:78
const std::string & getNamespace() const
int sdhdevicenum_
Definition: sdh.cpp:99
void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
Executes the callback from the actionlib.
Definition: sdh.cpp:288
double dsa_calib_pressure_
Definition: sdh.cpp:103
int dsadevicenum_
Definition: sdh.cpp:105
ros::Publisher topicPub_TactileSensor_
Definition: sdh.cpp:67
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
~SdhNode()
Destructor for SdhNode class.
Definition: sdh.cpp:147
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > as_
Definition: sdh.cpp:86
bool srvCallback_MotorPowerOff(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Disable motor power.
Definition: sdh.cpp:669
bool sleep()
void topicCallback_setVelocitiesRaw(const std_msgs::Float64MultiArrayPtr &velocities)
Definition: sdh.cpp:375
bool isError_
Definition: sdh.cpp:111
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool init()
Initializes node to get parameters, subscribe and publish to topics.
Definition: sdh.cpp:159
std::vector< double > targetAngles_
Definition: sdh.cpp:119
std::vector< std::string > joint_names_
Definition: sdh.cpp:117
int dsa_dbg_level_
Definition: sdh.cpp:101
Implementation of ROS node for sdh.
Definition: sdh.cpp:58
bool getParam(const std::string &key, std::string &s) const
void updateSdh()
Main routine to update sdh.
Definition: sdh.cpp:691
ros::Subscriber subSetVelocitiesRaw_
Definition: sdh.cpp:73
ros::NodeHandle nh_
create a handle for this node, initialize node
Definition: sdh.cpp:62
bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for init.
Definition: sdh.cpp:415
std::vector< double > velocities_
Definition: sdh.cpp:120
static Time now()
ros::Publisher topicPub_ControllerState_
Definition: sdh.cpp:66
bool ok() const
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
static const std::vector< std::string > temperature_names_
Definition: sdh.cpp:124
ROSCPP_DECL void spinOnce()
bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for stop.
Definition: sdh.cpp:525
#define ROS_ERROR(...)
std::string action_name_
Definition: sdh.cpp:87
double timeout_
Definition: sdh.cpp:107
bool hasNewGoal_
Definition: sdh.cpp:121
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for set_operation_mode.
Definition: sdh.cpp:553
ros::Publisher topicPub_Diagnostics_
Definition: sdh.cpp:68
#define ROS_DEBUG(...)
ros::ServiceServer srvServer_Stop_
Definition: sdh.cpp:77


schunk_sdh
Author(s): Mathias Luedtke , Florian Weisshardt
autogenerated on Mon Nov 25 2019 03:48:23