kdl_manager.cpp
Go to the documentation of this file.
2 
4 {
5 KDLManager::KDLManager(const std::string &chain_base_link, ros::NodeHandle nh)
6  : chain_base_link_(chain_base_link), nh_(nh)
7 {
8  if (!model_.initParam("/robot_description"))
9  {
10  throw std::runtime_error(
11  "ERROR getting robot description (/robot_description)");
12  }
13 
14  getParam();
15 }
16 
18 
20 {
21  if (!nh_.getParam("kdl_manager/eps", eps_))
22  {
23  ROS_WARN("KDLManager: Missing eps parameter, setting default");
24  eps_ = 0.001;
25  }
26 
27  if (!nh_.getParam("kdl_manager/max_tf_attempts", max_tf_attempts_))
28  {
29  ROS_WARN("KDLManager: Missing max_tf_attempts parameter, setting default");
30  max_tf_attempts_ = 5;
31  }
32 
33  if (!nh_.getParam("kdl_manager/ikvel_solver", ikvel_solver_))
34  {
35  ROS_WARN("KDLManager: Missing ikvel_solver parameter, setting default");
37  }
38 
39  if (!nh_.getParam("kdl_manager/ik_angle_tolerance", ik_angle_tolerance_))
40  {
41  ROS_WARN(
42  "KDLManager: Missing ik_angle_tolerance parameter, setting default");
43  ik_angle_tolerance_ = 0.01;
44  }
45 
46  if (!nh_.getParam("kdl_manager/ik_pos_tolerance", ik_pos_tolerance_))
47  {
48  ROS_WARN("KDLManager: Missing ik_pos_tolerance parameter, setting default");
49  ik_pos_tolerance_ = 0.005;
50  }
51 
53  {
54  ROS_ERROR_STREAM("KDLManager: ikvel_solver has value "
55  << ikvel_solver_ << "but admissible values are "
56  << WDLS_SOLVER << " and " << NSO_SOLVER);
57  ROS_WARN_STREAM("KDLManager: setting ikvel_solver to " << WDLS_SOLVER);
59  }
60 
62  {
63  if (!nh_.getParam("kdl_manager/nso_weight", nso_weight_))
64  {
65  ROS_WARN("KDLManager: Missing nso_weight parameter, setting default");
66  nso_weight_ = 4;
67  }
68  }
69 
70  std::vector<double> gravity;
71  if (!nh_.getParam("kdl_manager/gravity_in_base_link", gravity))
72  {
74  "KDLManager: Missing kdl_manager/gravity_in_base_link parameter. This "
75  "will affect the dynamic solvers");
77  }
78  else
79  {
80  if (gravity.size() != 3)
81  {
82  ROS_WARN_STREAM("KDLManager: Got gravity vector of size "
83  << gravity.size() << ". Should have size 3");
85  }
86  else
87  {
89  KDL::Vector(gravity[0], gravity[1], gravity[2]);
90  }
91  }
92 
93  return true;
94 }
95 
96 bool KDLManager::initializeArm(const std::string &end_effector_link)
97 {
98  if (!initializeArmCommon(end_effector_link))
99  {
100  return false;
101  }
102 
103  if (chain_.find(end_effector_link) == chain_.end())
104  {
105  return false;
106  }
107 
108  if (ikvel_solver_ == WDLS_SOLVER)
109  {
110  ikvel_[end_effector_link] = IkSolverVelPtr(
111  new KDL::ChainIkSolverVel_wdls(chain_.at(end_effector_link), eps_));
112  }
113  else
114  {
115  unsigned int joint_n = chain_.at(end_effector_link).getNrOfJoints();
116 
117  if (joint_n < 6)
118  {
119  ROS_WARN(
120  "Number of joints for kinematic chain is smaller than 6 (%d). The "
121  "NSO ik solver vel has issues with under-actuated chains. Using WDLS",
122  joint_n);
123  ikvel_[end_effector_link] = IkSolverVelPtr(
124  new KDL::ChainIkSolverVel_wdls(chain_.at(end_effector_link), eps_));
125  }
126  else
127  {
128  KDL::JntArray w(joint_n), q_min(joint_n), q_max(joint_n),
129  q_vel_lim(joint_n), q_desired(joint_n);
130  getJointLimits(end_effector_link, q_min, q_max, q_vel_lim);
131 
132  for (unsigned int i = 0; i < joint_n; i++)
133  {
134  w(i) = nso_weight_;
135  q_desired(i) = (q_max(i) + q_min(i)) / 2;
136  }
137 
138  ikvel_[end_effector_link] =
140  chain_.at(end_effector_link), q_desired, w, eps_));
141  }
142  }
143 
144  return true;
145 }
146 
147 bool KDLManager::isInitialized(const std::string &end_effector_link) const
148 {
149  return (chain_.find(end_effector_link) != chain_.end());
150 }
151 
152 bool KDLManager::initializeArmCommon(const std::string &end_effector_link)
153 {
154  if (chain_.find(end_effector_link) != chain_.end())
155  {
156  ROS_ERROR_STREAM("Tried to initialize arm "
157  << end_effector_link
158  << ", but it was already initialized");
159  return false;
160  }
161 
162  KDL::Tree tree;
163  KDL::Joint kdl_joint;
164  KDL::Chain chain;
166  model_, tree); // convert URDF description of the robot into a KDL tree
167  if (!tree.getChain(chain_base_link_, end_effector_link, chain))
168  {
169  ROS_ERROR_STREAM("Failed to find chain <" << chain_base_link_ << ", "
170  << end_effector_link
171  << "> in the kinematic tree");
172  return false;
173  }
174 
175  // Ready to accept the end-effector as valid
176  chain_[end_effector_link] = chain;
177  dynamic_chain_[end_effector_link] = ChainDynParamPtr(new KDL::ChainDynParam(
178  chain_.at(end_effector_link), gravity_in_chain_base_link_));
179  std::vector<std::string> new_vector;
180 
181  ROS_DEBUG_STREAM("Initializing chain for arm " << end_effector_link);
182  for (unsigned int i = 0; i < chain.getNrOfSegments();
183  i++) // check for non-movable joints
184  {
185  kdl_joint = chain.getSegment(i).getJoint();
186 
187  if (kdl_joint.getTypeName() == "None")
188  {
189  continue;
190  }
191 
192  ROS_DEBUG_STREAM(kdl_joint.getName());
193  new_vector.push_back(kdl_joint.getName());
194  }
195 
196  actuated_joint_names_[end_effector_link] = new_vector;
197 
198  // Initialize solvers
199  fkpos_[end_effector_link] =
200  FkSolverPosPtr(new FkSolverPos(chain_.at(end_effector_link)));
201  fkvel_[end_effector_link] =
202  FkSolverVelPtr(new FkSolverVel(chain_.at(end_effector_link)));
203  ikpos_[end_effector_link] =
204  IkSolverPosPtr(new IkSolverPos(chain_.at(end_effector_link)));
205  jac_solver_[end_effector_link] =
206  JacSolverPtr(new JacSolver(chain_.at(end_effector_link)));
207  eef_to_gripping_point_[end_effector_link] =
208  KDL::Frame::Identity(); // Initialize a neutral transform.
209  eef_to_sensor_point_[end_effector_link] =
210  KDL::Frame::Identity(); // Initialize a neutral transform.
211 
212  return true;
213 }
214 
215 bool KDLManager::setGrippingPoint(const std::string &end_effector_link,
216  const std::string &gripping_point_frame)
217 {
218  if (chain_.find(end_effector_link) == chain_.end())
219  {
220  return false;
221  }
222 
223  KDL::Frame eef_to_gripping_point;
224 
225  if (!getRigidTransform(end_effector_link, gripping_point_frame,
226  eef_to_gripping_point))
227  {
228  return false;
229  }
230 
231  eef_to_gripping_point_.at(end_effector_link) =
232  eef_to_gripping_point.Inverse();
233  return true;
234 }
235 
236 bool KDLManager::setSensorPoint(const std::string &end_effector_link,
237  const std::string &sensor_point_frame)
238 {
239  if (chain_.find(end_effector_link) == chain_.end())
240  {
241  return false;
242  }
243 
244  KDL::Frame eef_to_sensor_point;
245 
246  if (!getRigidTransform(end_effector_link, sensor_point_frame,
247  eef_to_sensor_point))
248  {
249  return false;
250  }
251 
252  eef_to_sensor_point_.at(end_effector_link) = eef_to_sensor_point;
253  return true;
254 }
255 
256 bool KDLManager::getJointState(const std::string &end_effector_link,
257  const Eigen::VectorXd &qdot,
258  sensor_msgs::JointState &state) const
259 {
260  if (chain_.find(end_effector_link) == chain_.end())
261  {
262  return false;
263  }
264 
265  if (chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
266  {
267  ROS_ERROR(
268  "Joint chain for eef %s has a different number of joints than the "
269  "provided",
270  end_effector_link.c_str());
271  return false;
272  }
273 
274  Eigen::VectorXd q(chain_.at(end_effector_link).getNrOfJoints());
275  int joint_index = 0;
276 
277  for (unsigned long i = 0; i < state.name.size(); i++)
278  {
279  if (hasJoint(chain_.at(end_effector_link), state.name[i]))
280  {
281  q[joint_index] = state.position[i];
282  joint_index++;
283  }
284 
285  if (joint_index == chain_.at(end_effector_link).getNrOfJoints())
286  {
287  break;
288  }
289  }
290 
291  if (joint_index != chain_.at(end_effector_link).getNrOfJoints())
292  {
293  ROS_ERROR(
294  "Provided joint state does not have all of the required chain joints");
295  return false;
296  }
297 
298  return getJointState(end_effector_link, q, qdot, state);
299 }
300 
301 bool KDLManager::getJointState(const std::string &end_effector_link,
302  const Eigen::VectorXd &q,
303  const Eigen::VectorXd &qdot,
304  sensor_msgs::JointState &state) const
305 {
306  if (q.rows() != qdot.rows())
307  {
308  ROS_ERROR(
309  "Given joint state with a different number of joint positions and "
310  "velocities");
311  return false;
312  }
313 
314  if (chain_.find(end_effector_link) == chain_.end())
315  {
316  return false;
317  }
318 
319  if (chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
320  {
321  ROS_ERROR(
322  "Joint chain for eef %s has a different number of joints than the "
323  "provided",
324  end_effector_link.c_str());
325  return false;
326  }
327 
328  bool found;
329 
330  for (unsigned long i = 0;
331  i < actuated_joint_names_.at(end_effector_link).size(); i++)
332  {
333  found = false;
334  for (unsigned long j = 0; j < state.name.size(); j++)
335  {
336  if (state.name[j] == actuated_joint_names_.at(end_effector_link)[i])
337  {
338  state.position[j] = q[i];
339  state.velocity[j] = qdot[i];
340  found = true;
341  break;
342  }
343  }
344 
345  if (!found)
346  {
347  ROS_ERROR_STREAM("KDLManager: Missing joint "
348  << actuated_joint_names_.at(end_effector_link)[i]
349  << " from given joint state");
350  return false;
351  }
352  }
353 
354  return true;
355 }
356 
357 bool KDLManager::getJointState(const std::string &end_effector_link,
358  const Eigen::VectorXd &q,
359  const Eigen::VectorXd &qdot,
360  const Eigen::VectorXd &effort,
361  sensor_msgs::JointState &state) const
362 {
363  if (!getJointState(end_effector_link, q, qdot, state))
364  {
365  return false;
366  }
367 
368  if (chain_.find(end_effector_link) == chain_.end())
369  {
370  return false;
371  }
372 
373  if (chain_.at(end_effector_link).getNrOfJoints() != effort.rows())
374  {
375  ROS_ERROR_STREAM("Joint chain for eef "
376  << end_effector_link
377  << " has a different number of joints than the provided");
378  return false;
379  }
380 
381  bool found;
382  for (unsigned long i = 0;
383  i < actuated_joint_names_.at(end_effector_link).size(); i++)
384  {
385  found = false;
386  for (unsigned long j = 0; j < state.name.size(); j++)
387  {
388  if (state.name[j] == actuated_joint_names_.at(end_effector_link)[i])
389  {
390  state.effort[j] = effort[i];
391  found = true;
392  break;
393  }
394  }
395 
396  if (!found)
397  {
398  ROS_ERROR_STREAM("KDLManager: Missing joint "
399  << actuated_joint_names_.at(end_effector_link)[i]
400  << " from given joint state");
401  return false;
402  }
403  }
404 
405  return true;
406 }
407 
408 bool KDLManager::getGrippingPoint(const std::string &end_effector_link,
409  const sensor_msgs::JointState &state,
410  KDL::Frame &out) const
411 {
412  if (chain_.find(end_effector_link) == chain_.end())
413  {
414  return false;
415  }
416 
417  KDL::Frame eef_pose;
418  if (!getEefPose(end_effector_link, state, eef_pose))
419  {
420  return false;
421  }
422 
423  out = eef_pose * eef_to_gripping_point_.at(end_effector_link);
424  return true;
425 }
426 
427 bool KDLManager::getSensorPoint(const std::string &end_effector_link,
428  const sensor_msgs::JointState &state,
429  KDL::Frame &out) const
430 {
431  if (chain_.find(end_effector_link) == chain_.end())
432  {
433  return false;
434  }
435 
436  KDL::Frame eef_pose;
437  if (!getEefPose(end_effector_link, state, eef_pose))
438  {
439  return false;
440  }
441 
442  out = eef_pose * eef_to_sensor_point_.at(end_effector_link);
443  return true;
444 }
445 
446 bool KDLManager::getGrippingTwist(const std::string &end_effector_link,
447  const sensor_msgs::JointState &state,
448  KDL::Twist &out) const
449 {
450  if (chain_.find(end_effector_link) == chain_.end())
451  {
452  return false;
453  }
454 
455  KDL::Frame gripping_pose;
456  if (!getGrippingPoint(end_effector_link, state, gripping_pose))
457  {
458  return false;
459  }
460 
461  KDL::Frame eef_pose;
462  if (!getEefPose(end_effector_link, state, eef_pose))
463  {
464  return false;
465  }
466 
467  KDL::FrameVel eef_twist;
468  if (!getEefTwist(end_effector_link, state, eef_twist))
469  {
470  return false;
471  }
472 
473  Eigen::Vector3d vel_eig, rot_eig, converted_vel, r_eig;
474  KDL::Vector r = gripping_pose.p - eef_pose.p;
475 
476  vel_eig << eef_twist.GetTwist().vel.data[0], eef_twist.GetTwist().vel.data[1],
477  eef_twist.GetTwist().vel.data[2];
478  rot_eig << eef_twist.GetTwist().rot.data[0], eef_twist.GetTwist().rot.data[1],
479  eef_twist.GetTwist().rot.data[2];
480  r_eig << r.data[0], r.data[1], r.data[2];
481 
482  converted_vel = vel_eig - MatrixParser::computeSkewSymmetric(r_eig) * rot_eig;
483  out.vel = KDL::Vector(converted_vel[0], converted_vel[1], converted_vel[2]);
484  out.rot = eef_twist.GetTwist().rot;
485 
486  return true;
487 }
488 
489 bool KDLManager::getEefPose(const std::string &end_effector_link,
490  const sensor_msgs::JointState &state,
491  KDL::Frame &out) const
492 {
493  if (chain_.find(end_effector_link) == chain_.end())
494  {
495  return false;
496  }
497 
498  KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
499  KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
500 
501  if (!getChainJointState(state, end_effector_link, positions, velocities))
502  {
503  return false;
504  }
505 
506  fkpos_.at(end_effector_link)->JntToCart(positions, out);
507  return true;
508 }
509 
510 bool KDLManager::getEefTwist(const std::string &end_effector_link,
511  const sensor_msgs::JointState &state,
512  KDL::FrameVel &out) const
513 {
514  if (chain_.find(end_effector_link) == chain_.end())
515  {
516  return false;
517  }
518 
519  KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
520  KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
521  if (!getChainJointState(state, end_effector_link, positions, velocities))
522  {
523  return false;
524  }
525 
526  fkvel_.at(end_effector_link)->JntToCart(velocities, out);
527  return true;
528 }
529 
530 bool KDLManager::getJointLimits(const std::string &end_effector_link,
531  KDL::JntArray &q_min, KDL::JntArray &q_max,
532  KDL::JntArray &q_vel_lim) const
533 {
534  if (chain_.find(end_effector_link) == chain_.end())
535  {
536  return false;
537  }
538 
539  unsigned int joint_n = chain_.at(end_effector_link).getNrOfJoints();
540  if (q_min.rows() != joint_n || q_max.rows() != joint_n ||
541  q_vel_lim.rows() != joint_n)
542  {
543  ROS_ERROR(
544  "KDLManager::getJointPositionLimits requires initialized joint arrays");
545  return false;
546  }
547 
548  urdf::JointConstSharedPtr joint;
549  urdf::JointLimitsSharedPtr limits;
550  int j = 0;
551  // run through the kinematic chain joints and get the limits from the urdf
552  // model
553  for (unsigned int i = 0; i < chain_.at(end_effector_link).getNrOfSegments();
554  i++)
555  {
556  if (chain_.at(end_effector_link).getSegment(i).getJoint().getType() ==
557  KDL::Joint::JointType::None)
558  {
559  continue;
560  }
561 
562  joint = model_.getJoint(
563  chain_.at(end_effector_link).getSegment(i).getJoint().getName());
564  limits = joint->limits;
565  q_min(j) = limits->lower;
566  q_max(j) = limits->upper;
567  q_vel_lim(j) = limits->velocity;
568  j++;
569  }
570 
571  return true;
572 }
573 
574 bool KDLManager::getJointPositions(const std::string &end_effector_link,
575  const sensor_msgs::JointState &state,
576  KDL::JntArray &q) const
577 {
578  if (chain_.find(end_effector_link) == chain_.end())
579  {
580  return false;
581  }
582 
583  q.resize(chain_.at(end_effector_link).getNrOfJoints());
584  KDL::JntArrayVel v(q.rows());
585  if (!getChainJointState(state, end_effector_link, q, v))
586  {
587  return false;
588  }
589 
590  return true;
591 }
592 
593 bool KDLManager::getJointPositions(const std::string &end_effector_link,
594  const sensor_msgs::JointState &state,
595  Eigen::VectorXd &q) const
596 {
597  if (chain_.find(end_effector_link) == chain_.end())
598  {
599  return false;
600  }
601 
602  KDL::JntArray q_kdl;
603 
604  if (!getJointPositions(end_effector_link, state, q_kdl))
605  {
606  return false;
607  }
608 
609  q = q_kdl.data;
610  return true;
611 }
612 
613 bool KDLManager::getJointVelocities(const std::string &end_effector_link,
614  const sensor_msgs::JointState &state,
615  KDL::JntArray &q_dot) const
616 {
617  if (chain_.find(end_effector_link) == chain_.end())
618  {
619  return false;
620  }
621 
622  q_dot.resize(chain_.at(end_effector_link).getNrOfJoints());
623  KDL::JntArray q(q_dot.rows());
624  KDL::JntArrayVel v(q_dot.rows());
625  if (!getChainJointState(state, end_effector_link, q, v))
626  {
627  return false;
628  }
629 
630  q_dot = v.qdot;
631  return true;
632 }
633 
634 bool KDLManager::getInertia(const std::string &end_effector_link,
635  const sensor_msgs::JointState &state,
636  Eigen::MatrixXd &H)
637 {
638  if (chain_.find(end_effector_link) == chain_.end())
639  {
640  return false;
641  }
642 
643  KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
644  KDL::JntSpaceInertiaMatrix B(chain_.at(end_effector_link).getNrOfJoints());
645  dynamic_chain_.at(end_effector_link)->JntToMass(q, B);
646 
647  H = B.data;
648  return true;
649 }
650 
651 bool KDLManager::getGravity(const std::string &end_effector_link,
652  const sensor_msgs::JointState &state,
653  Eigen::MatrixXd &g)
654 {
655  if (chain_.find(end_effector_link) == chain_.end())
656  {
657  return false;
658  }
659 
660  KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
661  KDL::JntArrayVel q_dot(chain_.at(end_effector_link).getNrOfJoints());
662  if (!getChainJointState(state, end_effector_link, q, q_dot))
663  {
664  return false;
665  }
666 
667  KDL::JntArray q_gravity(chain_.at(end_effector_link).getNrOfJoints());
668  dynamic_chain_.at(end_effector_link)->JntToGravity(q, q_gravity);
669 
670  g = q_gravity.data;
671 
672  return true;
673 }
674 
675 bool KDLManager::getCoriolis(const std::string &end_effector_link,
676  const sensor_msgs::JointState &state,
677  Eigen::MatrixXd &coriolis)
678 {
679  if (chain_.find(end_effector_link) == chain_.end())
680  {
681  return false;
682  }
683 
684  KDL::JntArray q(chain_.at(end_effector_link).getNrOfJoints());
685  KDL::JntArrayVel q_dot(chain_.at(end_effector_link).getNrOfJoints());
686  if (!getChainJointState(state, end_effector_link, q, q_dot))
687  {
688  return false;
689  }
690 
691  KDL::JntArray cor(chain_.at(end_effector_link).getNrOfJoints());
692  dynamic_chain_.at(end_effector_link)->JntToCoriolis(q, q_dot.qdot, cor);
693  coriolis = cor.data;
694  return true;
695 }
696 
697 bool KDLManager::getRigidTransform(const std::string &base_frame,
698  const std::string &target_frame,
699  KDL::Frame &out) const
700 {
701  geometry_msgs::PoseStamped base_to_target;
702  base_to_target.header.frame_id = base_frame;
703  base_to_target.header.stamp = ros::Time(0);
704  base_to_target.pose.position.x = 0;
705  base_to_target.pose.position.y = 0;
706  base_to_target.pose.position.z = 0;
707  base_to_target.pose.orientation.x = 0;
708  base_to_target.pose.orientation.y = 0;
709  base_to_target.pose.orientation.z = 0;
710  base_to_target.pose.orientation.w = 1;
711 
712  int attempts;
713  for (attempts = 0; attempts < max_tf_attempts_; attempts++)
714  {
715  try
716  {
717  listener_.transformPose(target_frame, base_to_target, base_to_target);
718  break;
719  }
720  catch (tf::TransformException ex)
721  {
722  ROS_WARN("TF exception in kdl manager: %s", ex.what());
723  ros::Duration(0.1).sleep();
724  }
725  }
726 
727  if (attempts >= max_tf_attempts_)
728  {
729  ROS_ERROR(
730  "KDL manager could not find the transform between frames %s and %s",
731  base_frame.c_str(), target_frame.c_str());
732  return false;
733  }
734 
735  tf::poseMsgToKDL(base_to_target.pose, out);
736  return true;
737 }
738 
739 bool KDLManager::verifyPose(const std::string &end_effector_link,
740  const KDL::Frame &in) const
741 {
742  if (chain_.find(end_effector_link) == chain_.end())
743  {
744  return false;
745  }
746 
747  sensor_msgs::JointState dummy_state;
748 
749  for (unsigned int i = 0;
750  i < actuated_joint_names_.at(end_effector_link).size(); i++)
751  {
752  dummy_state.name.push_back(actuated_joint_names_.at(end_effector_link)[i]);
753  dummy_state.position.push_back(0);
754  dummy_state.velocity.push_back(0);
755  dummy_state.effort.push_back(0);
756  }
757 
758  KDL::JntArray dummy_out(dummy_state.name.size());
759  if (getPoseIK(end_effector_link, dummy_state, in, dummy_out))
760  {
761  return true;
762  }
763 
764  return false;
765 }
766 
767 bool KDLManager::getPoseIK(const std::string &end_effector_link,
768  const sensor_msgs::JointState &state,
769  const KDL::Frame &in, KDL::JntArray &out) const
770 {
771  if (chain_.find(end_effector_link) == chain_.end())
772  {
773  return false;
774  }
775 
776  KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
777  KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
778  KDL::Frame computedPose, difference;
779  if (!getChainJointState(state, end_effector_link, positions, velocities))
780  {
781  return false;
782  }
783 
784  out.resize(chain_.at(end_effector_link).getNrOfJoints());
785  ikpos_.at(end_effector_link)->CartToJnt(positions, in, out);
786  getPoseFK(end_effector_link, state, out,
787  computedPose); // verify if the forward kinematics of the computed
788  // solution are close to the desired pose
789 
790  difference = computedPose.Inverse() * in;
791  Eigen::Vector3d quat_v;
792  double quat_w;
793 
794  difference.M.GetQuaternion(quat_v[0], quat_v[1], quat_v[2], quat_w);
795  double angle = 2 * atan2(quat_v.norm(), quat_w);
796 
797  if (fabs(angle) > ik_angle_tolerance_)
798  {
799  ROS_ERROR(
800  "KDL manager could not compute pose ik for end-effector %s. Final "
801  "orientation error was %.2f",
802  end_effector_link.c_str(), angle);
803  return false;
804  }
805 
806  if (fabs(difference.p.Norm()) > ik_pos_tolerance_)
807  {
808  ROS_ERROR(
809  "KDL manager could not compute pose ik for end-effector %s. Final "
810  "position error was %.2f",
811  end_effector_link.c_str(), difference.p.Norm());
812  return false;
813  }
814 
815  return true;
816 }
817 
818 bool KDLManager::getGrippingPoseIK(const std::string &end_effector_link,
819  const sensor_msgs::JointState &state,
820  const KDL::Frame &in,
821  KDL::JntArray &out) const
822 {
823  if (chain_.find(end_effector_link) == chain_.end())
824  {
825  return false;
826  }
827 
828  KDL::Frame pose_in_eef =
829  in * eef_to_gripping_point_.at(end_effector_link).Inverse();
830 
831  return getPoseIK(end_effector_link, state, pose_in_eef, out);
832 }
833 
834 bool KDLManager::getPoseFK(const std::string &end_effector_link,
835  const sensor_msgs::JointState &state,
836  const KDL::JntArray &in, KDL::Frame &out) const
837 {
838  if (chain_.find(end_effector_link) == chain_.end())
839  {
840  return false;
841  }
842 
843  fkpos_.at(end_effector_link)->JntToCart(in, out);
844  return true;
845 }
846 
847 bool KDLManager::getGrippingVelIK(const std::string &end_effector_link,
848  const sensor_msgs::JointState &state,
849  const KDL::Twist &in,
850  KDL::JntArray &out) const
851 {
852  KDL::Frame pgrip, peef;
853  KDL::Twist modified_in, rotated_in;
854 
855  if (chain_.find(end_effector_link) == chain_.end())
856  {
857  return false;
858  }
859 
860  if (!getGrippingPoint(end_effector_link, state, pgrip))
861  {
862  return false;
863  }
864 
865  if (!getEefPose(end_effector_link, state, peef))
866  {
867  return false;
868  }
869 
870  // convert the input twist (in the gripping frame) to the base frame
871  Eigen::Vector3d vel_eig, rot_eig, peef_eig, pgrip_eig;
872  modified_in = pgrip.M * in;
873 
874  tf::vectorKDLToEigen(peef.p, peef_eig);
875  tf::vectorKDLToEigen(pgrip.p, pgrip_eig);
876  tf::vectorKDLToEigen(modified_in.vel, vel_eig);
877  tf::vectorKDLToEigen(modified_in.rot, rot_eig);
878 
879  vel_eig = MatrixParser::computeSkewSymmetric(pgrip_eig - peef_eig) * rot_eig +
880  vel_eig;
881 
882  tf::vectorEigenToKDL(vel_eig, modified_in.vel);
883 
884  if (!getVelIK(end_effector_link, state, modified_in, out))
885  {
886  return false;
887  }
888 
889  return true;
890 }
891 
892 bool KDLManager::getVelIK(const std::string &end_effector_link,
893  const sensor_msgs::JointState &state,
894  const KDL::Twist &in, KDL::JntArray &out) const
895 {
896  if (chain_.find(end_effector_link) == chain_.end())
897  {
898  return false;
899  }
900 
901  KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
902  KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
903  if (!getChainJointState(state, end_effector_link, positions, velocities))
904  {
905  return false;
906  }
907 
908  out.resize(chain_.at(end_effector_link).getNrOfJoints());
909  ikvel_.at(end_effector_link)->CartToJnt(positions, in, out);
910  return true;
911 }
912 
913 bool KDLManager::getJacobian(const std::string &end_effector_link,
914  const sensor_msgs::JointState &state,
915  KDL::Jacobian &out) const
916 {
917  if (chain_.find(end_effector_link) == chain_.end())
918  {
919  return false;
920  }
921 
922  KDL::JntArray positions(chain_.at(end_effector_link).getNrOfJoints());
923  KDL::JntArrayVel velocities(chain_.at(end_effector_link).getNrOfJoints());
924  if (!getChainJointState(state, end_effector_link, positions, velocities))
925  {
926  return false;
927  }
928 
929  out.resize(positions.rows());
930  jac_solver_.at(end_effector_link)->JntToJac(positions, out);
931  return true;
932 }
933 
934 bool KDLManager::checkStateMessage(const std::string &end_effector_link,
935  const sensor_msgs::JointState &state) const
936 {
937  if (chain_.find(end_effector_link) == chain_.end())
938  {
939  return false;
940  }
941 
942  unsigned int processed_joints = 0, name_size, pos_size, vel_size;
943  name_size = state.name.size();
944  pos_size = state.position.size();
945  vel_size = state.velocity.size();
946 
947  if (name_size != pos_size || name_size != vel_size)
948  {
949  ROS_ERROR(
950  "Got joint state where the name, position and velocity dimensions "
951  "(resp. %d, %d, %d) are different",
952  name_size, pos_size, vel_size);
953  return false;
954  }
955 
956  for (unsigned long i = 0;
957  i < actuated_joint_names_.at(end_effector_link).size(); i++)
958  {
959  for (unsigned long j = 0; j < state.name.size(); j++)
960  {
961  if (actuated_joint_names_.at(end_effector_link)[i] == state.name[j])
962  {
963  processed_joints++;
964  }
965  }
966  }
967 
968  if (processed_joints != actuated_joint_names_.at(end_effector_link).size())
969  {
970  return false;
971  }
972 
973  return true;
974 }
975 
977  const sensor_msgs::JointState &current_state,
978  const std::string &end_effector_link, KDL::JntArray &positions,
979  KDL::JntArrayVel &velocities) const
980 {
981  unsigned int processed_joints = 0;
982  unsigned int name_size, pos_size, vel_size;
983 
984  name_size = current_state.name.size();
985  pos_size = current_state.position.size();
986  vel_size = current_state.velocity.size();
987 
988  if (name_size != pos_size || name_size != vel_size)
989  {
990  ROS_ERROR(
991  "Got joint state where the name, position and velocity dimensions "
992  "(resp. %d, %d, %d) are different",
993  name_size, pos_size, vel_size);
994  return false;
995  }
996 
997  for (unsigned long i = 0;
998  i < actuated_joint_names_.at(end_effector_link).size(); i++)
999  {
1000  for (unsigned long j = 0; j < current_state.name.size(); j++)
1001  {
1002  if (actuated_joint_names_.at(end_effector_link)[i] ==
1003  current_state.name[j])
1004  {
1005  positions(processed_joints) = current_state.position[j];
1006  velocities.q(processed_joints) = current_state.position[j];
1007  velocities.qdot(processed_joints) = current_state.velocity[j];
1008  processed_joints++;
1009  }
1010  }
1011  }
1012 
1013  if (processed_joints != actuated_joint_names_.at(end_effector_link).size())
1014  {
1015  ROS_ERROR("Failed to acquire chain joint state");
1016  return false;
1017  }
1018 
1019  return true;
1020 }
1021 
1023  const std::string &joint_name) const
1024 {
1025  for (unsigned int i = 0; i < chain.getNrOfSegments(); i++)
1026  {
1027  if (chain.segments[i].getJoint().getName() == joint_name)
1028  {
1029  return true;
1030  }
1031  }
1032 
1033  return false;
1034 }
1035 
1036 bool KDLManager::getNumJoints(const std::string &end_effector_link,
1037  unsigned int &num_joints) const
1038 {
1039  if (chain_.find(end_effector_link) == chain_.end())
1040  {
1041  return false;
1042  }
1043 
1044  num_joints = chain_.at(end_effector_link).getNrOfJoints();
1045  return true;
1046 }
1047 
1048 bool setKDLManager(const ArmInfo &arm_info, std::shared_ptr<KDLManager> manager)
1049 {
1050  if (!manager->initializeArm(arm_info.kdl_eef_frame))
1051  {
1052  return false;
1053  }
1054 
1055  if (!manager->setGrippingPoint(arm_info.kdl_eef_frame,
1056  arm_info.gripping_frame))
1057  {
1058  return false;
1059  }
1060 
1061  ROS_DEBUG(
1062  "Successfully set up arm %s with eef_frame %s and gripping_frame %s",
1063  arm_info.name.c_str(), arm_info.kdl_eef_frame.c_str(),
1064  arm_info.gripping_frame.c_str());
1065 
1066  return true;
1067 }
1068 } // namespace generic_control_toolbox
bool getJointPositions(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q) const
bool getEefPose(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
bool initializeArm(const std::string &end_effector_link)
Definition: kdl_manager.cpp:96
static Eigen::Matrix3d computeSkewSymmetric(const Eigen::Vector3d &v)
bool getJointLimits(const std::string &end_effector_link, KDL::JntArray &q_min, KDL::JntArray &q_max, KDL::JntArray &q_vel_lim) const
const Segment & getSegment(unsigned int nr) const
const std::string WDLS_SOLVER("wdls")
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
unsigned int rows() const
void resize(unsigned int newNrOfColumns)
bool getPoseIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Frame &in, KDL::JntArray &out) const
const std::string NSO_SOLVER("nso")
Vector vel
std::map< std::string, IkSolverPosPtr > ikpos_
bool sleep() const
std::map< std::string, FkSolverPosPtr > fkpos_
unsigned int getNrOfSegments() const
IMETHOD Twist GetTwist() const
bool hasJoint(const KDL::Chain &chain, const std::string &joint_name) const
bool initializeArmCommon(const std::string &end_effector_link)
std::map< std::string, JacSolverPtr > jac_solver_
bool getSensorPoint(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
#define ROS_WARN(...)
std::map< std::string, KDL::Chain > chain_
bool getChainJointState(const sensor_msgs::JointState &current_state, const std::string &end_effector_link, KDL::JntArray &positions, KDL::JntArrayVel &velocities) const
std::map< std::string, ChainDynParamPtr > dynamic_chain_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::string chain_base_link_
list of actuated joints per arm
std::map< std::string, KDL::Frame > eef_to_sensor_point_
bool getNumJoints(const std::string &end_effector_link, unsigned int &num_joints) const
Rotation M
void GetQuaternion(double &x, double &y, double &z, double &w) const
KDL::ChainFkSolverPos_recursive FkSolverPos
std::shared_ptr< IkSolverPos > IkSolverPosPtr
std::shared_ptr< FkSolverVel > FkSolverVelPtr
const std::string & getName() const
KDLManager(const std::string &chain_base_link, ros::NodeHandle nh=ros::NodeHandle("~"))
Definition: kdl_manager.cpp:5
bool getJointState(const std::string &end_effector_link, const Eigen::VectorXd &qdot, sensor_msgs::JointState &state) const
Vector rot
bool getRigidTransform(const std::string &base_frame, const std::string &target_frame, KDL::Frame &out) const
std::map< std::string, IkSolverVelPtr > ikvel_
double data[3]
Eigen::VectorXd data
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
const Joint & getJoint() const
bool getGrippingPoint(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
bool getGrippingPoseIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Frame &in, KDL::JntArray &out) const
URDF_EXPORT bool initParam(const std::string &param)
void vectorEigenToKDL(const Eigen::Matrix< double, 3, 1 > &e, KDL::Vector &k)
bool getEefTwist(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::FrameVel &out) const
Frame Inverse() const
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::shared_ptr< JacSolver > JacSolverPtr
KDL::ChainFkSolverVel_recursive FkSolverVel
bool setSensorPoint(const std::string &end_effector_link, const std::string &sensor_point_frame)
std::shared_ptr< KDL::ChainDynParam > ChainDynParamPtr
KDL::ChainJntToJacSolver JacSolver
bool getCoriolis(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &coriolis)
bool getInertia(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &H)
void resize(unsigned int newSize)
TFSIMD_FORCE_INLINE const tfScalar & w() const
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
bool getGrippingTwist(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Twist &out) const
std::map< std::string, std::vector< std::string > > actuated_joint_names_
bool getJointVelocities(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q_dot) const
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
void vectorKDLToEigen(const KDL::Vector &k, Eigen::Matrix< double, 3, 1 > &e)
static Frame Identity()
bool getParam(const std::string &key, std::string &s) const
std::vector< Segment > segments
bool setKDLManager(const ArmInfo &arm_info, std::shared_ptr< KDLManager > manager)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
bool setGrippingPoint(const std::string &end_effector_link, const std::string &gripping_point_frame)
const std::string getTypeName() const
bool getPoseFK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::JntArray &in, KDL::Frame &out) const
bool getJacobian(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Jacobian &out) const
#define ROS_ERROR_STREAM(args)
std::shared_ptr< FkSolverPos > FkSolverPosPtr
std::map< std::string, KDL::Frame > eef_to_gripping_point_
KDL::ChainIkSolverPos_LMA IkSolverPos
#define ROS_ERROR(...)
bool checkStateMessage(const std::string &end_effector_link, const sensor_msgs::JointState &state) const
std::map< std::string, FkSolverVelPtr > fkvel_
bool getVelIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const
std::shared_ptr< IkSolverVel > IkSolverVelPtr
bool getGravity(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &g)
bool isInitialized(const std::string &end_effector_link) const
bool verifyPose(const std::string &end_effector_link, const KDL::Frame &in) const
bool getGrippingVelIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const
#define ROS_DEBUG(...)


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44