RobotiqHandPlugin.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2014 Open Source Robotics Foundation
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  This file has been modified from the original, by Devon Ash
19 */
20 
21 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotInput.h>
22 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotOutput.h>
23 #include <ros/ros.h>
24 #include <string>
25 #include <vector>
26 
27 /*
28 
29 Due to necessity, I had to change the PID.hh file's definition from private members to public to allow public access of its members. They're private in 1.9 and getter functions aren't implemented until gazebo 3.0. I thought that was silly, and so I hacked around it. The functions directly access the private members by necessity. It can only change if Gazebo patches 1.9 and 2.2 to include getters for it.
30 
31 I'm not sure exactly where the dependency chain includes PID.hh for the first time, so I've encapsulated all of the gazebo includes. Not pretty, but it works. If you're reading this and know of a better soln', feel free to change it.
32 
33 */
34 #define private public
35 #include <gazebo/common/Plugin.hh>
36 #include <gazebo/common/Time.hh>
37 #include <gazebo/physics/physics.hh>
39 #undef private
40 
41 // Default topic names initialization.
43  "/left_hand/command";
45  "/left_hand/state";
47  "/right_hand/command";
49  "/right_hand/state";
50 
53 {
54  // PID default parameters.
55  for (int i = 0; i < this->NumJoints; ++i)
56  {
57  this->posePID[i].Init(1.0, 0, 0.5, 0.0, 0.0, 60.0, -60.0);
58  this->posePID[i].SetCmd(0.0);
59  }
60 
61  // Default grasping mode: Basic mode.
62  this->graspingMode = Basic;
63 
64  // Default hand state: Disabled.
65  this->handState = Disabled;
66 }
67 
70 {
71 #if GAZEBO_MAJOR_VERSION < 9
72  gazebo::event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
73 #endif
74  this->rosNode->shutdown();
75  this->rosQueue.clear();
76  this->rosQueue.disable();
77  this->callbackQueueThread.join();
78 }
79 
81 void RobotiqHandPlugin::Load(gazebo::physics::ModelPtr _parent,
82  sdf::ElementPtr _sdf)
83 {
84  this->model = _parent;
85  this->world = this->model->GetWorld();
86  this->sdf = _sdf;
87 
88  if (!this->sdf->HasElement("side") ||
89  !this->sdf->GetElement("side")->GetValue()->Get(this->side) ||
90  ((this->side != "left") && (this->side != "right")))
91  {
92  gzerr << "Failed to determine which hand we're controlling; "
93  "aborting plugin load. <Side> should be either 'left' or 'right'."
94  << std::endl;
95  return;
96  }
97 
98  // Load the vector of all joints.
99  std::string prefix;
100  if (this->side == "left")
101  prefix = "l_";
102  else
103  prefix = "r_";
104 
105  // Load the vector of all joints.
106  if (!this->FindJoints())
107  return;
108 
109  gzlog << "Prior to iterating.." << std::endl;
110  // Initialize joint state vector.
111  this->jointStates.name.resize(this->jointNames.size());
112  this->jointStates.position.resize(this->jointNames.size());
113  this->jointStates.velocity.resize(this->jointNames.size());
114  this->jointStates.effort.resize(this->jointNames.size());
115  gzlog << "About to iterate things.." << std::endl;
116  for (size_t i = 0; i < this->jointNames.size(); ++i)
117  {
118  this->jointStates.name[i] = this->jointNames[i];
119  this->jointStates.position[i] = 0;
120  this->jointStates.velocity[i] = 0;
121  this->jointStates.effort[i] = 0;
122  }
123  gzlog << "Initialized the joint state vector" << std::endl;
124 
125  // Default ROS topic names.
126  std::string controlTopicName = this->DefaultLeftTopicCommand;
127  std::string stateTopicName = this->DefaultLeftTopicState;
128  if (this->side == "right")
129  {
130  controlTopicName = this->DefaultRightTopicCommand;
131  stateTopicName = this->DefaultRightTopicState;
132  }
133  gzlog << "Using control topic " << controlTopicName << std::endl;
134 
135  for (int i = 0; i < this->NumJoints; ++i)
136  {
137  // Set the PID effort limits.
138  this->posePID[i].SetCmdMin(-this->fingerJoints[i]->GetEffortLimit(0));
139  this->posePID[i].SetCmdMax(this->fingerJoints[i]->GetEffortLimit(0));
140 
141  // Overload the PID parameters if they are available.
142  if (this->sdf->HasElement("kp_position"))
143  this->posePID[i].SetPGain(this->sdf->Get<double>("kp_position"));
144 
145  if (this->sdf->HasElement("ki_position"))
146  this->posePID[i].SetIGain(this->sdf->Get<double>("ki_position"));
147 
148  if (this->sdf->HasElement("kd_position"))
149  {
150  this->posePID[i].SetDGain(this->sdf->Get<double>("kd_position"));
151  std::cout << "dGain after overloading: " << this->posePID[i].dGain
152  << std::endl;
153  }
154 
155  if (this->sdf->HasElement("position_effort_min"))
156  this->posePID[i].SetCmdMin(this->sdf->Get<double>("position_effort_min"));
157 
158  if (this->sdf->HasElement("position_effort_max"))
159  this->posePID[i].SetCmdMax(this->sdf->Get<double>("position_effort_max"));
160  }
161 
162  // Overload the ROS topics for the hand if they are available.
163  if (this->sdf->HasElement("topic_command"))
164  controlTopicName = this->sdf->Get<std::string>("topic_command");
165 
166  if (this->sdf->HasElement("topic_state"))
167  stateTopicName = this->sdf->Get<std::string>("topic_state");
168 
169  // Initialize ROS.
170  if (!ros::isInitialized())
171  {
172  gzerr << "Not loading plugin since ROS hasn't been "
173  << "properly initialized. Try starting gazebo with ROS plugin:\n"
174  << " gazebo -s libgazebo_ros_api_plugin.so\n";
175  return;
176  }
177 
178  // Create a ROS node.
179  this->rosNode.reset(new ros::NodeHandle(""));
180 
181  // Publish multi queue.
182  this->pmq.startServiceThread();
183 
184  // Broadcasts state.
185  this->pubHandleStateQueue = this->pmq.addPub<robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput>();
186  this->pubHandleState = this->rosNode->advertise<robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput>(
187  stateTopicName, 100, true);
188 
189  // Broadcast joint state.
190  std::string topicBase = std::string("robotiq_hands/") + this->side;
191  this->pubJointStatesQueue = this->pmq.addPub<sensor_msgs::JointState>();
192  this->pubJointStates = this->rosNode->advertise<sensor_msgs::JointState>(
193  topicBase + std::string("_hand/joint_states"), 10);
194 
195  // Subscribe to user published handle control commands.
196  ros::SubscribeOptions handleCommandSo =
197  ros::SubscribeOptions::create<robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput>(
198  controlTopicName, 100,
199  boost::bind(&RobotiqHandPlugin::SetHandleCommand, this, _1),
200  ros::VoidPtr(), &this->rosQueue);
201 
202  // Enable TCP_NODELAY since TCP causes bursty communication with high jitter.
203  handleCommandSo.transport_hints =
205  this->subHandleCommand = this->rosNode->subscribe(handleCommandSo);
206 
207  // Controller time control.
208 #if GAZEBO_MAJOR_VERSION >= 9
209  this->lastControllerUpdateTime = this->world->SimTime();
210 #else
211  this->lastControllerUpdateTime = this->world->GetSimTime();
212 #endif
213 
214  // Start callback queue.
215  this->callbackQueueThread =
216  boost::thread(boost::bind(&RobotiqHandPlugin::RosQueueThread, this));
217 
218  // Connect to gazebo world update.
219  this->updateConnection =
220  gazebo::event::Events::ConnectWorldUpdateBegin(
221  boost::bind(&RobotiqHandPlugin::UpdateStates, this));
222 
223  // Log information.
224  gzlog << "RobotiqHandPlugin loaded for " << this->side << " hand."
225  << std::endl;
226  for (int i = 0; i < this->NumJoints; ++i)
227  {
228  gzlog << "Position PID parameters for joint ["
229  << this->fingerJoints[i]->GetName() << "]:" << std::endl
230  << "\tKP: " << this->posePID[i].pGain << std::endl
231  << "\tKI: " << this->posePID[i].iGain << std::endl
232  << "\tKD: " << this->posePID[i].dGain << std::endl
233  << "\tIMin: " << this->posePID[i].iMin << std::endl
234  << "\tIMax: " << this->posePID[i].iMax << std::endl
235  << "\tCmdMin: " << this->posePID[i].cmdMin << std::endl
236  << "\tCmdMax: " << this->posePID[i].cmdMax << std::endl
237  << std::endl;
238  }
239  gzlog << "Topic for sending hand commands: [" << controlTopicName
240  << "]\nTopic for receiving hand state: [" << stateTopicName
241  << "]" << std::endl;
242 }
243 
245 bool RobotiqHandPlugin::VerifyField(const std::string &_label, int _min,
246  int _max, int _v)
247 {
248  if (_v < _min || _v > _max)
249  {
250  std::cerr << "Illegal " << _label << " value: [" << _v << "]. The correct "
251  << "range is [" << _min << "," << _max << "]" << std::endl;
252  return false;
253  }
254  return true;
255 }
256 
259  const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_command)
260 {
261  return this->VerifyField("rACT", 0, 1, _command->rACT) &&
262  this->VerifyField("rMOD", 0, 3, _command->rACT) &&
263  this->VerifyField("rGTO", 0, 1, _command->rACT) &&
264  this->VerifyField("rATR", 0, 1, _command->rACT) &&
265  this->VerifyField("rICF", 0, 1, _command->rACT) &&
266  this->VerifyField("rICS", 0, 1, _command->rACT) &&
267  this->VerifyField("rPRA", 0, 255, _command->rACT) &&
268  this->VerifyField("rSPA", 0, 255, _command->rACT) &&
269  this->VerifyField("rFRA", 0, 255, _command->rACT) &&
270  this->VerifyField("rPRB", 0, 255, _command->rACT) &&
271  this->VerifyField("rSPB", 0, 255, _command->rACT) &&
272  this->VerifyField("rFRB", 0, 255, _command->rACT) &&
273  this->VerifyField("rPRC", 0, 255, _command->rACT) &&
274  this->VerifyField("rSPC", 0, 255, _command->rACT) &&
275  this->VerifyField("rFRC", 0, 255, _command->rACT) &&
276  this->VerifyField("rPRS", 0, 255, _command->rACT) &&
277  this->VerifyField("rSPS", 0, 255, _command->rACT) &&
278  this->VerifyField("rFRS", 0, 255, _command->rACT);
279 }
280 
283  const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_msg)
284 {
285  boost::mutex::scoped_lock lock(this->controlMutex);
286 
287  // Sanity check.
288  if (!this->VerifyCommand(_msg))
289  {
290  std::cerr << "Ignoring command" << std::endl;
291  return;
292  }
293 
294  this->prevCommand = this->handleCommand;
295 
296  // Update handleCommand.
297  this->handleCommand = *_msg;
298 }
299 
302 {
303  // Open the fingers.
304  this->handleCommand.rPRA = 0;
305  this->handleCommand.rPRB = 0;
306  this->handleCommand.rPRC = 0;
307 
308  // Half speed.
309  this->handleCommand.rSPA = 127;
310  this->handleCommand.rSPB = 127;
311  this->handleCommand.rSPC = 127;
312 }
313 
316 {
317  // Set the target positions to the current ones.
318  this->handleCommand.rPRA = this->handleState.gPRA;
319  this->handleCommand.rPRB = this->handleState.gPRB;
320  this->handleCommand.rPRC = this->handleState.gPRC;
321 }
322 
325 {
326  bool fingersOpen = true;
327 
328  // The hand will be fully open when all the fingers are within 'tolerance'
329  // from their lower limits.
330 #if GAZEBO_MAJOR_VERSION >= 9
331  ignition::math::Angle tolerance;
332  tolerance.Degree(1.0);
333 #else
334  gazebo::math::Angle tolerance;
335  tolerance.SetFromDegree(1.0);
336 #endif
337 
338  for (int i = 2; i < this->NumJoints; ++i)
339  {
340  fingersOpen = fingersOpen &&
341 #if GAZEBO_MAJOR_VERSION >= 9
342  (this->joints[i]->Position(0) < (this->joints[i]->LowerLimit(0) + tolerance()));
343 #else
344  (this->joints[i]->GetAngle(0) < (this->joints[i]->GetLowerLimit(0) + tolerance));
345 #endif
346  }
347 
348  return fingersOpen;
349 }
350 
353 {
354  boost::mutex::scoped_lock lock(this->controlMutex);
355 #if GAZEBO_MAJOR_VERSION >= 9
356  gazebo::common::Time curTime = this->world->SimTime();
357 #else
358  gazebo::common::Time curTime = this->world->GetSimTime();
359 #endif
360 
361  // Step 1: State transitions.
362  if (curTime > this->lastControllerUpdateTime)
363  {
364  this->userHandleCommand = this->handleCommand;
365 
366  // Deactivate gripper.
367  if (this->handleCommand.rACT == 0)
368  {
369  this->handState = Disabled;
370  }
371  // Emergency auto-release.
372  else if (this->handleCommand.rATR == 1)
373  {
374  this->handState = Emergency;
375  }
376  // Individual Control of Scissor.
377  else if (this->handleCommand.rICS == 1)
378  {
379  this->handState = ICS;
380  }
381  // Individual Control of Fingers.
382  else if (this->handleCommand.rICF == 1)
383  {
384  this->handState = ICF;
385  }
386  else
387  {
388  // Change the grasping mode.
389  if (static_cast<int>(this->handleCommand.rMOD) != this->graspingMode)
390  {
393 
394  // Update the grasping mode.
395  this->graspingMode =
396  static_cast<GraspingMode>(this->handleCommand.rMOD);
397  }
398  else if (this->handState != ChangeModeInProgress)
399  {
400  this->handState = Simplified;
401  }
402 
403  // Grasping mode initialized, let's change the state to Simplified Mode.
404  if (this->handState == ChangeModeInProgress && this->IsHandFullyOpen())
405  {
406  this->prevCommand = this->handleCommand;
407 
408  // Restore the original command.
409  this->handleCommand = this->lastHandleCommand;
410  this->handState = Simplified;
411  }
412  }
413 
414  // Step 2: Actions in each state.
415  switch (this->handState)
416  {
417  case Disabled:
418  break;
419 
420  case Emergency:
421  // Open the hand.
422  if (this->IsHandFullyOpen())
423  this->StopHand();
424  else
425  this->ReleaseHand();
426  break;
427 
428  case ICS:
429  std::cerr << "Individual Control of Scissor not supported" << std::endl;
430  break;
431 
432  case ICF:
433  if (this->handleCommand.rGTO == 0)
434  {
435  // "Stop" action.
436  this->StopHand();
437  }
438  break;
439 
441  // Open the hand.
442  this->ReleaseHand();
443  break;
444 
445  case Simplified:
446  // We are in Simplified mode, so all the fingers should follow finger A.
447  // Position.
448  this->handleCommand.rPRB = this->handleCommand.rPRA;
449  this->handleCommand.rPRC = this->handleCommand.rPRA;
450  // Velocity.
451  this->handleCommand.rSPB = this->handleCommand.rSPA;
452  this->handleCommand.rSPC = this->handleCommand.rSPA;
453  // Force.
454  this->handleCommand.rFRB = this->handleCommand.rFRA;
455  this->handleCommand.rFRC = this->handleCommand.rFRA;
456 
457  if (this->handleCommand.rGTO == 0)
458  {
459  // "Stop" action.
460  this->StopHand();
461  }
462  break;
463 
464  default:
465  std::cerr << "Unrecognized state [" << this->handState << "]"
466  << std::endl;
467  }
468 
469  // Update the hand controller.
470  this->UpdatePIDControl((curTime - this->lastControllerUpdateTime).Double());
471 
472  // Gather robot state data and publish them.
473  this->GetAndPublishHandleState();
474 
475  // Publish joint states.
476  this->GetAndPublishJointState(curTime);
477 
478  this->lastControllerUpdateTime = curTime;
479  }
480 }
481 
484  const gazebo::physics::JointPtr &_joint, int _index, uint8_t _rPR,
485  uint8_t _prevrPR)
486 {
487  // Check finger's speed.
488  bool isMoving = _joint->GetVelocity(0) > this->VelTolerance;
489 
490  // Check if the finger reached its target positions. We look at the error in
491  // the position PID to decide if reached the target.
492  double pe, ie, de;
493  this->posePID[_index].GetErrors(pe, ie, de);
494  bool reachPosition = pe < this->PoseTolerance;
495 
496  if (isMoving)
497  {
498  // Finger is in motion.
499  return 0;
500  }
501  else
502  {
503  if (reachPosition)
504  {
505  // Finger is at the requestedPosition.
506  return 3;
507  }
508  else if (_rPR - _prevrPR > 0)
509  {
510  // Finger has stopped due to a contact while closing.
511  return 2;
512  }
513  else
514  {
515  // Finger has stopped due to a contact while opening.
516  return 1;
517  }
518  }
519 }
520 
523  const gazebo::physics::JointPtr &_joint)
524 {
525  // Full range of motion.
526 #if GAZEBO_MAJOR_VERSION >= 9
527  ignition::math::Angle range = _joint->UpperLimit(0) - _joint->LowerLimit(0);
528 #else
529  gazebo::math::Angle range = _joint->GetUpperLimit(0) - _joint->GetLowerLimit(0);
530 #endif
531 
532  // The maximum value in pinch mode is 177.
533  if (this->graspingMode == Pinch)
534  range *= 177.0 / 255.0;
535 
536  // Angle relative to the lower limit.
537 #if GAZEBO_MAJOR_VERSION >= 9
538  ignition::math::Angle relAngle = _joint->Position(0) - _joint->LowerLimit(0);
539 #else
540  gazebo::math::Angle relAngle = _joint->GetAngle(0) - _joint->GetLowerLimit(0);
541 #endif
542 
543 #if GAZEBO_MAJOR_VERSION >= 9
544  return static_cast<uint8_t>(round(255.0 * relAngle() / range()));
545 #else
546  static_cast<uint8_t>(round(255.0 * relAngle.Radian() / range.Radian()));
547 #endif
548 }
549 
552 {
553  // gACT. Initialization status.
554  this->handleState.gACT = this->userHandleCommand.rACT;
555 
556  // gMOD. Operation mode status.
557  this->handleState.gMOD = this->userHandleCommand.rMOD;
558 
559  // gGTO. Action status.
560  this->handleState.gGTO = this->userHandleCommand.rGTO;
561 
562  // gIMC. Gripper status.
563  if (this->handState == Emergency)
564  this->handleState.gIMC = 0;
565  else if (this->handState == ChangeModeInProgress)
566  this->handleState.gIMC = 2;
567  else
568  this->handleState.gIMC = 3;
569 
570  // Check fingers' speed.
571  bool isMovingA = this->joints[2]->GetVelocity(0) > this->VelTolerance;
572  bool isMovingB = this->joints[3]->GetVelocity(0) > this->VelTolerance;
573  bool isMovingC = this->joints[4]->GetVelocity(0) > this->VelTolerance;
574 
575  // Check if the fingers reached their target positions.
576  double pe, ie, de;
577  this->posePID[2].GetErrors(pe, ie, de);
578  bool reachPositionA = pe < this->PoseTolerance;
579  this->posePID[3].GetErrors(pe, ie, de);
580  bool reachPositionB = pe < this->PoseTolerance;
581  this->posePID[4].GetErrors(pe, ie, de);
582  bool reachPositionC = pe < this->PoseTolerance;
583 
584  // gSTA. Motion status.
585  if (isMovingA || isMovingB || isMovingC)
586  {
587  // Gripper is in motion.
588  this->handleState.gSTA = 0;
589  }
590  else
591  {
592  if (reachPositionA && reachPositionB && reachPositionC)
593  {
594  // Gripper is stopped: All fingers reached requested position.
595  this->handleState.gSTA = 3;
596  }
597  else if (!reachPositionA && !reachPositionB && !reachPositionC)
598  {
599  // Gripper is stopped: All fingers stopped before requested position.
600  this->handleState.gSTA = 2;
601  }
602  else
603  {
604  // Gripper stopped. One or two fingers stopped before requested position.
605  this->handleState.gSTA = 1;
606  }
607  }
608 
609  // gDTA. Finger A object detection.
610  this->handleState.gDTA = this->GetObjectDetection(this->joints[2], 2,
611  this->handleCommand.rPRA, this->prevCommand.rPRA);
612 
613  // gDTB. Finger B object detection.
614  this->handleState.gDTB = this->GetObjectDetection(this->joints[3], 3,
615  this->handleCommand.rPRB, this->prevCommand.rPRB);
616 
617  // gDTC. Finger C object detection
618  this->handleState.gDTC = this->GetObjectDetection(this->joints[4], 4,
619  this->handleCommand.rPRC, this->prevCommand.rPRC);
620 
621  // gDTS. Scissor object detection. We use finger A as a reference.
622  this->handleState.gDTS = this->GetObjectDetection(this->joints[0], 0,
623  this->handleCommand.rPRS, this->prevCommand.rPRS);
624 
625  // gFLT. Fault status.
626  if (this->handState == ChangeModeInProgress)
627  this->handleState.gFLT = 6;
628  else if (this->handState == Disabled)
629  this->handleState.gFLT = 7;
630  else if (this->handState == Emergency)
631  this->handleState.gFLT = 11;
632  else
633  this->handleState.gFLT = 0;
634 
635  // gPRA. Echo of requested position for finger A.
636  this->handleState.gPRA = this->userHandleCommand.rPRA;
637  // gPOA. Finger A position [0-255].
638  this->handleState.gPOA = this->GetCurrentPosition(this->joints[2]);
639  // gCUA. Not implemented.
640  this->handleState.gCUA = 0;
641 
642  // gPRB. Echo of requested position for finger B.
643  this->handleState.gPRB = this->userHandleCommand.rPRB;
644  // gPOB. Finger B position [0-255].
645  this->handleState.gPOB = this->GetCurrentPosition(this->joints[3]);
646  // gCUB. Not implemented.
647  this->handleState.gCUB = 0;
648 
649  // gPRC. Echo of requested position for finger C.
650  this->handleState.gPRC = this->userHandleCommand.rPRC;
651  // gPOC. Finger C position [0-255].
652  this->handleState.gPOC = this->GetCurrentPosition(this->joints[4]);
653  // gCUS. Not implemented.
654  this->handleState.gCUC = 0;
655 
656  // gPRS. Echo of requested position of the scissor action
657  this->handleState.gPRS = this->userHandleCommand.rPRS;
658  // gPOS. Scissor current position [0-255]. We use finger B as reference.
659  this->handleState.gPOS = this->GetCurrentPosition(this->joints[1]);
660  // gCUS. Not implemented.
661  this->handleState.gCUS = 0;
662 
663  // Publish robot states.
664  this->pubHandleStateQueue->push(this->handleState, this->pubHandleState);
665 }
666 
669  const gazebo::common::Time &_curTime)
670 {
671  this->jointStates.header.stamp = ros::Time(_curTime.sec, _curTime.nsec);
672  for (size_t i = 0; i < this->joints.size(); ++i)
673  {
674 #if GAZEBO_MAJOR_VERSION >= 9
675  this->jointStates.position[i] = this->joints[i]->Position(0);
676 #else
677  this->jointStates.position[i] = this->joints[i]->GetAngle(0).Radian();
678 #endif
679  this->jointStates.velocity[i] = this->joints[i]->GetVelocity(0);
680  // better to use GetForceTorque dot joint axis
681  this->jointStates.effort[i] = this->joints[i]->GetForce(0u);
682  }
683  this->pubJointStatesQueue->push(this->jointStates, this->pubJointStates);
684 }
685 
688 {
689  if (this->handState == Disabled)
690  {
691  for (int i = 0; i < this->NumJoints; ++i)
692  this->fingerJoints[i]->SetForce(0, 0.0);
693 
694  return;
695  }
696 
697  for (int i = 0; i < this->NumJoints; ++i)
698  {
699  double targetPose = 0.0;
700  double targetSpeed = (this->MinVelocity + this->MaxVelocity) / 2.0;
701 
702  if (i == 0)
703  {
704  switch (this->graspingMode)
705  {
706  case Wide:
707 #if GAZEBO_MAJOR_VERSION >= 9
708  targetPose = this->joints[i]->UpperLimit(0);
709 #else
710  targetPose = this->joints[i]->GetUpperLimit(0).Radian();
711 #endif
712  break;
713 
714  case Pinch:
715  // --11 degrees.
716  targetPose = -0.1919;
717  break;
718 
719  case Scissor:
720  // Max position is reached at value 215.
721 #if GAZEBO_MAJOR_VERSION >= 9
722  targetPose = this->joints[i]->UpperLimit(0) -
723  (this->joints[i]->UpperLimit(0) -
724  this->joints[i]->LowerLimit(0)) * (215.0 / 255.0)
725 #else
726  targetPose = this->joints[i]->GetUpperLimit(0).Radian() -
727  (this->joints[i]->GetUpperLimit(0).Radian() -
728  this->joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
729 #endif
730  * this->handleCommand.rPRA / 255.0;
731  break;
732  }
733  }
734  else if (i == 1)
735  {
736  switch (this->graspingMode)
737  {
738  case Wide:
739 #if GAZEBO_MAJOR_VERSION >= 9
740  targetPose = this->joints[i]->LowerLimit(0);
741 #else
742  targetPose = this->joints[i]->GetLowerLimit(0).Radian();
743 #endif
744  break;
745 
746  case Pinch:
747  // 11 degrees.
748  targetPose = 0.1919;
749  break;
750 
751  case Scissor:
752  // Max position is reached at value 215.
753 #if GAZEBO_MAJOR_VERSION >= 9
754  targetPose = this->joints[i]->LowerLimit(0) +
755  (this->joints[i]->UpperLimit(0) -
756  this->joints[i]->LowerLimit(0)) * (215.0 / 255.0)
757 #else
758  targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
759  (this->joints[i]->GetUpperLimit(0).Radian() -
760  this->joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
761 #endif
762  * this->handleCommand.rPRA / 255.0;
763  break;
764  }
765  }
766  else if (i >= 2 && i <= 4)
767  {
768  if (this->graspingMode == Pinch)
769  {
770  // Max position is reached at value 177.
771 #if GAZEBO_MAJOR_VERSION >= 9
772  targetPose = this->joints[i]->LowerLimit(0) +
773  (this->joints[i]->UpperLimit(0) -
774  this->joints[i]->LowerLimit(0)) * (177.0 / 255.0)
775 #else
776  targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
777  (this->joints[i]->GetUpperLimit(0).Radian() -
778  this->joints[i]->GetLowerLimit(0).Radian()) * (177.0 / 255.0)
779 #endif
780  * this->handleCommand.rPRA / 255.0;
781  }
782  else if (this->graspingMode == Scissor)
783  {
784  targetSpeed = this->MinVelocity +
785  ((this->MaxVelocity - this->MinVelocity) *
786  this->handleCommand.rSPA / 255.0);
787  }
788  else
789  {
790 #if GAZEBO_MAJOR_VERSION >= 9
791  targetPose = this->joints[i]->LowerLimit(0) +
792  (this->joints[i]->UpperLimit(0) -
793  this->joints[i]->LowerLimit(0))
794 #else
795  targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
796  (this->joints[i]->GetUpperLimit(0).Radian() -
797  this->joints[i]->GetLowerLimit(0).Radian())
798 #endif
799  * this->handleCommand.rPRA / 255.0;
800  }
801  }
802 
803  // Get the current pose.
804 #if GAZEBO_MAJOR_VERSION >= 9
805  double currentPose = this->joints[i]->Position(0);
806 #else
807  double currentPose = this->joints[i]->GetAngle(0).Radian();
808 #endif
809 
810  // Position error.
811  double poseError = currentPose - targetPose;
812 
813  // Update the PID.
814  double torque = this->posePID[i].Update(poseError, _dt);
815 
816  // Apply the PID command.
817  this->fingerJoints[i]->SetForce(0, torque);
818  }
819 }
820 
822 bool RobotiqHandPlugin::GetAndPushBackJoint(const std::string& _jointName,
823  gazebo::physics::Joint_V& _joints)
824 {
825  gazebo::physics::JointPtr joint = this->model->GetJoint(_jointName);
826 
827  if (!joint)
828  {
829  gzerr << "Failed to find joint [" << _jointName
830  << "] aborting plugin load." << std::endl;
831  return false;
832  }
833  _joints.push_back(joint);
834  gzlog << "RobotiqHandPlugin found joint [" << _jointName << "]" << std::endl;
835  return true;
836 }
837 
840 {
841  // Load up the joints we expect to use, finger by finger.
842  gazebo::physics::JointPtr joint;
843  std::string prefix;
844  std::string suffix;
845  if (this->side == "left")
846  prefix = "l_";
847  else
848  prefix = "r_";
849 
850  // palm_finger_1_joint (actuated).
851  suffix = "palm_finger_1_joint";
852  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
853  return false;
854  if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
855  return false;
856  this->jointNames.push_back(prefix + suffix);
857 
858  // palm_finger_2_joint (actuated).
859  suffix = "palm_finger_2_joint";
860  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
861  return false;
862  if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
863  return false;
864  this->jointNames.push_back(prefix + suffix);
865 
866  // We read the joint state from finger_1_joint_1
867  // but we actuate finger_1_joint_proximal_actuating_hinge (actuated).
868  suffix = "finger_1_joint_proximal_actuating_hinge";
869  if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
870  return false;
871  suffix = "finger_1_joint_1";
872  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
873  return false;
874  this->jointNames.push_back(prefix + suffix);
875 
876  // We read the joint state from finger_2_joint_1
877  // but we actuate finger_2_proximal_actuating_hinge (actuated).
878  suffix = "finger_2_joint_proximal_actuating_hinge";
879  if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
880  return false;
881  suffix = "finger_2_joint_1";
882  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
883  return false;
884  this->jointNames.push_back(prefix + suffix);
885 
886  // We read the joint state from finger_middle_joint_1
887  // but we actuate finger_middle_proximal_actuating_hinge (actuated).
888  suffix = "finger_middle_joint_proximal_actuating_hinge";
889  if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
890  return false;
891  suffix = "finger_middle_joint_1";
892  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
893  return false;
894  this->jointNames.push_back(prefix + suffix);
895 
896  // finger_1_joint_2 (underactuated).
897  suffix = "finger_1_joint_2";
898  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
899  return false;
900  this->jointNames.push_back(prefix + suffix);
901 
902  // finger_1_joint_3 (underactuated).
903  suffix = "finger_1_joint_3";
904  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
905  return false;
906  this->jointNames.push_back(prefix + suffix);
907 
908  // finger_2_joint_2 (underactuated).
909  suffix = "finger_2_joint_2";
910  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
911  return false;
912  this->jointNames.push_back(prefix + suffix);
913 
914  // finger_2_joint_3 (underactuated).
915  suffix = "finger_2_joint_3";
916  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
917  return false;
918  this->jointNames.push_back(prefix + suffix);
919 
920  // palm_finger_middle_joint (underactuated).
921  suffix = "palm_finger_middle_joint";
922  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
923  return false;
924  this->jointNames.push_back(prefix + suffix);
925 
926  // finger_middle_joint_2 (underactuated).
927  suffix = "finger_middle_joint_2";
928  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
929  return false;
930  this->jointNames.push_back(prefix + suffix);
931 
932  // finger_middle_joint_3 (underactuated).
933  suffix = "finger_middle_joint_3";
934  if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
935  return false;
936  this->jointNames.push_back(prefix + suffix);
937 
938  gzlog << "RobotiqHandPlugin found all joints for " << this->side
939  << " hand." << std::endl;
940  return true;
941 }
942 
945 {
946  static const double timeout = 0.01;
947 
948  while (this->rosNode->ok())
949  {
950  this->rosQueue.callAvailable(ros::WallDuration(timeout));
951  }
952 }
953 
GZ_REGISTER_MODEL_PLUGIN(GazeboRosElevator)
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput prevCommand
Previous command received. We know if the hand is opening or closing by comparing the current command...
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput handleState
Robotiq Hand State.
void push(T &msg, ros::Publisher &pub)
gazebo::common::Time lastControllerUpdateTime
keep track of controller update sim-time.
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
static const int NumJoints
Number of joints in the hand. The three fingers can do abduction/adduction. Fingers 1 and 2 can do ci...
ros::Publisher pubHandleState
ROS publisher for Robotiq Hand state.
bool VerifyField(const std::string &_label, int _min, int _max, int _v)
Verify that one command field is within the correct range.
TransportHints & reliable()
void UpdatePIDControl(double _dt)
Update PID Joint controllers.
static constexpr double MinVelocity
Min. joint speed (rad/s). Finger is 125mm and tip speed is 22mm/s.
ROSCPP_DECL bool isInitialized()
sdf::ElementPtr sdf
Pointer to the SDF of this plugin.
std::string side
Used to select between &#39;left&#39; or &#39;right&#39; hand.
gazebo::event::ConnectionPtr updateConnection
gazebo world update connection.
void GetAndPublishHandleState()
Publish Robotiq Hand state.
gazebo::physics::Joint_V joints
Vector containing all the joints.
static constexpr double PoseTolerance
Position tolerance. If the difference between target position and current position is within this val...
static constexpr double MaxVelocity
Max. joint speed (rad/s). Finger is 125mm and tip speed is 110mm/s.
boost::mutex controlMutex
Controller update mutex.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput userHandleCommand
Original HandleControl message (published by user and unmodified).
TransportHints & tcpNoDelay(bool nodelay=true)
std::vector< std::string > jointNames
Vector containing all the joint names.
gazebo::physics::WorldPtr world
World pointer.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput lastHandleCommand
HandleControl message. Last command received before changing the grasping mode.
gazebo::physics::ModelPtr model
Parent model of the hand.
void SetHandleCommand(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_msg)
ROS topic callback to update Robotiq Hand Control Commands.
gazebo::physics::Joint_V fingerJoints
Vector containing all the actuated finger joints.
sensor_msgs::JointState jointStates
ROS joint state message.
static const std::string DefaultRightTopicCommand
Default topic name for sending control updates to the right hand.
GraspingMode
Different grasping modes.
bool FindJoints()
Grab pointers to all the joints.
PubQueue< robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput >::Ptr pubHandleStateQueue
ROS publisher queue for Robotiq Hand state.
static const std::string DefaultLeftTopicState
Default topic name for receiving state updates from the left hand.
GraspingMode graspingMode
Grasping mode.
uint8_t GetObjectDetection(const gazebo::physics::JointPtr &_joint, int _index, uint8_t _rPR, uint8_t _prevrPR)
Internal helper to get the object detection value.
static constexpr double VelTolerance
Velocity tolerance. Below this value we assume that the joint is stopped (rad/s). ...
TransportHints transport_hints
State handState
Hand state.
ros::CallbackQueue rosQueue
ROS callback queue.
boost::shared_ptr< PubQueue< T > > addPub()
ros::Publisher pubJointStates
Joint state publisher (rviz visualization).
void GetAndPublishJointState(const gazebo::common::Time &_curTime)
Publish Robotiq Joint state.
A plugin that implements the Robotiq 3-Finger Adaptative Gripper. The plugin exposes the next paramet...
boost::scoped_ptr< ros::NodeHandle > rosNode
ROS NodeHandle.
static const std::string DefaultLeftTopicCommand
Default topic name for sending control updates to the left hand.
bool IsHandFullyOpen()
Checks if the hand is fully open. return True when all the fingers are fully open or false otherwise...
static const std::string DefaultRightTopicState
Default topic name for receiving state updates from the right hand.
bool GetAndPushBackJoint(const std::string &_jointName, gazebo::physics::Joint_V &_joints)
Internal helper to reduce code duplication. If the joint name is found, a pointer to the joint is add...
boost::thread callbackQueueThread
ROS callback queue thread.
void RosQueueThread()
ROS callback queue thread.
void startServiceThread()
ros::Subscriber subHandleCommand
ROS control interface.
PubQueue< sensor_msgs::JointState >::Ptr pubJointStatesQueue
ROS publisher queue for joint states.
void StopHand()
Stop the fingers.
boost::shared_ptr< void > VoidPtr
virtual ~RobotiqHandPlugin()
Destructor.
gazebo::common::PID posePID[NumJoints]
PIDs used to control the finger positions.
uint8_t GetCurrentPosition(const gazebo::physics::JointPtr &_joint)
Internal helper to get the actual position of the finger.
bool VerifyCommand(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_command)
Verify that all the command fields are within the correct range.
void UpdateStates()
Update the controller.
void ReleaseHand()
Fully open the hand at half of the maximum speed.
RobotiqHandPlugin()
Constructor.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput handleCommand
HandleControl message. Originally published by user but some of the fields might be internally modifi...


robotiq_3f_gripper_articulated_gazebo_plugins
Author(s): Devon Ash , John Hsu
autogenerated on Tue Jun 1 2021 02:29:50