kdl_manager.cpp
Go to the documentation of this file.
00001 #include <generic_control_toolbox/kdl_manager.hpp>
00002 
00003 namespace generic_control_toolbox
00004 {
00005 KDLManager::KDLManager(const std::string &chain_base_link, ros::NodeHandle nh)
00006     : chain_base_link_(chain_base_link), nh_(nh)
00007 {
00008   if (!model_.initParam("/robot_description"))
00009   {
00010     throw std::runtime_error(
00011         "ERROR getting robot description (/robot_description)");
00012   }
00013 
00014   getParam();
00015 }
00016 
00017 KDLManager::~KDLManager() {}
00018 
00019 bool KDLManager::getParam()
00020 {
00021   if (!nh_.getParam("kdl_manager/eps", eps_))
00022   {
00023     ROS_WARN("KDLManager: Missing eps parameter, setting default");
00024     eps_ = 0.001;
00025   }
00026 
00027   if (!nh_.getParam("kdl_manager/max_tf_attempts", max_tf_attempts_))
00028   {
00029     ROS_WARN("KDLManager: Missing max_tf_attempts parameter, setting default");
00030     max_tf_attempts_ = 5;
00031   }
00032 
00033   if (!nh_.getParam("kdl_manager/ikvel_solver", ikvel_solver_))
00034   {
00035     ROS_WARN("KDLManager: Missing ikvel_solver parameter, setting default");
00036     ikvel_solver_ = WDLS_SOLVER;
00037   }
00038 
00039   if (!nh_.getParam("kdl_manager/ik_angle_tolerance", ik_angle_tolerance_))
00040   {
00041     ROS_WARN(
00042         "KDLManager: Missing ik_angle_tolerance parameter, setting default");
00043     ik_angle_tolerance_ = 0.01;
00044   }
00045 
00046   if (!nh_.getParam("kdl_manager/ik_pos_tolerance", ik_pos_tolerance_))
00047   {
00048     ROS_WARN("KDLManager: Missing ik_pos_tolerance parameter, setting default");
00049     ik_pos_tolerance_ = 0.005;
00050   }
00051 
00052   if (ikvel_solver_ != WDLS_SOLVER && ikvel_solver_ != NSO_SOLVER)
00053   {
00054     ROS_ERROR_STREAM("KDLManager: ikvel_solver has value "
00055                      << ikvel_solver_ << "but admissible values are "
00056                      << WDLS_SOLVER << " and " << NSO_SOLVER);
00057     ROS_WARN_STREAM("KDLManager: setting ikvel_solver to " << WDLS_SOLVER);
00058     ikvel_solver_ = WDLS_SOLVER;
00059   }
00060 
00061   if (ikvel_solver_ == NSO_SOLVER)
00062   {
00063     if (!nh_.getParam("kdl_manager/nso_weight", nso_weight_))
00064     {
00065       ROS_WARN("KDLManager: Missing nso_weight parameter, setting default");
00066       nso_weight_ = 4;
00067     }
00068   }
00069 
00070   std::vector<double> gravity;
00071   if (!nh_.getParam("kdl_manager/gravity_in_base_link", gravity))
00072   {
00073     ROS_WARN_STREAM(
00074         "KDLManager: Missing kdl_manager/gravity_in_base_link parameter. This "
00075         "will affect the dynamic solvers");
00076     gravity_in_chain_base_link_ = KDL::Vector(0, 0, 0);
00077   }
00078   else
00079   {
00080     if (gravity.size() != 3)
00081     {
00082       ROS_WARN_STREAM("KDLManager: Got gravity vector of size "
00083                       << gravity.size() << ". Should have size 3");
00084       gravity_in_chain_base_link_ = KDL::Vector(0, 0, 0);
00085     }
00086     else
00087     {
00088       gravity_in_chain_base_link_ =
00089           KDL::Vector(gravity[0], gravity[1], gravity[2]);
00090     }
00091   }
00092 
00093   return true;
00094 }
00095 
00096 bool KDLManager::initializeArm(const std::string &end_effector_link)
00097 {
00098   if (!initializeArmCommon(end_effector_link))
00099   {
00100     return false;
00101   }
00102 
00103   if (chain_.find(end_effector_link) == chain_.end())
00104   {
00105     return false;
00106   }
00107 
00108   if (ikvel_solver_ == WDLS_SOLVER)
00109   {
00110     ikvel_[end_effector_link] = IkSolverVelPtr(
00111         new KDL::ChainIkSolverVel_wdls(chain_.at(end_effector_link), eps_));
00112   }
00113   else
00114   {
00115     unsigned int joint_n = chain_.at(end_effector_link).getNrOfJoints();
00116 
00117     if (joint_n < 6)
00118     {
00119       ROS_WARN(
00120           "Number of joints for kinematic chain is smaller than 6 (%d). The "
00121           "NSO ik solver vel has issues with under-actuated chains. Using WDLS",
00122           joint_n);
00123       ikvel_[end_effector_link] = IkSolverVelPtr(
00124           new KDL::ChainIkSolverVel_wdls(chain_.at(end_effector_link), eps_));
00125     }
00126     else
00127     {
00128       KDL::JntArray w(joint_n), q_min(joint_n), q_max(joint_n),
00129           q_vel_lim(joint_n), q_desired(joint_n);
00130       getJointLimits(end_effector_link, q_min, q_max, q_vel_lim);
00131 
00132       for (unsigned int i = 0; i < joint_n; i++)
00133       {
00134         w(i) = nso_weight_;
00135         q_desired(i) = (q_max(i) + q_min(i)) / 2;
00136       }
00137 
00138       ikvel_[end_effector_link] =
00139           IkSolverVelPtr(new KDL::ChainIkSolverVel_pinv_nso(
00140               chain_.at(end_effector_link), q_desired, w, eps_));
00141     }
00142   }
00143 
00144   return true;
00145 }
00146 
00147 bool KDLManager::isInitialized(const std::string &end_effector_link) const
00148 {
00149   return (chain_.find(end_effector_link) != chain_.end());
00150 }
00151 
00152 bool KDLManager::initializeArmCommon(const std::string &end_effector_link)
00153 {
00154   if (chain_.find(end_effector_link) != chain_.end())
00155   {
00156     ROS_ERROR_STREAM("Tried to initialize arm "
00157                      << end_effector_link
00158                      << ", but it was already initialized");
00159     return false;
00160   }
00161 
00162   KDL::Tree tree;
00163   KDL::Joint kdl_joint;
00164   KDL::Chain chain;
00165   kdl_parser::treeFromUrdfModel(
00166       model_, tree);  // convert URDF description of the robot into a KDL tree
00167   if (!tree.getChain(chain_base_link_, end_effector_link, chain))
00168   {
00169     ROS_ERROR_STREAM("Failed to find chain <" << chain_base_link_ << ", "
00170                                               << end_effector_link
00171                                               << "> in the kinematic tree");
00172     return false;
00173   }
00174 
00175   // Ready to accept the end-effector as valid
00176   chain_[end_effector_link] = chain;
00177   dynamic_chain_[end_effector_link] = ChainDynParamPtr(new KDL::ChainDynParam(
00178       chain_.at(end_effector_link), gravity_in_chain_base_link_));
00179   std::vector<std::string> new_vector;
00180 
00181   ROS_DEBUG_STREAM("Initializing chain for arm " << end_effector_link);
00182   for (unsigned int i = 0; i < chain.getNrOfSegments();
00183        i++)  // check for non-movable joints
00184   {
00185     kdl_joint = chain.getSegment(i).getJoint();
00186 
00187     if (kdl_joint.getTypeName() == "None")
00188     {
00189       continue;
00190     }
00191 
00192     ROS_DEBUG_STREAM(kdl_joint.getName());
00193     new_vector.push_back(kdl_joint.getName());
00194   }
00195 
00196   actuated_joint_names_[end_effector_link] = new_vector;
00197 
00198   // Initialize solvers
00199   fkpos_[end_effector_link] =
00200       FkSolverPosPtr(new FkSolverPos(chain_.at(end_effector_link)));
00201   fkvel_[end_effector_link] =
00202       FkSolverVelPtr(new FkSolverVel(chain_.at(end_effector_link)));
00203   ikpos_[end_effector_link] =
00204       IkSolverPosPtr(new IkSolverPos(chain_.at(end_effector_link)));
00205   jac_solver_[end_effector_link] =
00206       JacSolverPtr(new JacSolver(chain_.at(end_effector_link)));
00207   eef_to_gripping_point_[end_effector_link] =
00208       KDL::Frame::Identity();  // Initialize a neutral transform.
00209   eef_to_sensor_point_[end_effector_link] =
00210       KDL::Frame::Identity();  // Initialize a neutral transform.
00211 
00212   return true;
00213 }
00214 
00215 bool KDLManager::setGrippingPoint(const std::string &end_effector_link,
00216                                   const std::string &gripping_point_frame)
00217 {
00218   if (chain_.find(end_effector_link) == chain_.end())
00219   {
00220     return false;
00221   }
00222 
00223   KDL::Frame eef_to_gripping_point;
00224 
00225   if (!getRigidTransform(end_effector_link, gripping_point_frame,
00226                          eef_to_gripping_point))
00227   {
00228     return false;
00229   }
00230 
00231   eef_to_gripping_point_.at(end_effector_link) =
00232       eef_to_gripping_point.Inverse();
00233   return true;
00234 }
00235 
00236 bool KDLManager::setSensorPoint(const std::string &end_effector_link,
00237                                 const std::string &sensor_point_frame)
00238 {
00239   if (chain_.find(end_effector_link) == chain_.end())
00240   {
00241     return false;
00242   }
00243 
00244   KDL::Frame eef_to_sensor_point;
00245 
00246   if (!getRigidTransform(end_effector_link, sensor_point_frame,
00247                          eef_to_sensor_point))
00248   {
00249     return false;
00250   }
00251 
00252   eef_to_sensor_point_.at(end_effector_link) = eef_to_sensor_point;
00253   return true;
00254 }
00255 
00256 bool KDLManager::getJointState(const std::string &end_effector_link,
00257                                const Eigen::VectorXd &qdot,
00258                                sensor_msgs::JointState &state) const
00259 {
00260   if (chain_.find(end_effector_link) == chain_.end())
00261   {
00262     return false;
00263   }
00264 
00265   if (chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
00266   {
00267     ROS_ERROR(
00268         "Joint chain for eef %s has a different number of joints than the "
00269         "provided",
00270         end_effector_link.c_str());
00271     return false;
00272   }
00273 
00274   Eigen::VectorXd q(chain_.at(end_effector_link).getNrOfJoints());
00275   int joint_index = 0;
00276 
00277   for (unsigned long i = 0; i < state.name.size(); i++)
00278   {
00279     if (hasJoint(chain_.at(end_effector_link), state.name[i]))
00280     {
00281       q[joint_index] = state.position[i];
00282       joint_index++;
00283     }
00284 
00285     if (joint_index == chain_.at(end_effector_link).getNrOfJoints())
00286     {
00287       break;
00288     }
00289   }
00290 
00291   if (joint_index != chain_.at(end_effector_link).getNrOfJoints())
00292   {
00293     ROS_ERROR(
00294         "Provided joint state does not have all of the required chain joints");
00295     return false;
00296   }
00297 
00298   return getJointState(end_effector_link, q, qdot, state);
00299 }
00300 
00301 bool KDLManager::getJointState(const std::string &end_effector_link,
00302                                const Eigen::VectorXd &q,
00303                                const Eigen::VectorXd &qdot,
00304                                sensor_msgs::JointState &state) const
00305 {
00306   if (q.rows() != qdot.rows())
00307   {
00308     ROS_ERROR(
00309         "Given joint state with a different number of joint positions and "
00310         "velocities");
00311     return false;
00312   }
00313 
00314   if (chain_.find(end_effector_link) == chain_.end())
00315   {
00316     return false;
00317   }
00318 
00319   if (chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
00320   {
00321     ROS_ERROR(
00322         "Joint chain for eef %s has a different number of joints than the "
00323         "provided",
00324         end_effector_link.c_str());
00325     return false;
00326   }
00327 
00328   bool found;
00329 
00330   for (unsigned long i = 0;
00331        i < actuated_joint_names_.at(end_effector_link).size(); i++)
00332   {
00333     found = false;
00334     for (unsigned long j = 0; j < state.name.size(); j++)
00335     {
00336       if (state.name[j] == actuated_joint_names_.at(end_effector_link)[i])
00337       {
00338         state.position[j] = q[i];
00339         state.velocity[j] = qdot[i];
00340         found = true;
00341         break;
00342       }
00343     }
00344 
00345     if (!found)
00346     {
00347       ROS_ERROR_STREAM("KDLManager: Missing joint "
00348                        << actuated_joint_names_.at(end_effector_link)[i]
00349                        << " from given joint state");
00350       return false;
00351     }
00352   }
00353 
00354   return true;
00355 }
00356 
00357 bool KDLManager::getJointState(const std::string &end_effector_link,
00358                                const Eigen::VectorXd &q,
00359                                const Eigen::VectorXd &qdot,
00360                                const Eigen::VectorXd &effort,
00361                                sensor_msgs::JointState &state) const
00362 {
00363   if (!getJointState(end_effector_link, q, qdot, state))
00364   {
00365     return false;
00366   }
00367 
00368   if (chain_.find(end_effector_link) == chain_.end())
00369   {
00370     return false;
00371   }
00372 
00373   if (chain_.at(end_effector_link).getNrOfJoints() != effort.rows())
00374   {
00375     ROS_ERROR_STREAM("Joint chain for eef "
00376                      << end_effector_link
00377                      << " has a different number of joints than the provided");
00378     return false;
00379   }
00380 
00381   bool found;
00382   for (unsigned long i = 0;
00383        i < actuated_joint_names_.at(end_effector_link).size(); i++)
00384   {
00385     found = false;
00386     for (unsigned long j = 0; j < state.name.size(); j++)
00387     {
00388       if (state.name[j] == actuated_joint_names_.at(end_effector_link)[i])
00389       {
00390         state.effort[j] = effort[i];
00391         found = true;
00392         break;
00393       }
00394     }
00395 
00396     if (!found)
00397     {
00398       ROS_ERROR_STREAM("KDLManager: Missing joint "
00399                        << actuated_joint_names_.at(end_effector_link)[i]
00400                        << " from given joint state");
00401       return false;
00402     }
00403   }
00404 
00405   return true;
00406 }
00407 
00408 bool KDLManager::getGrippingPoint(const std::string &end_effector_link,
00409                                   const sensor_msgs::JointState &state,
00410                                   KDL::Frame &out) const
00411 {
00412   if (chain_.find(end_effector_link) == chain_.end())
00413   {
00414     return false;
00415   }
00416 
00417   KDL::Frame eef_pose;
00418   if (!getEefPose(end_effector_link, state, eef_pose))
00419   {
00420     return false;
00421   }
00422 
00423   out = eef_pose * eef_to_gripping_point_.at(end_effector_link);
00424   return true;
00425 }
00426 
00427 bool KDLManager::getSensorPoint(const std::string &end_effector_link,
00428                                 const sensor_msgs::JointState &state,
00429                                 KDL::Frame &out) const
00430 {
00431   if (chain_.find(end_effector_link) == chain_.end())
00432   {
00433     return false;
00434   }
00435 
00436   KDL::Frame eef_pose;
00437   if (!getEefPose(end_effector_link, state, eef_pose))
00438   {
00439     return false;
00440   }
00441 
00442   out = eef_pose * eef_to_sensor_point_.at(end_effector_link);
00443   return true;
00444 }
00445 
00446 bool KDLManager::getGrippingTwist(const std::string &end_effector_link,
00447                                   const sensor_msgs::JointState &state,
00448                                   KDL::Twist &out) const
00449 {
00450   if (chain_.find(end_effector_link) == chain_.end())
00451   {
00452     return false;
00453   }
00454 
00455   KDL::Frame gripping_pose;
00456   if (!getGrippingPoint(end_effector_link, state, gripping_pose))
00457   {
00458     return false;
00459   }
00460 
00461   KDL::Frame eef_pose;
00462   if (!getEefPose(end_effector_link, state, eef_pose))
00463   {
00464     return false;
00465   }
00466 
00467   KDL::FrameVel eef_twist;
00468   if (!getEefTwist(end_effector_link, state, eef_twist))
00469   {
00470     return false;
00471   }
00472 
00473   Eigen::Vector3d vel_eig, rot_eig, converted_vel, r_eig;
00474   KDL::Vector r = gripping_pose.p - eef_pose.p;
00475 
00476   vel_eig << eef_twist.GetTwist().vel.data[0], eef_twist.GetTwist().vel.data[1],
00477       eef_twist.GetTwist().vel.data[2];
00478   rot_eig << eef_twist.GetTwist().rot.data[0], eef_twist.GetTwist().rot.data[1],
00479       eef_twist.GetTwist().rot.data[2];
00480   r_eig << r.data[0], r.data[1], r.data[2];
00481 
00482   converted_vel = vel_eig - MatrixParser::computeSkewSymmetric(r_eig) * rot_eig;
00483   out.vel = KDL::Vector(converted_vel[0], converted_vel[1], converted_vel[2]);
00484   out.rot = eef_twist.GetTwist().rot;
00485 
00486   return true;
00487 }
00488 
00489 bool KDLManager::getEefPose(const std::string &end_effector_link,
00490                             const sensor_msgs::JointState &state,
00491                             KDL::Frame &out) const
00492 {
00493   if (chain_.find(end_effector_link) == chain_.end())
00494   {
00495     return false;
00496   }
00497 
00498   KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
00499   KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
00500 
00501   if (!getChainJointState(state, end_effector_link, positions, velocities))
00502   {
00503     return false;
00504   }
00505 
00506   fkpos_.at(end_effector_link)->JntToCart(positions, out);
00507   return true;
00508 }
00509 
00510 bool KDLManager::getEefTwist(const std::string &end_effector_link,
00511                              const sensor_msgs::JointState &state,
00512                              KDL::FrameVel &out) const
00513 {
00514   if (chain_.find(end_effector_link) == chain_.end())
00515   {
00516     return false;
00517   }
00518 
00519   KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
00520   KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
00521   if (!getChainJointState(state, end_effector_link, positions, velocities))
00522   {
00523     return false;
00524   }
00525 
00526   fkvel_.at(end_effector_link)->JntToCart(velocities, out);
00527   return true;
00528 }
00529 
00530 bool KDLManager::getJointLimits(const std::string &end_effector_link,
00531                                 KDL::JntArray &q_min, KDL::JntArray &q_max,
00532                                 KDL::JntArray &q_vel_lim) const
00533 {
00534   if (chain_.find(end_effector_link) == chain_.end())
00535   {
00536     return false;
00537   }
00538 
00539   unsigned int joint_n = chain_.at(end_effector_link).getNrOfJoints();
00540   if (q_min.rows() != joint_n || q_max.rows() != joint_n ||
00541       q_vel_lim.rows() != joint_n)
00542   {
00543     ROS_ERROR(
00544         "KDLManager::getJointPositionLimits requires initialized joint arrays");
00545     return false;
00546   }
00547 
00548   urdf::JointConstSharedPtr joint;
00549   urdf::JointLimitsSharedPtr limits;
00550   int j = 0;
00551   // run through the kinematic chain joints and get the limits from the urdf
00552   // model
00553   for (unsigned int i = 0; i < chain_.at(end_effector_link).getNrOfSegments();
00554        i++)
00555   {
00556     if (chain_.at(end_effector_link).getSegment(i).getJoint().getType() ==
00557         KDL::Joint::JointType::None)
00558     {
00559       continue;
00560     }
00561 
00562     joint = model_.getJoint(
00563         chain_.at(end_effector_link).getSegment(i).getJoint().getName());
00564     limits = joint->limits;
00565     q_min(j) = limits->lower;
00566     q_max(j) = limits->upper;
00567     q_vel_lim(j) = limits->velocity;
00568     j++;
00569   }
00570 
00571   return true;
00572 }
00573 
00574 bool KDLManager::getJointPositions(const std::string &end_effector_link,
00575                                    const sensor_msgs::JointState &state,
00576                                    KDL::JntArray &q) const
00577 {
00578   if (chain_.find(end_effector_link) == chain_.end())
00579   {
00580     return false;
00581   }
00582 
00583   q.resize(chain_.at(end_effector_link).getNrOfJoints());
00584   KDL::JntArrayVel v(q.rows());
00585   if (!getChainJointState(state, end_effector_link, q, v))
00586   {
00587     return false;
00588   }
00589 
00590   return true;
00591 }
00592 
00593 bool KDLManager::getJointPositions(const std::string &end_effector_link,
00594                                    const sensor_msgs::JointState &state,
00595                                    Eigen::VectorXd &q) const
00596 {
00597   if (chain_.find(end_effector_link) == chain_.end())
00598   {
00599     return false;
00600   }
00601 
00602   KDL::JntArray q_kdl;
00603 
00604   if (!getJointPositions(end_effector_link, state, q_kdl))
00605   {
00606     return false;
00607   }
00608 
00609   q = q_kdl.data;
00610   return true;
00611 }
00612 
00613 bool KDLManager::getJointVelocities(const std::string &end_effector_link,
00614                                     const sensor_msgs::JointState &state,
00615                                     KDL::JntArray &q_dot) const
00616 {
00617   if (chain_.find(end_effector_link) == chain_.end())
00618   {
00619     return false;
00620   }
00621 
00622   q_dot.resize(chain_.at(end_effector_link).getNrOfJoints());
00623   KDL::JntArray q(q_dot.rows());
00624   KDL::JntArrayVel v(q_dot.rows());
00625   if (!getChainJointState(state, end_effector_link, q, v))
00626   {
00627     return false;
00628   }
00629 
00630   q_dot = v.qdot;
00631   return true;
00632 }
00633 
00634 bool KDLManager::getInertia(const std::string &end_effector_link,
00635                             const sensor_msgs::JointState &state,
00636                             Eigen::MatrixXd &H)
00637 {
00638   if (chain_.find(end_effector_link) == chain_.end())
00639   {
00640     return false;
00641   }
00642 
00643   KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
00644   KDL::JntSpaceInertiaMatrix B(chain_.at(end_effector_link).getNrOfJoints());
00645   dynamic_chain_.at(end_effector_link)->JntToMass(q, B);
00646 
00647   H = B.data;
00648   return true;
00649 }
00650 
00651 bool KDLManager::getGravity(const std::string &end_effector_link,
00652                             const sensor_msgs::JointState &state,
00653                             Eigen::MatrixXd &g)
00654 {
00655   if (chain_.find(end_effector_link) == chain_.end())
00656   {
00657     return false;
00658   }
00659 
00660   KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
00661   KDL::JntArrayVel q_dot(chain_.at(end_effector_link).getNrOfJoints());
00662   if (!getChainJointState(state, end_effector_link, q, q_dot))
00663   {
00664     return false;
00665   }
00666 
00667   KDL::JntArray q_gravity(chain_.at(end_effector_link).getNrOfJoints());
00668   dynamic_chain_.at(end_effector_link)->JntToGravity(q, q_gravity);
00669 
00670   g = q_gravity.data;
00671 
00672   return true;
00673 }
00674 
00675 bool KDLManager::getCoriolis(const std::string &end_effector_link,
00676                              const sensor_msgs::JointState &state,
00677                              Eigen::MatrixXd &coriolis)
00678 {
00679   if (chain_.find(end_effector_link) == chain_.end())
00680   {
00681     return false;
00682   }
00683 
00684   KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
00685   KDL::JntArrayVel q_dot(chain_.at(end_effector_link).getNrOfJoints());
00686   if (!getChainJointState(state, end_effector_link, q, q_dot))
00687   {
00688     return false;
00689   }
00690 
00691   KDL::JntArray cor(chain_.at(end_effector_link).getNrOfJoints());
00692   dynamic_chain_.at(end_effector_link)->JntToCoriolis(q, q_dot.qdot, cor);
00693   coriolis = cor.data;
00694   return true;
00695 }
00696 
00697 bool KDLManager::getRigidTransform(const std::string &base_frame,
00698                                    const std::string &target_frame,
00699                                    KDL::Frame &out) const
00700 {
00701   geometry_msgs::PoseStamped base_to_target;
00702   base_to_target.header.frame_id = base_frame;
00703   base_to_target.header.stamp = ros::Time(0);
00704   base_to_target.pose.position.x = 0;
00705   base_to_target.pose.position.y = 0;
00706   base_to_target.pose.position.z = 0;
00707   base_to_target.pose.orientation.x = 0;
00708   base_to_target.pose.orientation.y = 0;
00709   base_to_target.pose.orientation.z = 0;
00710   base_to_target.pose.orientation.w = 1;
00711 
00712   int attempts;
00713   for (attempts = 0; attempts < max_tf_attempts_; attempts++)
00714   {
00715     try
00716     {
00717       listener_.transformPose(target_frame, base_to_target, base_to_target);
00718       break;
00719     }
00720     catch (tf::TransformException ex)
00721     {
00722       ROS_WARN("TF exception in kdl manager: %s", ex.what());
00723       ros::Duration(0.1).sleep();
00724     }
00725   }
00726 
00727   if (attempts >= max_tf_attempts_)
00728   {
00729     ROS_ERROR(
00730         "KDL manager could not find the transform between frames %s and %s",
00731         base_frame.c_str(), target_frame.c_str());
00732     return false;
00733   }
00734 
00735   tf::poseMsgToKDL(base_to_target.pose, out);
00736   return true;
00737 }
00738 
00739 bool KDLManager::verifyPose(const std::string &end_effector_link,
00740                             const KDL::Frame &in) const
00741 {
00742   if (chain_.find(end_effector_link) == chain_.end())
00743   {
00744     return false;
00745   }
00746 
00747   sensor_msgs::JointState dummy_state;
00748 
00749   for (unsigned int i = 0;
00750        i < actuated_joint_names_.at(end_effector_link).size(); i++)
00751   {
00752     dummy_state.name.push_back(actuated_joint_names_.at(end_effector_link)[i]);
00753     dummy_state.position.push_back(0);
00754     dummy_state.velocity.push_back(0);
00755     dummy_state.effort.push_back(0);
00756   }
00757 
00758   KDL::JntArray dummy_out(dummy_state.name.size());
00759   if (getPoseIK(end_effector_link, dummy_state, in, dummy_out))
00760   {
00761     return true;
00762   }
00763 
00764   return false;
00765 }
00766 
00767 bool KDLManager::getPoseIK(const std::string &end_effector_link,
00768                            const sensor_msgs::JointState &state,
00769                            const KDL::Frame &in, KDL::JntArray &out) const
00770 {
00771   if (chain_.find(end_effector_link) == chain_.end())
00772   {
00773     return false;
00774   }
00775 
00776   KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
00777   KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
00778   KDL::Frame computedPose, difference;
00779   if (!getChainJointState(state, end_effector_link, positions, velocities))
00780   {
00781     return false;
00782   }
00783 
00784   out.resize(chain_.at(end_effector_link).getNrOfJoints());
00785   ikpos_.at(end_effector_link)->CartToJnt(positions, in, out);
00786   getPoseFK(end_effector_link, state, out,
00787             computedPose);  // verify if the forward kinematics of the computed
00788                             // solution are close to the desired pose
00789 
00790   difference = computedPose.Inverse() * in;
00791   Eigen::Vector3d quat_v;
00792   double quat_w;
00793 
00794   difference.M.GetQuaternion(quat_v[0], quat_v[1], quat_v[2], quat_w);
00795   double angle = 2 * atan2(quat_v.norm(), quat_w);
00796 
00797   if (fabs(angle) > ik_angle_tolerance_)
00798   {
00799     ROS_ERROR(
00800         "KDL manager could not compute pose ik for end-effector %s. Final "
00801         "orientation error was %.2f",
00802         end_effector_link.c_str(), angle);
00803     return false;
00804   }
00805 
00806   if (fabs(difference.p.Norm()) > ik_pos_tolerance_)
00807   {
00808     ROS_ERROR(
00809         "KDL manager could not compute pose ik for end-effector %s. Final "
00810         "position error was %.2f",
00811         end_effector_link.c_str(), difference.p.Norm());
00812     return false;
00813   }
00814 
00815   return true;
00816 }
00817 
00818 bool KDLManager::getGrippingPoseIK(const std::string &end_effector_link,
00819                                    const sensor_msgs::JointState &state,
00820                                    const KDL::Frame &in,
00821                                    KDL::JntArray &out) const
00822 {
00823   if (chain_.find(end_effector_link) == chain_.end())
00824   {
00825     return false;
00826   }
00827 
00828   KDL::Frame pose_in_eef =
00829       in * eef_to_gripping_point_.at(end_effector_link).Inverse();
00830 
00831   return getPoseIK(end_effector_link, state, pose_in_eef, out);
00832 }
00833 
00834 bool KDLManager::getPoseFK(const std::string &end_effector_link,
00835                            const sensor_msgs::JointState &state,
00836                            const KDL::JntArray &in, KDL::Frame &out) const
00837 {
00838   if (chain_.find(end_effector_link) == chain_.end())
00839   {
00840     return false;
00841   }
00842 
00843   fkpos_.at(end_effector_link)->JntToCart(in, out);
00844   return true;
00845 }
00846 
00847 bool KDLManager::getGrippingVelIK(const std::string &end_effector_link,
00848                                   const sensor_msgs::JointState &state,
00849                                   const KDL::Twist &in,
00850                                   KDL::JntArray &out) const
00851 {
00852   KDL::Frame pgrip, peef;
00853   KDL::Twist modified_in, rotated_in;
00854 
00855   if (chain_.find(end_effector_link) == chain_.end())
00856   {
00857     return false;
00858   }
00859 
00860   if (!getGrippingPoint(end_effector_link, state, pgrip))
00861   {
00862     return false;
00863   }
00864 
00865   if (!getEefPose(end_effector_link, state, peef))
00866   {
00867     return false;
00868   }
00869 
00870   // convert the input twist (in the gripping frame) to the base frame
00871   Eigen::Vector3d vel_eig, rot_eig, peef_eig, pgrip_eig;
00872   modified_in = pgrip.M * in;
00873 
00874   tf::vectorKDLToEigen(peef.p, peef_eig);
00875   tf::vectorKDLToEigen(pgrip.p, pgrip_eig);
00876   tf::vectorKDLToEigen(modified_in.vel, vel_eig);
00877   tf::vectorKDLToEigen(modified_in.rot, rot_eig);
00878 
00879   vel_eig = MatrixParser::computeSkewSymmetric(pgrip_eig - peef_eig) * rot_eig +
00880             vel_eig;
00881 
00882   tf::vectorEigenToKDL(vel_eig, modified_in.vel);
00883 
00884   if (!getVelIK(end_effector_link, state, modified_in, out))
00885   {
00886     return false;
00887   }
00888 
00889   return true;
00890 }
00891 
00892 bool KDLManager::getVelIK(const std::string &end_effector_link,
00893                           const sensor_msgs::JointState &state,
00894                           const KDL::Twist &in, KDL::JntArray &out) const
00895 {
00896   if (chain_.find(end_effector_link) == chain_.end())
00897   {
00898     return false;
00899   }
00900 
00901   KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
00902   KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
00903   if (!getChainJointState(state, end_effector_link, positions, velocities))
00904   {
00905     return false;
00906   }
00907 
00908   out.resize(chain_.at(end_effector_link).getNrOfJoints());
00909   ikvel_.at(end_effector_link)->CartToJnt(positions, in, out);
00910   return true;
00911 }
00912 
00913 bool KDLManager::getJacobian(const std::string &end_effector_link,
00914                              const sensor_msgs::JointState &state,
00915                              KDL::Jacobian &out) const
00916 {
00917   if (chain_.find(end_effector_link) == chain_.end())
00918   {
00919     return false;
00920   }
00921 
00922   KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
00923   KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
00924   if (!getChainJointState(state, end_effector_link, positions, velocities))
00925   {
00926     return false;
00927   }
00928 
00929   out.resize(positions.rows());
00930   jac_solver_.at(end_effector_link)->JntToJac(positions, out);
00931   return true;
00932 }
00933 
00934 bool KDLManager::checkStateMessage(const std::string &end_effector_link,
00935                                    const sensor_msgs::JointState &state) const
00936 {
00937   if (chain_.find(end_effector_link) == chain_.end())
00938   {
00939     return false;
00940   }
00941 
00942   unsigned int processed_joints = 0, name_size, pos_size, vel_size;
00943   name_size = state.name.size();
00944   pos_size = state.position.size();
00945   vel_size = state.velocity.size();
00946 
00947   if (name_size != pos_size || name_size != vel_size)
00948   {
00949     ROS_ERROR(
00950         "Got joint state where the name, position and velocity dimensions "
00951         "(resp. %d, %d, %d) are different",
00952         name_size, pos_size, vel_size);
00953     return false;
00954   }
00955 
00956   for (unsigned long i = 0;
00957        i < actuated_joint_names_.at(end_effector_link).size(); i++)
00958   {
00959     for (unsigned long j = 0; j < state.name.size(); j++)
00960     {
00961       if (actuated_joint_names_.at(end_effector_link)[i] == state.name[j])
00962       {
00963         processed_joints++;
00964       }
00965     }
00966   }
00967 
00968   if (processed_joints != actuated_joint_names_.at(end_effector_link).size())
00969   {
00970     return false;
00971   }
00972 
00973   return true;
00974 }
00975 
00976 bool KDLManager::getChainJointState(
00977     const sensor_msgs::JointState &current_state,
00978     const std::string &end_effector_link, KDL::JntArray &positions,
00979     KDL::JntArrayVel &velocities) const
00980 {
00981   unsigned int processed_joints = 0;
00982   unsigned int name_size, pos_size, vel_size;
00983 
00984   name_size = current_state.name.size();
00985   pos_size = current_state.position.size();
00986   vel_size = current_state.velocity.size();
00987 
00988   if (name_size != pos_size || name_size != vel_size)
00989   {
00990     ROS_ERROR(
00991         "Got joint state where the name, position and velocity dimensions "
00992         "(resp. %d, %d, %d) are different",
00993         name_size, pos_size, vel_size);
00994     return false;
00995   }
00996 
00997   for (unsigned long i = 0;
00998        i < actuated_joint_names_.at(end_effector_link).size(); i++)
00999   {
01000     for (unsigned long j = 0; j < current_state.name.size(); j++)
01001     {
01002       if (actuated_joint_names_.at(end_effector_link)[i] ==
01003           current_state.name[j])
01004       {
01005         positions(processed_joints) = current_state.position[j];
01006         velocities.q(processed_joints) = current_state.position[j];
01007         velocities.qdot(processed_joints) = current_state.velocity[j];
01008         processed_joints++;
01009       }
01010     }
01011   }
01012 
01013   if (processed_joints != actuated_joint_names_.at(end_effector_link).size())
01014   {
01015     ROS_ERROR("Failed to acquire chain joint state");
01016     return false;
01017   }
01018 
01019   return true;
01020 }
01021 
01022 bool KDLManager::hasJoint(const KDL::Chain &chain,
01023                           const std::string &joint_name) const
01024 {
01025   for (unsigned int i = 0; i < chain.getNrOfSegments(); i++)
01026   {
01027     if (chain.segments[i].getJoint().getName() == joint_name)
01028     {
01029       return true;
01030     }
01031   }
01032 
01033   return false;
01034 }
01035 
01036 bool KDLManager::getNumJoints(const std::string &end_effector_link,
01037                               unsigned int &num_joints) const
01038 {
01039   if (chain_.find(end_effector_link) == chain_.end())
01040   {
01041     return false;
01042   }
01043 
01044   num_joints = chain_.at(end_effector_link).getNrOfJoints();
01045   return true;
01046 }
01047 
01048 bool setKDLManager(const ArmInfo &arm_info, std::shared_ptr<KDLManager> manager)
01049 {
01050   if (!manager->initializeArm(arm_info.kdl_eef_frame))
01051   {
01052     return false;
01053   }
01054 
01055   if (!manager->setGrippingPoint(arm_info.kdl_eef_frame,
01056                                  arm_info.gripping_frame))
01057   {
01058     return false;
01059   }
01060 
01061   ROS_DEBUG(
01062       "Successfully set up arm %s with eef_frame %s and gripping_frame %s",
01063       arm_info.name.c_str(), arm_info.kdl_eef_frame.c_str(),
01064       arm_info.gripping_frame.c_str());
01065 
01066   return true;
01067 }
01068 }  // namespace generic_control_toolbox


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57