00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052 #include "pr2_bringup_gazebo_demo/pr2_gripper_transmission.h"
00053 #include <pluginlib/class_list_macros.h>
00054 #include <algorithm>
00055 #include <numeric>
00056 #include <angles/angles.h>
00057
00058 using namespace pr2_hardware_interface;
00059 using namespace pr2_bringup_gazebo_demo;
00060
00061 PLUGINLIB_DECLARE_CLASS(pr2_bringup_gazebo_demo, PR2GripperTransmissionCal,
00062 pr2_bringup_gazebo_demo::PR2GripperTransmissionCal,
00063 pr2_mechanism_model::Transmission)
00064
00065 bool PR2GripperTransmissionCal::initXml(TiXmlElement *config, pr2_mechanism_model::Robot *robot)
00066 {
00067 const char *name = config->Attribute("name");
00068 name_ = name ? name : "";
00069
00070 TiXmlElement *ael = config->FirstChildElement("actuator");
00071 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00072 if (!actuator_name || !robot->getActuator(actuator_name))
00073 {
00074 ROS_ERROR("PR2GripperTransmissionCal could not find actuator named \"%s\"", actuator_name);
00075 return false;
00076 }
00077 robot->getActuator(actuator_name)->command_.enable_ = true;
00078 actuator_names_.push_back(actuator_name);
00079
00080 for (TiXmlElement *j = config->FirstChildElement("gap_joint"); j; j = j->NextSiblingElement("gap_joint"))
00081 {
00082 const char *joint_name = j->Attribute("name");
00083 if (!joint_name)
00084 {
00085 ROS_ERROR("PR2GripperTransmissionCal did not specify joint name");
00086 return false;
00087 }
00088
00089 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00090 if (!joint)
00091 {
00092 ROS_ERROR("PR2GripperTransmissionCal could not find joint named \"%s\"", joint_name);
00093 return false;
00094 }
00095 gap_joint_ = std::string(joint_name);
00096 joint_names_.push_back(joint_name);
00097
00098
00099 const char *joint_reduction = j->Attribute("mechanical_reduction");
00100 if (!joint_reduction)
00101 {
00102 ROS_ERROR("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: mechanical reduction.", joint_name);
00103 return false;
00104 }
00105 gap_mechanical_reduction_ = atof(joint_reduction);
00106
00107
00108 const char *screw_reduction_str = j->Attribute("screw_reduction");
00109 if (screw_reduction_str == NULL)
00110 {
00111 screw_reduction_ = 2.0/1000.0;
00112 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: screw drive reduction, using default for PR2 alpha2.", joint_name);
00113 }
00114 else
00115 screw_reduction_ = atof(screw_reduction_str);
00116
00117
00118
00119 const char *gear_ratio_str = j->Attribute("gear_ratio");
00120 if (gear_ratio_str == NULL)
00121 {
00122 gear_ratio_ = 29.16;
00123 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: gear_ratio, using default for PR2 alpha2.", joint_name);
00124 }
00125 else
00126 gear_ratio_ = atof(gear_ratio_str);
00127
00128
00129
00130 const char *theta0_str = j->Attribute("theta0");
00131 if (theta0_str == NULL)
00132 {
00133 theta0_ = 2.97571*M_PI/180.0;
00134 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: theta0, using default for PR2 alpha2.", joint_name);
00135 }
00136 else
00137 theta0_ = atof(theta0_str);
00138
00139 const char *phi0_str = j->Attribute("phi0");
00140 if (phi0_str == NULL)
00141 {
00142 phi0_ = 29.98717*M_PI/180.0;
00143 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: phi0, using default for PR2 alpha2.", joint_name);
00144 }
00145 else
00146 phi0_ = atof(phi0_str);
00147
00148 const char *t0_str = j->Attribute("t0");
00149 if (t0_str == NULL)
00150 {
00151 t0_ = -0.19543/1000.0;
00152 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: t0, using default for PR2 alpha2.", joint_name);
00153 }
00154 else
00155 t0_ = atof(t0_str);
00156
00157 const char *L0_str = j->Attribute("L0");
00158 if (L0_str == NULL)
00159 {
00160 L0_ = 34.70821/1000.0;
00161 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: L0, using default for PR2 alpha2.", joint_name);
00162 }
00163 else
00164 L0_ = atof(L0_str);
00165
00166 const char *h_str = j->Attribute("h");
00167 if (h_str == NULL)
00168 {
00169 h_ = 5.200/1000.0;
00170 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: h, using default for PR2 alpha2.", joint_name);
00171 }
00172 else
00173 h_ = atof(h_str);
00174
00175 const char *a_str = j->Attribute("a");
00176 if (a_str == NULL)
00177 {
00178 a_ = 67.56801/1000.0;
00179 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: a, using default for PR2 alpha2.", joint_name);
00180 }
00181 else
00182 a_ = atof(a_str);
00183
00184 const char *b_str = j->Attribute("b");
00185 if (b_str == NULL)
00186 {
00187 b_ = 48.97193/1000.0;
00188 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: b, using default for PR2 alpha2.", joint_name);
00189 }
00190 else
00191 b_ = atof(b_str);
00192
00193 const char *r_str = j->Attribute("r");
00194 if (r_str == NULL)
00195 {
00196 r_ = 91.50000/1000.0;
00197 ROS_WARN("PR2GripperTransmissionCal's joint \"%s\" has no coefficient: r, using default for PR2 alpha2.", joint_name);
00198 }
00199 else
00200 r_ = atof(r_str);
00201 }
00202
00203
00204 ROS_DEBUG("Gripper transmission parameters for %s: a=%f, b=%f, r=%f, h=%f, L0=%f, t0=%f, theta0=%f, phi0=%f, gear_ratio=%f, screw_red=%f",
00205 name_.c_str(), a_, b_, r_, h_, L0_, t0_, theta0_, phi0_, gear_ratio_, screw_reduction_);
00206
00207
00208 for (TiXmlElement *j = config->FirstChildElement("passive_joint"); j; j = j->NextSiblingElement("passive_joint"))
00209 {
00210 const char *joint_name = j->Attribute("name");
00211 if (!joint_name)
00212 {
00213 ROS_ERROR("PR2GripperTransmissionCal did not specify joint name");
00214 return false;
00215 }
00216 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00217
00218 if (!joint)
00219 {
00220 ROS_ERROR("PR2GripperTransmissionCal could not find joint named \"%s\"", joint_name);
00221 return false;
00222 }
00223
00224
00225 joint_names_.push_back(joint_name);
00226 passive_joints_.push_back(joint_name);
00227 }
00228
00229
00230 if (config->FirstChildElement("use_simulated_gripper_joint")) use_simulated_gripper_joint = true;
00231
00232 return true;
00233 }
00234
00237 void PR2GripperTransmissionCal::computeGapStates(
00238 double MR,double MR_dot,double MT,
00239 double &theta,double &dtheta_dMR,double &dt_dtheta,double &dt_dMR,double &gap_size,double &gap_velocity,double &gap_effort)
00240 {
00241
00242
00243
00244 double u = (a_*a_+b_*b_-h_*h_
00245 -pow(L0_+MR*screw_reduction_/gear_ratio_,2))/(2.0*a_*b_);
00246 u = u < -1.0 ? -1.0 : u > 1.0 ? 1.0 : u;
00247 theta = theta0_ - phi0_ + acos(u);
00248
00249
00250
00251
00252
00253 gap_size = t0_ + r_ * ( sin(theta) - sin(theta0_) );
00254
00255
00256
00257
00258
00259 MR = MR >= 0.0 ? MR : 0.0;
00260
00261 u = (a_*a_+b_*b_-h_*h_
00262 -pow(L0_+MR*screw_reduction_/gear_ratio_,2))/(2.0*a_*b_);
00263 u = u < -1.0 ? -1.0 : u > 1.0 ? 1.0 : u;
00264 double tmp_theta = theta0_ - phi0_ + acos(u);
00265
00266
00267 double arg = 1.0 - pow(u,2);
00268 arg = arg > TOL ? arg : TOL;
00269
00270 double du_dMR = -(L0_ * screw_reduction_)/(gear_ratio_*a_*b_)
00271 -MR/(a_*b_)*pow(screw_reduction_/gear_ratio_,2);
00272
00273 dtheta_dMR = -1.0/sqrt(arg) * du_dMR;
00274
00275 dt_dtheta = r_ * cos( tmp_theta );
00276 dt_dMR = dt_dtheta * dtheta_dMR;
00277 gap_velocity = MR_dot * dt_dMR;
00278
00279
00280
00281
00282
00283
00284
00285
00286 gap_effort = MT / dt_dMR / RAD2MR ;
00287
00288 }
00289
00294 void PR2GripperTransmissionCal::inverseGapStates(
00295 double theta,double &MR,double &dMR_dtheta,double &dtheta_dt,double &dMR_dt)
00296 {
00297
00298
00299
00300
00301
00302
00303 double arg = -2.0*a_*b_*cos(theta-theta0_+phi0_)
00304 -h_*h_+a_*a_+b_*b_;
00305 if (arg > 0.0)
00306 {
00307 MR = gear_ratio_/screw_reduction_ * ( sqrt(arg) - L0_ );
00308 dMR_dtheta = gear_ratio_/(2.0 * screw_reduction_) / sqrt(arg)
00309 * 2.0 * a_ * b_ * sin(theta + phi0_ - theta0_);
00310 }
00311 else
00312 {
00313 MR = gear_ratio_/screw_reduction_ * ( 0.0 - L0_ );
00314 dMR_dtheta = 0.0;
00315 }
00316
00317
00318 double gap_size = t0_ + r_ * ( sin(theta) - sin(theta0_) );
00319
00320
00321
00322
00323
00324 double tmp_dMR_dtheta = fabs(dMR_dtheta);
00325
00326 double u = (gap_size - t0_)/r_ + sin(theta0_);
00327 double arg2 = 1.0 - pow(u,2);
00328 arg2 = arg2 > TOL ? arg2 : TOL;
00329 dtheta_dt = 1.0 / sqrt( arg2 ) / r_;
00330 dMR_dt = tmp_dMR_dtheta * dtheta_dt;
00331 }
00332
00333 void PR2GripperTransmissionCal::getRateFromMaxRateJoint(
00334 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as,
00335 int &max_rate_joint_index,double &rate)
00336 {
00337
00338
00339 double max_rate = -1.0;
00340 max_rate_joint_index = js.size();
00341
00342
00343
00344
00345 for (size_t i = 1; i < js.size(); ++i)
00346 {
00347 if (fabs(js[i]->velocity_) > max_rate)
00348 {
00349 max_rate = fabs(js[i]->velocity_);
00350 max_rate_joint_index = i;
00351
00352 }
00353 }
00354 if (max_rate_joint_index >= (int)js.size())
00355 ROS_ERROR("PR2 Gripper Transmission could not find a passive joint with minimum rate, mostly likely finger joints have exploded. js[0:4]->velocity_=(%f,%f,%f,%f,%f)",js[0]->velocity_,js[1]->velocity_,js[2]->velocity_,js[3]->velocity_,js[4]->velocity_);
00356
00357 rate = js[max_rate_joint_index]->velocity_;
00358 }
00359
00360
00364 void PR2GripperTransmissionCal::propagatePosition(
00365 std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00366 {
00367
00368 ROS_ASSERT(as.size() == 1);
00369 ROS_ASSERT(js.size() == 1 + passive_joints_.size());
00370
00374 double MR = as[0]->state_.position_ / gap_mechanical_reduction_ * RAD2MR ;
00375
00377 double MR_dot = as[0]->state_.velocity_ / gap_mechanical_reduction_ * RAD2MR ;
00378
00388
00389
00390
00392 double MT = as[0]->state_.last_measured_effort_ / gap_mechanical_reduction_;
00393
00395 double theta, dtheta_dMR, dt_dtheta, dt_dMR;
00397 double gap_size,gap_velocity,gap_effort;
00398
00399
00400 computeGapStates(MR,MR_dot,MT,theta,dtheta_dMR, dt_dtheta, dt_dMR,gap_size,gap_velocity,gap_effort);
00401
00402
00403 js[0]->position_ = gap_size*2.0;
00404 js[0]->velocity_ = gap_velocity*2.0;
00405 js[0]->measured_effort_ = gap_effort/2.0;
00406
00407
00408
00409
00410 for (size_t i = 1; i < js.size(); ++i)
00411 {
00412 js[i]->position_ = theta - theta0_;
00413 js[i]->velocity_ = dtheta_dMR * MR_dot;
00414 js[i]->measured_effort_ = MT / dtheta_dMR / RAD2MR;
00415 }
00416 }
00417
00418
00419 void PR2GripperTransmissionCal::propagatePositionBackwards(
00420 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00421 {
00422 ROS_ASSERT(as.size() == 1);
00423 ROS_ASSERT(js.size() == 1 + passive_joints_.size());
00424
00425
00426 double MR,dMR_dtheta,dtheta_dt,dMR_dt;
00427 double joint_angle, joint_rate;
00428 if (use_simulated_gripper_joint)
00429 {
00430
00431
00432 double gap_size = js[0]->position_/2.0;
00433
00434 double sin_theta = (gap_size - t0_)/r_ + sin(theta0_);
00435 sin_theta = sin_theta > 1.0 ? 1.0 : sin_theta < -1.0 ? -1.0 : sin_theta;
00436 double theta = asin(sin_theta);
00437
00438
00439 inverseGapStates(theta,MR,dMR_dtheta,dtheta_dt,dMR_dt);
00440 double gap_rate = js[0]->velocity_/2.0;
00441 joint_rate = gap_rate * dtheta_dt;
00442 }
00443 else
00444 {
00445
00446 joint_angle = js[default_passive_joint_index_from_sim]->position_;
00447 joint_rate = js[default_passive_joint_index_from_sim]->velocity_;
00448
00449 double theta = angles::shortest_angular_distance(theta0_,joint_angle)+2.0*theta0_;
00450
00451 inverseGapStates(theta,MR,dMR_dtheta,dtheta_dt,dMR_dt);
00452 }
00453 double gap_effort = js[0]->commanded_effort_;
00454
00455
00456
00458 as[0]->state_.position_ = MR * gap_mechanical_reduction_ / RAD2MR ;
00459
00462 as[0]->state_.velocity_ = joint_rate * dMR_dtheta * gap_mechanical_reduction_ / RAD2MR ;
00463
00467 as[0]->state_.last_measured_effort_ = 2.0*gap_effort / dMR_dt * RAD2MR * gap_mechanical_reduction_;
00468
00469
00470 this->joint_calibration_simulator_.simulateJointCalibration(js[0],as[0]);
00471 }
00472
00473 void PR2GripperTransmissionCal::propagateEffort(
00474 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00475 {
00476 ROS_ASSERT(as.size() == 1);
00477 ROS_ASSERT(js.size() == 1 + passive_joints_.size());
00478
00479
00480
00481
00482
00483
00484
00485 double joint_angle, joint_rate, joint_torque;
00486
00487 joint_angle = js[default_passive_joint_index_from_sim]->position_;
00488 joint_rate = js[default_passive_joint_index_from_sim]->velocity_;
00489 joint_torque = js[default_passive_joint_index_from_sim]->measured_effort_;
00490
00491
00492 double theta = angles::shortest_angular_distance(theta0_,joint_angle)+2.0*theta0_;
00493
00494
00495 double MR,dMR_dtheta,dtheta_dt,dMR_dt;
00496
00497 inverseGapStates(theta,MR,dMR_dtheta,dtheta_dt,dMR_dt);
00498
00499 double gap_effort = js[0]->commanded_effort_;
00500
00501
00502
00504 as[0]->command_.effort_ = 2.0*gap_effort / dMR_dt * RAD2MR * gap_mechanical_reduction_;
00505 }
00506
00507 void PR2GripperTransmissionCal::propagateEffortBackwards(
00508 std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00509 {
00510 ROS_ASSERT(as.size() == 1);
00511 ROS_ASSERT(js.size() == 1 + passive_joints_.size());
00512
00513
00514
00515
00517 double MR = as[0]->state_.position_ / gap_mechanical_reduction_ * RAD2MR ;
00518 double MR_dot = as[0]->state_.velocity_ / gap_mechanical_reduction_ * RAD2MR ;
00519 double MT = as[0]->command_.effort_ / gap_mechanical_reduction_;
00520
00522 double theta, dtheta_dMR, dt_dtheta, dt_dMR;
00524 double gap_size,gap_velocity,gap_effort;
00525
00526
00527 computeGapStates(MR,MR_dot,MT,theta,dtheta_dMR, dt_dtheta, dt_dMR,gap_size,gap_velocity,gap_effort);
00528
00529 if (use_simulated_gripper_joint)
00530 {
00531
00532 double eps=0.01;
00533 js[0]->commanded_effort_ = (1.0-eps)*js[0]->commanded_effort_ + eps*gap_effort/2.0;
00534
00535 }
00536 else
00537 for (size_t i = 1; i < js.size(); ++i)
00538 {
00539
00540
00541
00542
00543
00544
00545
00546 double joint_theta = angles::shortest_angular_distance(theta0_,js[i]->position_) + 2.0*theta0_;
00547
00548 double joint_MR,joint_dMR_dtheta,joint_dtheta_dt,joint_dMR_dt;
00549
00550 inverseGapStates(joint_theta,joint_MR,joint_dMR_dtheta,joint_dtheta_dt,joint_dMR_dt);
00551
00552
00553
00554
00555
00556 int max_joint_rate_index;
00557 double scale=1.0,rate_threshold=0.5;
00558 double max_joint_rate;
00559 getRateFromMaxRateJoint(js, as, max_joint_rate_index, max_joint_rate);
00560 if (fabs(max_joint_rate)>rate_threshold) scale /= pow(fabs(max_joint_rate/rate_threshold),2.0);
00561
00562
00563 double eps2=0.01;
00564 js[i]->commanded_effort_ = (1.0-eps2)*js[i]->commanded_effort_ + eps2*scale*MT / dtheta_dMR / RAD2MR /2.0;
00565
00566 }
00567 }
00568