00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <robotiq_s_model_articulated_msgs/SModelRobotInput.h>
00022 #include <robotiq_s_model_articulated_msgs/SModelRobotOutput.h>
00023 #include <ros/ros.h>
00024 #include <string>
00025 #include <vector>
00026
00027
00028
00029
00030
00031
00032
00033
00034 #define private public
00035 #include <gazebo/common/Plugin.hh>
00036 #include <gazebo/common/Time.hh>
00037 #include <gazebo/math/Angle.hh>
00038 #include <gazebo/physics/physics.hh>
00039 #include <robotiq_s_model_articulated_gazebo_plugins/RobotiqHandPlugin.h>
00040 #undef private
00041
00042
00043 const std::string RobotiqHandPlugin::DefaultLeftTopicCommand =
00044 "/left_hand/command";
00045 const std::string RobotiqHandPlugin::DefaultLeftTopicState =
00046 "/left_hand/state";
00047 const std::string RobotiqHandPlugin::DefaultRightTopicCommand =
00048 "/right_hand/command";
00049 const std::string RobotiqHandPlugin::DefaultRightTopicState =
00050 "/right_hand/state";
00051
00053 RobotiqHandPlugin::RobotiqHandPlugin()
00054 {
00055
00056 for (int i = 0; i < this->NumJoints; ++i)
00057 {
00058 this->posePID[i].Init(1.0, 0, 0.5, 0.0, 0.0, 60.0, -60.0);
00059 this->posePID[i].SetCmd(0.0);
00060 }
00061
00062
00063 this->graspingMode = Basic;
00064
00065
00066 this->handState = Disabled;
00067 }
00068
00070 RobotiqHandPlugin::~RobotiqHandPlugin()
00071 {
00072 gazebo::event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
00073 this->rosNode->shutdown();
00074 this->rosQueue.clear();
00075 this->rosQueue.disable();
00076 this->callbackQueueThread.join();
00077 }
00078
00080 void RobotiqHandPlugin::Load(gazebo::physics::ModelPtr _parent,
00081 sdf::ElementPtr _sdf)
00082 {
00083 this->model = _parent;
00084 this->world = this->model->GetWorld();
00085 this->sdf = _sdf;
00086
00087 if (!this->sdf->HasElement("side") ||
00088 !this->sdf->GetElement("side")->GetValue()->Get(this->side) ||
00089 ((this->side != "left") && (this->side != "right")))
00090 {
00091 gzerr << "Failed to determine which hand we're controlling; "
00092 "aborting plugin load. <Side> should be either 'left' or 'right'."
00093 << std::endl;
00094 return;
00095 }
00096
00097
00098 std::string prefix;
00099 if (this->side == "left")
00100 prefix = "l_";
00101 else
00102 prefix = "r_";
00103
00104
00105 if (!this->FindJoints())
00106 return;
00107
00108 gzlog << "Prior to iterating.." << std::endl;
00109
00110 this->jointStates.name.resize(this->jointNames.size());
00111 this->jointStates.position.resize(this->jointNames.size());
00112 this->jointStates.velocity.resize(this->jointNames.size());
00113 this->jointStates.effort.resize(this->jointNames.size());
00114 gzlog << "About to iterate things.." << std::endl;
00115 for (size_t i = 0; i < this->jointNames.size(); ++i)
00116 {
00117 this->jointStates.name[i] = this->jointNames[i];
00118 this->jointStates.position[i] = 0;
00119 this->jointStates.velocity[i] = 0;
00120 this->jointStates.effort[i] = 0;
00121 }
00122 gzlog << "Initialized the joint state vector" << std::endl;
00123
00124
00125 std::string controlTopicName = this->DefaultLeftTopicCommand;
00126 std::string stateTopicName = this->DefaultLeftTopicState;
00127 if (this->side == "right")
00128 {
00129 controlTopicName = this->DefaultRightTopicCommand;
00130 stateTopicName = this->DefaultRightTopicState;
00131 }
00132 gzlog << "Using control topic " << controlTopicName << std::endl;
00133
00134 for (int i = 0; i < this->NumJoints; ++i)
00135 {
00136
00137 this->posePID[i].SetCmdMin(-this->fingerJoints[i]->GetEffortLimit(0));
00138 this->posePID[i].SetCmdMax(this->fingerJoints[i]->GetEffortLimit(0));
00139
00140
00141 if (this->sdf->HasElement("kp_position"))
00142 this->posePID[i].SetPGain(this->sdf->Get<double>("kp_position"));
00143
00144 if (this->sdf->HasElement("ki_position"))
00145 this->posePID[i].SetIGain(this->sdf->Get<double>("ki_position"));
00146
00147 if (this->sdf->HasElement("kd_position"))
00148 {
00149 this->posePID[i].SetDGain(this->sdf->Get<double>("kd_position"));
00150 std::cout << "dGain after overloading: " << this->posePID[i].dGain
00151 << std::endl;
00152 }
00153
00154 if (this->sdf->HasElement("position_effort_min"))
00155 this->posePID[i].SetCmdMin(this->sdf->Get<double>("position_effort_min"));
00156
00157 if (this->sdf->HasElement("position_effort_max"))
00158 this->posePID[i].SetCmdMax(this->sdf->Get<double>("position_effort_max"));
00159 }
00160
00161
00162 if (this->sdf->HasElement("topic_command"))
00163 controlTopicName = this->sdf->Get<std::string>("topic_command");
00164
00165 if (this->sdf->HasElement("topic_state"))
00166 stateTopicName = this->sdf->Get<std::string>("topic_state");
00167
00168
00169 if (!ros::isInitialized())
00170 {
00171 gzerr << "Not loading plugin since ROS hasn't been "
00172 << "properly initialized. Try starting gazebo with ROS plugin:\n"
00173 << " gazebo -s libgazebo_ros_api_plugin.so\n";
00174 return;
00175 }
00176
00177
00178 this->rosNode.reset(new ros::NodeHandle(""));
00179
00180
00181 this->pmq.startServiceThread();
00182
00183
00184 this->pubHandleStateQueue = this->pmq.addPub<robotiq_s_model_articulated_msgs::SModelRobotInput>();
00185 this->pubHandleState = this->rosNode->advertise<robotiq_s_model_articulated_msgs::SModelRobotInput>(
00186 stateTopicName, 100, true);
00187
00188
00189 std::string topicBase = std::string("robotiq_hands/") + this->side;
00190 this->pubJointStatesQueue = this->pmq.addPub<sensor_msgs::JointState>();
00191 this->pubJointStates = this->rosNode->advertise<sensor_msgs::JointState>(
00192 topicBase + std::string("_hand/joint_states"), 10);
00193
00194
00195 ros::SubscribeOptions handleCommandSo =
00196 ros::SubscribeOptions::create<robotiq_s_model_articulated_msgs::SModelRobotOutput>(
00197 controlTopicName, 100,
00198 boost::bind(&RobotiqHandPlugin::SetHandleCommand, this, _1),
00199 ros::VoidPtr(), &this->rosQueue);
00200
00201
00202 handleCommandSo.transport_hints =
00203 ros::TransportHints().reliable().tcpNoDelay(true);
00204 this->subHandleCommand = this->rosNode->subscribe(handleCommandSo);
00205
00206
00207 this->lastControllerUpdateTime = this->world->GetSimTime();
00208
00209
00210 this->callbackQueueThread =
00211 boost::thread(boost::bind(&RobotiqHandPlugin::RosQueueThread, this));
00212
00213
00214 this->updateConnection =
00215 gazebo::event::Events::ConnectWorldUpdateBegin(
00216 boost::bind(&RobotiqHandPlugin::UpdateStates, this));
00217
00218
00219 gzlog << "RobotiqHandPlugin loaded for " << this->side << " hand."
00220 << std::endl;
00221 for (int i = 0; i < this->NumJoints; ++i)
00222 {
00223 gzlog << "Position PID parameters for joint ["
00224 << this->fingerJoints[i]->GetName() << "]:" << std::endl
00225 << "\tKP: " << this->posePID[i].pGain << std::endl
00226 << "\tKI: " << this->posePID[i].iGain << std::endl
00227 << "\tKD: " << this->posePID[i].dGain << std::endl
00228 << "\tIMin: " << this->posePID[i].iMin << std::endl
00229 << "\tIMax: " << this->posePID[i].iMax << std::endl
00230 << "\tCmdMin: " << this->posePID[i].cmdMin << std::endl
00231 << "\tCmdMax: " << this->posePID[i].cmdMax << std::endl
00232 << std::endl;
00233 }
00234 gzlog << "Topic for sending hand commands: [" << controlTopicName
00235 << "]\nTopic for receiving hand state: [" << stateTopicName
00236 << "]" << std::endl;
00237 }
00238
00240 bool RobotiqHandPlugin::VerifyField(const std::string &_label, int _min,
00241 int _max, int _v)
00242 {
00243 if (_v < _min || _v > _max)
00244 {
00245 std::cerr << "Illegal " << _label << " value: [" << _v << "]. The correct "
00246 << "range is [" << _min << "," << _max << "]" << std::endl;
00247 return false;
00248 }
00249 return true;
00250 }
00251
00253 bool RobotiqHandPlugin::VerifyCommand(
00254 const robotiq_s_model_articulated_msgs::SModelRobotOutput::ConstPtr &_command)
00255 {
00256 return this->VerifyField("rACT", 0, 1, _command->rACT) &&
00257 this->VerifyField("rMOD", 0, 3, _command->rACT) &&
00258 this->VerifyField("rGTO", 0, 1, _command->rACT) &&
00259 this->VerifyField("rATR", 0, 1, _command->rACT) &&
00260 this->VerifyField("rICF", 0, 1, _command->rACT) &&
00261 this->VerifyField("rICS", 0, 1, _command->rACT) &&
00262 this->VerifyField("rPRA", 0, 255, _command->rACT) &&
00263 this->VerifyField("rSPA", 0, 255, _command->rACT) &&
00264 this->VerifyField("rFRA", 0, 255, _command->rACT) &&
00265 this->VerifyField("rPRB", 0, 255, _command->rACT) &&
00266 this->VerifyField("rSPB", 0, 255, _command->rACT) &&
00267 this->VerifyField("rFRB", 0, 255, _command->rACT) &&
00268 this->VerifyField("rPRC", 0, 255, _command->rACT) &&
00269 this->VerifyField("rSPC", 0, 255, _command->rACT) &&
00270 this->VerifyField("rFRC", 0, 255, _command->rACT) &&
00271 this->VerifyField("rPRS", 0, 255, _command->rACT) &&
00272 this->VerifyField("rSPS", 0, 255, _command->rACT) &&
00273 this->VerifyField("rFRS", 0, 255, _command->rACT);
00274 }
00275
00277 void RobotiqHandPlugin::SetHandleCommand(
00278 const robotiq_s_model_articulated_msgs::SModelRobotOutput::ConstPtr &_msg)
00279 {
00280 boost::mutex::scoped_lock lock(this->controlMutex);
00281
00282
00283 if (!this->VerifyCommand(_msg))
00284 {
00285 std::cerr << "Ignoring command" << std::endl;
00286 return;
00287 }
00288
00289 this->prevCommand = this->handleCommand;
00290
00291
00292 this->handleCommand = *_msg;
00293 }
00294
00296 void RobotiqHandPlugin::ReleaseHand()
00297 {
00298
00299 this->handleCommand.rPRA = 0;
00300 this->handleCommand.rPRB = 0;
00301 this->handleCommand.rPRC = 0;
00302
00303
00304 this->handleCommand.rSPA = 127;
00305 this->handleCommand.rSPB = 127;
00306 this->handleCommand.rSPC = 127;
00307 }
00308
00310 void RobotiqHandPlugin::StopHand()
00311 {
00312
00313 this->handleCommand.rPRA = this->handleState.gPRA;
00314 this->handleCommand.rPRB = this->handleState.gPRB;
00315 this->handleCommand.rPRC = this->handleState.gPRC;
00316 }
00317
00319 bool RobotiqHandPlugin::IsHandFullyOpen()
00320 {
00321 bool fingersOpen = true;
00322
00323
00324
00325 gazebo::math::Angle tolerance;
00326 tolerance.SetFromDegree(1.0);
00327
00328 for (int i = 2; i < this->NumJoints; ++i)
00329 {
00330 fingersOpen = fingersOpen &&
00331 (this->joints[i]->GetAngle(0) <
00332 (this->joints[i]->GetLowerLimit(0) + tolerance));
00333 }
00334
00335 return fingersOpen;
00336 }
00337
00339 void RobotiqHandPlugin::UpdateStates()
00340 {
00341 boost::mutex::scoped_lock lock(this->controlMutex);
00342
00343 gazebo::common::Time curTime = this->world->GetSimTime();
00344
00345
00346 if (curTime > this->lastControllerUpdateTime)
00347 {
00348 this->userHandleCommand = this->handleCommand;
00349
00350
00351 if (this->handleCommand.rACT == 0)
00352 {
00353 this->handState = Disabled;
00354 }
00355
00356 else if (this->handleCommand.rATR == 1)
00357 {
00358 this->handState = Emergency;
00359 }
00360
00361 else if (this->handleCommand.rICS == 1)
00362 {
00363 this->handState = ICS;
00364 }
00365
00366 else if (this->handleCommand.rICF == 1)
00367 {
00368 this->handState = ICF;
00369 }
00370 else
00371 {
00372
00373 if (static_cast<int>(this->handleCommand.rMOD) != this->graspingMode)
00374 {
00375 this->handState = ChangeModeInProgress;
00376 lastHandleCommand = handleCommand;
00377
00378
00379 this->graspingMode =
00380 static_cast<GraspingMode>(this->handleCommand.rMOD);
00381 }
00382 else if (this->handState != ChangeModeInProgress)
00383 {
00384 this->handState = Simplified;
00385 }
00386
00387
00388 if (this->handState == ChangeModeInProgress && this->IsHandFullyOpen())
00389 {
00390 this->prevCommand = this->handleCommand;
00391
00392
00393 this->handleCommand = this->lastHandleCommand;
00394 this->handState = Simplified;
00395 }
00396 }
00397
00398
00399 switch (this->handState)
00400 {
00401 case Disabled:
00402 break;
00403
00404 case Emergency:
00405
00406 if (this->IsHandFullyOpen())
00407 this->StopHand();
00408 else
00409 this->ReleaseHand();
00410 break;
00411
00412 case ICS:
00413 std::cerr << "Individual Control of Scissor not supported" << std::endl;
00414 break;
00415
00416 case ICF:
00417 if (this->handleCommand.rGTO == 0)
00418 {
00419
00420 this->StopHand();
00421 }
00422 break;
00423
00424 case ChangeModeInProgress:
00425
00426 this->ReleaseHand();
00427 break;
00428
00429 case Simplified:
00430
00431
00432 this->handleCommand.rPRB = this->handleCommand.rPRA;
00433 this->handleCommand.rPRC = this->handleCommand.rPRA;
00434
00435 this->handleCommand.rSPB = this->handleCommand.rSPA;
00436 this->handleCommand.rSPC = this->handleCommand.rSPA;
00437
00438 this->handleCommand.rFRB = this->handleCommand.rFRA;
00439 this->handleCommand.rFRC = this->handleCommand.rFRA;
00440
00441 if (this->handleCommand.rGTO == 0)
00442 {
00443
00444 this->StopHand();
00445 }
00446 break;
00447
00448 default:
00449 std::cerr << "Unrecognized state [" << this->handState << "]"
00450 << std::endl;
00451 }
00452
00453
00454 this->UpdatePIDControl((curTime - this->lastControllerUpdateTime).Double());
00455
00456
00457 this->GetAndPublishHandleState();
00458
00459
00460 this->GetAndPublishJointState(curTime);
00461
00462 this->lastControllerUpdateTime = curTime;
00463 }
00464 }
00465
00467 uint8_t RobotiqHandPlugin::GetObjectDetection(
00468 const gazebo::physics::JointPtr &_joint, int _index, uint8_t _rPR,
00469 uint8_t _prevrPR)
00470 {
00471
00472 bool isMoving = _joint->GetVelocity(0) > this->VelTolerance;
00473
00474
00475
00476 double pe, ie, de;
00477 this->posePID[_index].GetErrors(pe, ie, de);
00478 bool reachPosition = pe < this->PoseTolerance;
00479
00480 if (isMoving)
00481 {
00482
00483 return 0;
00484 }
00485 else
00486 {
00487 if (reachPosition)
00488 {
00489
00490 return 3;
00491 }
00492 else if (_rPR - _prevrPR > 0)
00493 {
00494
00495 return 2;
00496 }
00497 else
00498 {
00499
00500 return 1;
00501 }
00502 }
00503 }
00504
00506 uint8_t RobotiqHandPlugin::GetCurrentPosition(
00507 const gazebo::physics::JointPtr &_joint)
00508 {
00509
00510 gazebo::math::Angle range =
00511 _joint->GetUpperLimit(0) - _joint->GetLowerLimit(0);
00512
00513
00514 if (this->graspingMode == Pinch)
00515 range *= 177.0 / 255.0;
00516
00517
00518 gazebo::math::Angle relAngle = _joint->GetAngle(0) - _joint->GetLowerLimit(0);
00519
00520 return
00521 static_cast<uint8_t>(round(255.0 * relAngle.Radian() / range.Radian()));
00522 }
00523
00525 void RobotiqHandPlugin::GetAndPublishHandleState()
00526 {
00527
00528 this->handleState.gACT = this->userHandleCommand.rACT;
00529
00530
00531 this->handleState.gMOD = this->userHandleCommand.rMOD;
00532
00533
00534 this->handleState.gGTO = this->userHandleCommand.rGTO;
00535
00536
00537 if (this->handState == Emergency)
00538 this->handleState.gIMC = 0;
00539 else if (this->handState == ChangeModeInProgress)
00540 this->handleState.gIMC = 2;
00541 else
00542 this->handleState.gIMC = 3;
00543
00544
00545 bool isMovingA = this->joints[2]->GetVelocity(0) > this->VelTolerance;
00546 bool isMovingB = this->joints[3]->GetVelocity(0) > this->VelTolerance;
00547 bool isMovingC = this->joints[4]->GetVelocity(0) > this->VelTolerance;
00548
00549
00550 double pe, ie, de;
00551 this->posePID[2].GetErrors(pe, ie, de);
00552 bool reachPositionA = pe < this->PoseTolerance;
00553 this->posePID[3].GetErrors(pe, ie, de);
00554 bool reachPositionB = pe < this->PoseTolerance;
00555 this->posePID[4].GetErrors(pe, ie, de);
00556 bool reachPositionC = pe < this->PoseTolerance;
00557
00558
00559 if (isMovingA || isMovingB || isMovingC)
00560 {
00561
00562 this->handleState.gSTA = 0;
00563 }
00564 else
00565 {
00566 if (reachPositionA && reachPositionB && reachPositionC)
00567 {
00568
00569 this->handleState.gSTA = 3;
00570 }
00571 else if (!reachPositionA && !reachPositionB && !reachPositionC)
00572 {
00573
00574 this->handleState.gSTA = 2;
00575 }
00576 else
00577 {
00578
00579 this->handleState.gSTA = 1;
00580 }
00581 }
00582
00583
00584 this->handleState.gDTA = this->GetObjectDetection(this->joints[2], 2,
00585 this->handleCommand.rPRA, this->prevCommand.rPRA);
00586
00587
00588 this->handleState.gDTB = this->GetObjectDetection(this->joints[3], 3,
00589 this->handleCommand.rPRB, this->prevCommand.rPRB);
00590
00591
00592 this->handleState.gDTC = this->GetObjectDetection(this->joints[4], 4,
00593 this->handleCommand.rPRC, this->prevCommand.rPRC);
00594
00595
00596 this->handleState.gDTS = this->GetObjectDetection(this->joints[0], 0,
00597 this->handleCommand.rPRS, this->prevCommand.rPRS);
00598
00599
00600 if (this->handState == ChangeModeInProgress)
00601 this->handleState.gFLT = 6;
00602 else if (this->handState == Disabled)
00603 this->handleState.gFLT = 7;
00604 else if (this->handState == Emergency)
00605 this->handleState.gFLT = 11;
00606 else
00607 this->handleState.gFLT = 0;
00608
00609
00610 this->handleState.gPRA = this->userHandleCommand.rPRA;
00611
00612 this->handleState.gPOA = this->GetCurrentPosition(this->joints[2]);
00613
00614 this->handleState.gCUA = 0;
00615
00616
00617 this->handleState.gPRB = this->userHandleCommand.rPRB;
00618
00619 this->handleState.gPOB = this->GetCurrentPosition(this->joints[3]);
00620
00621 this->handleState.gCUB = 0;
00622
00623
00624 this->handleState.gPRC = this->userHandleCommand.rPRC;
00625
00626 this->handleState.gPOC = this->GetCurrentPosition(this->joints[4]);
00627
00628 this->handleState.gCUC = 0;
00629
00630
00631 this->handleState.gPRS = this->userHandleCommand.rPRS;
00632
00633 this->handleState.gPOS = this->GetCurrentPosition(this->joints[1]);
00634
00635 this->handleState.gCUS = 0;
00636
00637
00638 this->pubHandleStateQueue->push(this->handleState, this->pubHandleState);
00639 }
00640
00642 void RobotiqHandPlugin::GetAndPublishJointState(
00643 const gazebo::common::Time &_curTime)
00644 {
00645 this->jointStates.header.stamp = ros::Time(_curTime.sec, _curTime.nsec);
00646 for (size_t i = 0; i < this->joints.size(); ++i)
00647 {
00648 this->jointStates.position[i] = this->joints[i]->GetAngle(0).Radian();
00649 this->jointStates.velocity[i] = this->joints[i]->GetVelocity(0);
00650
00651 this->jointStates.effort[i] = this->joints[i]->GetForce(0u);
00652 }
00653 this->pubJointStatesQueue->push(this->jointStates, this->pubJointStates);
00654 }
00655
00657 void RobotiqHandPlugin::UpdatePIDControl(double _dt)
00658 {
00659 if (this->handState == Disabled)
00660 {
00661 for (int i = 0; i < this->NumJoints; ++i)
00662 this->fingerJoints[i]->SetForce(0, 0.0);
00663
00664 return;
00665 }
00666
00667 for (int i = 0; i < this->NumJoints; ++i)
00668 {
00669 double targetPose = 0.0;
00670 double targetSpeed = (this->MinVelocity + this->MaxVelocity) / 2.0;
00671
00672 if (i == 0)
00673 {
00674 switch (this->graspingMode)
00675 {
00676 case Wide:
00677 targetPose = this->joints[i]->GetUpperLimit(0).Radian();
00678 break;
00679
00680 case Pinch:
00681
00682 targetPose = -0.1919;
00683 break;
00684
00685 case Scissor:
00686
00687 targetPose = this->joints[i]->GetUpperLimit(0).Radian() -
00688 (this->joints[i]->GetUpperLimit(0).Radian() -
00689 this->joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
00690 * this->handleCommand.rPRA / 255.0;
00691 break;
00692 }
00693 }
00694 else if (i == 1)
00695 {
00696 switch (this->graspingMode)
00697 {
00698 case Wide:
00699 targetPose = this->joints[i]->GetLowerLimit(0).Radian();
00700 break;
00701
00702 case Pinch:
00703
00704 targetPose = 0.1919;
00705 break;
00706
00707 case Scissor:
00708
00709 targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
00710 (this->joints[i]->GetUpperLimit(0).Radian() -
00711 this->joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
00712 * this->handleCommand.rPRA / 255.0;
00713 break;
00714 }
00715 }
00716 else if (i >= 2 && i <= 4)
00717 {
00718 if (this->graspingMode == Pinch)
00719 {
00720
00721 targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
00722 (this->joints[i]->GetUpperLimit(0).Radian() -
00723 this->joints[i]->GetLowerLimit(0).Radian()) * (177.0 / 255.0)
00724 * this->handleCommand.rPRA / 255.0;
00725 }
00726 else if (this->graspingMode == Scissor)
00727 {
00728 targetSpeed = this->MinVelocity +
00729 ((this->MaxVelocity - this->MinVelocity) *
00730 this->handleCommand.rSPA / 255.0);
00731 }
00732 else
00733 {
00734 targetPose = this->joints[i]->GetLowerLimit(0).Radian() +
00735 (this->joints[i]->GetUpperLimit(0).Radian() -
00736 this->joints[i]->GetLowerLimit(0).Radian())
00737 * this->handleCommand.rPRA / 255.0;
00738 }
00739 }
00740
00741
00742 double currentPose = this->joints[i]->GetAngle(0).Radian();
00743
00744
00745 double poseError = currentPose - targetPose;
00746
00747
00748 double torque = this->posePID[i].Update(poseError, _dt);
00749
00750
00751 this->fingerJoints[i]->SetForce(0, torque);
00752 }
00753 }
00754
00756 bool RobotiqHandPlugin::GetAndPushBackJoint(const std::string& _jointName,
00757 gazebo::physics::Joint_V& _joints)
00758 {
00759 gazebo::physics::JointPtr joint = this->model->GetJoint(_jointName);
00760
00761 if (!joint)
00762 {
00763 gzerr << "Failed to find joint [" << _jointName
00764 << "] aborting plugin load." << std::endl;
00765 return false;
00766 }
00767 _joints.push_back(joint);
00768 gzlog << "RobotiqHandPlugin found joint [" << _jointName << "]" << std::endl;
00769 return true;
00770 }
00771
00773 bool RobotiqHandPlugin::FindJoints()
00774 {
00775
00776 gazebo::physics::JointPtr joint;
00777 std::string prefix;
00778 std::string suffix;
00779 if (this->side == "left")
00780 prefix = "l_";
00781 else
00782 prefix = "r_";
00783
00784
00785 suffix = "palm_finger_1_joint";
00786 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00787 return false;
00788 if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
00789 return false;
00790 this->jointNames.push_back(prefix + suffix);
00791
00792
00793 suffix = "palm_finger_2_joint";
00794 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00795 return false;
00796 if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
00797 return false;
00798 this->jointNames.push_back(prefix + suffix);
00799
00800
00801
00802 suffix = "finger_1_joint_proximal_actuating_hinge";
00803 if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
00804 return false;
00805 suffix = "finger_1_joint_1";
00806 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00807 return false;
00808 this->jointNames.push_back(prefix + suffix);
00809
00810
00811
00812 suffix = "finger_2_joint_proximal_actuating_hinge";
00813 if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
00814 return false;
00815 suffix = "finger_2_joint_1";
00816 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00817 return false;
00818 this->jointNames.push_back(prefix + suffix);
00819
00820
00821
00822 suffix = "finger_middle_joint_proximal_actuating_hinge";
00823 if (!this->GetAndPushBackJoint(prefix + suffix, this->fingerJoints))
00824 return false;
00825 suffix = "finger_middle_joint_1";
00826 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00827 return false;
00828 this->jointNames.push_back(prefix + suffix);
00829
00830
00831 suffix = "finger_1_joint_2";
00832 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00833 return false;
00834 this->jointNames.push_back(prefix + suffix);
00835
00836
00837 suffix = "finger_1_joint_3";
00838 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00839 return false;
00840 this->jointNames.push_back(prefix + suffix);
00841
00842
00843 suffix = "finger_2_joint_2";
00844 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00845 return false;
00846 this->jointNames.push_back(prefix + suffix);
00847
00848
00849 suffix = "finger_2_joint_3";
00850 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00851 return false;
00852 this->jointNames.push_back(prefix + suffix);
00853
00854
00855 suffix = "palm_finger_middle_joint";
00856 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00857 return false;
00858 this->jointNames.push_back(prefix + suffix);
00859
00860
00861 suffix = "finger_middle_joint_2";
00862 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00863 return false;
00864 this->jointNames.push_back(prefix + suffix);
00865
00866
00867 suffix = "finger_middle_joint_3";
00868 if (!this->GetAndPushBackJoint(prefix + suffix, this->joints))
00869 return false;
00870 this->jointNames.push_back(prefix + suffix);
00871
00872 gzlog << "RobotiqHandPlugin found all joints for " << this->side
00873 << " hand." << std::endl;
00874 return true;
00875 }
00876
00878 void RobotiqHandPlugin::RosQueueThread()
00879 {
00880 static const double timeout = 0.01;
00881
00882 while (this->rosNode->ok())
00883 {
00884 this->rosQueue.callAvailable(ros::WallDuration(timeout));
00885 }
00886 }
00887
00888 GZ_REGISTER_MODEL_PLUGIN(RobotiqHandPlugin)