moveit2
The MoveIt Motion Planning Framework for ROS 2.
kdl_kinematics_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */
36 
39 
40 #include <tf2_kdl/tf2_kdl.hpp>
41 // TODO: Remove conditional include when released to all active distros.
42 #if __has_include(<tf2/transform_datatypes.hpp>)
43 #include <tf2/transform_datatypes.hpp>
44 #else
45 #include <tf2/transform_datatypes.h>
46 #endif
47 
48 #include <kdl_parser/kdl_parser.hpp>
49 #include <kdl/chainfksolverpos_recursive.hpp>
50 #include <kdl/frames_io.hpp>
51 #include <kdl/kinfam_io.hpp>
52 
53 namespace kdl_kinematics_plugin
54 {
55 static rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kdl_kinematics_plugin.kdl_kinematics_plugin");
56 
57 rclcpp::Clock KDLKinematicsPlugin::steady_clock_{ RCL_STEADY_TIME };
58 
60 {
61 }
62 
63 void KDLKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array) const
64 {
65  state_->setToRandomPositions(joint_model_group_);
66  state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
67 }
68 
69 void KDLKinematicsPlugin::getRandomConfiguration(const Eigen::VectorXd& seed_state,
70  const std::vector<double>& consistency_limits,
71  Eigen::VectorXd& jnt_array) const
72 {
73  joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), &jnt_array[0],
74  &seed_state[0], consistency_limits);
75 }
76 
77 bool KDLKinematicsPlugin::checkConsistency(const Eigen::VectorXd& seed_state,
78  const std::vector<double>& consistency_limits,
79  const Eigen::VectorXd& solution) const
80 {
81  for (std::size_t i = 0; i < dimension_; ++i)
82  if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
83  return false;
84  return true;
85 }
86 
87 void KDLKinematicsPlugin::getJointWeights()
88 {
89  const std::vector<std::string>& active_names = joint_model_group_->getActiveJointModelNames();
90  std::vector<std::string> names;
91  std::vector<double> weights;
92  if (lookupParam(node_, "joint_weights.weights", weights, weights))
93  {
94  if (!lookupParam(node_, "joint_weights.names", names, names) || (names.size() != weights.size()))
95  {
96  RCLCPP_ERROR(LOGGER, "Expecting list parameter joint_weights.names of same size as list joint_weights.weights");
97  // fall back to default weights
98  weights.clear();
99  }
100  }
101  else if (lookupParam(node_, "joint_weights", weights,
102  weights)) // try reading weight lists (for all active joints) directly
103  {
104  std::size_t num_active = active_names.size();
105  if (weights.size() == num_active)
106  {
107  joint_weights_ = weights;
108  return;
109  }
110  else if (!weights.empty())
111  {
112  RCLCPP_ERROR(LOGGER, "Expecting parameter joint_weights to list weights for all active joints (%zu) in order",
113  num_active);
114  // fall back to default weights
115  weights.clear();
116  }
117  }
118 
119  // by default assign weights of 1.0 to all joints
120  joint_weights_ = std::vector<double>(active_names.size(), 1.0);
121  if (weights.empty()) // indicates default case
122  return;
123 
124  // modify weights of listed joints
125  assert(names.size() == weights.size());
126  for (size_t i = 0; i != names.size(); ++i)
127  {
128  auto it = std::find(active_names.begin(), active_names.end(), names[i]);
129  if (it == active_names.cend())
130  RCLCPP_WARN(LOGGER, "Joint '%s' is not an active joint in group '%s'", names[i].c_str(),
131  joint_model_group_->getName().c_str());
132  else if (weights[i] < 0.0)
133  RCLCPP_WARN(LOGGER, "Negative weight %f for joint '%s' will be ignored", weights[i], names[i].c_str());
134  else
135  joint_weights_[it - active_names.begin()] = weights[i];
136  }
137  RCLCPP_INFO_STREAM(
138  LOGGER, "Joint weights for group '"
139  << getGroupName() << "': \n"
140  << Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()).transpose());
141 }
142 
143 bool KDLKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
144  const std::string& group_name, const std::string& base_frame,
145  const std::vector<std::string>& tip_frames, double search_discretization)
146 {
147  node_ = node;
148  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
149  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
150  if (!joint_model_group_)
151  return false;
152 
153  if (!joint_model_group_->isChain())
154  {
155  RCLCPP_ERROR(LOGGER, "Group '%s' is not a chain", group_name.c_str());
156  return false;
157  }
158  if (!joint_model_group_->isSingleDOFJoints())
159  {
160  RCLCPP_ERROR(LOGGER, "Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
161  return false;
162  }
163 
164  KDL::Tree kdl_tree;
165 
166  if (!kdl_parser::treeFromUrdfModel(*robot_model.getURDF(), kdl_tree))
167  {
168  RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
169  return false;
170  }
171  if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
172  {
173  RCLCPP_ERROR(LOGGER, "Could not initialize chain object");
174  return false;
175  }
176 
177  dimension_ = joint_model_group_->getActiveJointModels().size() + joint_model_group_->getMimicJointModels().size();
178  for (std::size_t i = 0; i < joint_model_group_->getJointModels().size(); ++i)
179  {
180  if (joint_model_group_->getJointModels()[i]->getType() == moveit::core::JointModel::REVOLUTE ||
181  joint_model_group_->getJointModels()[i]->getType() == moveit::core::JointModel::PRISMATIC)
182  {
183  solver_info_.joint_names.push_back(joint_model_group_->getJointModelNames()[i]);
184  const std::vector<moveit_msgs::msg::JointLimits>& jvec =
185  joint_model_group_->getJointModels()[i]->getVariableBoundsMsg();
186  solver_info_.limits.insert(solver_info_.limits.end(), jvec.begin(), jvec.end());
187  }
188  }
189 
190  if (!joint_model_group_->hasLinkModel(getTipFrame()))
191  {
192  RCLCPP_ERROR(LOGGER, "Could not find tip name in joint group '%s'", group_name.c_str());
193  return false;
194  }
195  solver_info_.link_names.push_back(getTipFrame());
196 
197  joint_min_.resize(solver_info_.limits.size());
198  joint_max_.resize(solver_info_.limits.size());
199 
200  for (unsigned int i = 0; i < solver_info_.limits.size(); ++i)
201  {
202  joint_min_(i) = solver_info_.limits[i].min_position;
203  joint_max_(i) = solver_info_.limits[i].max_position;
204  }
205 
206  // Get Solver Parameters
207  lookupParam(node_, "max_solver_iterations", max_solver_iterations_, 500);
208  lookupParam(node_, "epsilon", epsilon_, 1e-5);
209  lookupParam(node_, "orientation_vs_position", orientation_vs_position_weight_, 1.0);
210 
211  bool position_ik;
212  lookupParam(node_, "position_only_ik", position_ik, false);
213  if (position_ik) // position_only_ik overrules orientation_vs_position
214  orientation_vs_position_weight_ = 0.0;
215  if (orientation_vs_position_weight_ == 0.0)
216  RCLCPP_INFO(LOGGER, "Using position only ik");
217 
218  getJointWeights();
219 
220  // Check for mimic joints
221  unsigned int joint_counter = 0;
222  for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
223  {
224  const moveit::core::JointModel* jm = robot_model_->getJointModel(kdl_chain_.segments[i].getJoint().getName());
225 
226  // first check whether it belongs to the set of active joints in the group
227  if (jm->getMimic() == nullptr && jm->getVariableCount() > 0)
228  {
229  JointMimic mimic_joint;
230  mimic_joint.reset(joint_counter);
231  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
232  mimic_joint.active = true;
233  mimic_joints_.push_back(mimic_joint);
234  ++joint_counter;
235  continue;
236  }
237  if (joint_model_group_->hasJointModel(jm->getName()))
238  {
239  if (jm->getMimic() && joint_model_group_->hasJointModel(jm->getMimic()->getName()))
240  {
241  JointMimic mimic_joint;
242  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
243  mimic_joint.offset = jm->getMimicOffset();
244  mimic_joint.multiplier = jm->getMimicFactor();
245  mimic_joints_.push_back(mimic_joint);
246  continue;
247  }
248  }
249  }
250  for (JointMimic& mimic_joint : mimic_joints_)
251  {
252  if (!mimic_joint.active)
253  {
254  const moveit::core::JointModel* joint_model =
255  joint_model_group_->getJointModel(mimic_joint.joint_name)->getMimic();
256  for (JointMimic& mimic_joint_recal : mimic_joints_)
257  {
258  if (mimic_joint_recal.joint_name == joint_model->getName())
259  {
260  mimic_joint.map_index = mimic_joint_recal.map_index;
261  }
262  }
263  }
264  }
265 
266  // Setup the joint state groups that we need
267  state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
268 
269  fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
270 
271  initialized_ = true;
272  RCLCPP_DEBUG(LOGGER, "KDL solver initialized");
273  return true;
274 }
275 
276 bool KDLKinematicsPlugin::timedOut(const rclcpp::Time& start_time, double duration) const
277 {
278  return ((steady_clock_.now() - start_time).seconds() >= duration);
279 }
280 
281 bool KDLKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
282  const std::vector<double>& ik_seed_state, std::vector<double>& solution,
283  moveit_msgs::msg::MoveItErrorCodes& error_code,
285 {
286  std::vector<double> consistency_limits;
287 
288  // limit search to a single attempt by setting a timeout of zero
289  return searchPositionIK(ik_pose, ik_seed_state, 0.0, consistency_limits, solution, IKCallbackFn(), error_code,
290  options);
291 }
292 
293 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
294  const std::vector<double>& ik_seed_state, double timeout,
295  std::vector<double>& solution,
296  moveit_msgs::msg::MoveItErrorCodes& error_code,
298 {
299  std::vector<double> consistency_limits;
300 
301  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
302  options);
303 }
304 
305 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
306  const std::vector<double>& ik_seed_state, double timeout,
307  const std::vector<double>& consistency_limits, std::vector<double>& solution,
308  moveit_msgs::msg::MoveItErrorCodes& error_code,
310 {
311  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
312  options);
313 }
314 
315 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
316  const std::vector<double>& ik_seed_state, double timeout,
317  std::vector<double>& solution, const IKCallbackFn& solution_callback,
318  moveit_msgs::msg::MoveItErrorCodes& error_code,
320 {
321  std::vector<double> consistency_limits;
322  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
323  options);
324 }
325 
326 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
327  const std::vector<double>& ik_seed_state, double timeout,
328  const std::vector<double>& consistency_limits, std::vector<double>& solution,
329  const IKCallbackFn& solution_callback,
330  moveit_msgs::msg::MoveItErrorCodes& error_code,
332 {
333  const rclcpp::Time start_time = steady_clock_.now();
334  if (!initialized_)
335  {
336  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
337  error_code.val = error_code.NO_IK_SOLUTION;
338  return false;
339  }
340 
341  if (ik_seed_state.size() != dimension_)
342  {
343  RCLCPP_ERROR(LOGGER, "Seed state must have size %d instead of size %zu\n", dimension_, ik_seed_state.size());
344  error_code.val = error_code.NO_IK_SOLUTION;
345  return false;
346  }
347 
348  // Resize consistency limits to remove mimic joints
349  std::vector<double> consistency_limits_mimic;
350  if (!consistency_limits.empty())
351  {
352  if (consistency_limits.size() != dimension_)
353  {
354  RCLCPP_ERROR(LOGGER, "Consistency limits must be empty or have size %d instead of size %zu\n", dimension_,
355  consistency_limits.size());
356  error_code.val = error_code.NO_IK_SOLUTION;
357  return false;
358  }
359 
360  for (std::size_t i = 0; i < dimension_; ++i)
361  {
362  if (mimic_joints_[i].active)
363  consistency_limits_mimic.push_back(consistency_limits[i]);
364  }
365  }
366  Eigen::Matrix<double, 6, 1> cartesian_weights;
367  cartesian_weights.topRows<3>().setConstant(1.0);
368  cartesian_weights.bottomRows<3>().setConstant(orientation_vs_position_weight_);
369 
370  KDL::JntArray jnt_seed_state(dimension_);
371  KDL::JntArray jnt_pos_in(dimension_);
372  KDL::JntArray jnt_pos_out(dimension_);
373  jnt_seed_state.data = Eigen::Map<const Eigen::VectorXd>(ik_seed_state.data(), ik_seed_state.size());
374  jnt_pos_in = jnt_seed_state;
375 
376  KDL::ChainIkSolverVelMimicSVD ik_solver_vel(kdl_chain_, mimic_joints_, orientation_vs_position_weight_ == 0.0);
377  solution.resize(dimension_);
378 
379  KDL::Frame pose_desired;
380  tf2::fromMsg(ik_pose, pose_desired);
381 
382  RCLCPP_DEBUG_STREAM(LOGGER, "searchPositionIK: Position request pose is "
383  << ik_pose.position.x << " " << ik_pose.position.y << " " << ik_pose.position.z << " "
384  << ik_pose.orientation.x << " " << ik_pose.orientation.y << " "
385  << ik_pose.orientation.z << " " << ik_pose.orientation.w);
386 
387  unsigned int attempt = 0;
388  do
389  {
390  ++attempt;
391  if (attempt > 1) // randomly re-seed after first attempt
392  {
393  if (!consistency_limits_mimic.empty())
394  getRandomConfiguration(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_in.data);
395  else
396  getRandomConfiguration(jnt_pos_in.data);
397  RCLCPP_DEBUG_STREAM(LOGGER, "New random configuration (" << attempt << "): " << jnt_pos_in);
398  }
399 
400  int ik_valid =
401  CartToJnt(ik_solver_vel, jnt_pos_in, pose_desired, jnt_pos_out, max_solver_iterations_,
402  Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()), cartesian_weights);
403  if (ik_valid == 0 || options.return_approximate_solution) // found acceptable solution
404  {
405  if (!consistency_limits_mimic.empty() &&
406  !checkConsistency(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_out.data))
407  continue;
408 
409  Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
410  if (solution_callback)
411  {
412  solution_callback(ik_pose, solution, error_code);
413  if (error_code.val != error_code.SUCCESS)
414  continue;
415  }
416 
417  // solution passed consistency check and solution callback
418  error_code.val = error_code.SUCCESS;
419  RCLCPP_DEBUG_STREAM(LOGGER, "Solved after " << (steady_clock_.now() - start_time).seconds() << " < " << timeout
420  << "s and " << attempt << " attempts");
421  return true;
422  }
423  } while (!timedOut(start_time, timeout));
424 
425  RCLCPP_DEBUG_STREAM(LOGGER, "IK timed out after " << (steady_clock_.now() - start_time).seconds() << " > " << timeout
426  << "s and " << attempt << " attempts");
427  error_code.val = error_code.TIMED_OUT;
428  return false;
429 }
430 
431 // NOLINTNEXTLINE(readability-identifier-naming)
432 int KDLKinematicsPlugin::CartToJnt(KDL::ChainIkSolverVelMimicSVD& ik_solver, const KDL::JntArray& q_init,
433  const KDL::Frame& p_in, KDL::JntArray& q_out, const unsigned int max_iter,
434  const Eigen::VectorXd& joint_weights, const Twist& cartesian_weights) const
435 {
436  double last_delta_twist_norm = DBL_MAX;
437  double step_size = 1.0;
438  KDL::Frame f;
439  KDL::Twist delta_twist;
440  KDL::JntArray delta_q(q_out.rows()), q_backup(q_out.rows());
441  Eigen::ArrayXd extra_joint_weights(joint_weights.rows());
442  extra_joint_weights.setOnes();
443 
444  q_out = q_init;
445  RCLCPP_DEBUG_STREAM(LOGGER, "Input: " << q_init);
446 
447  unsigned int i;
448  bool success = false;
449  for (i = 0; i < max_iter; ++i)
450  {
451  fk_solver_->JntToCart(q_out, f);
452  delta_twist = diff(f, p_in);
453  RCLCPP_DEBUG_STREAM(LOGGER, "[" << std::setw(3) << i << "] delta_twist: " << delta_twist);
454 
455  // check norms of position and orientation errors
456  const double position_error = delta_twist.vel.Norm();
457  const double orientation_error = ik_solver.isPositionOnly() ? 0 : delta_twist.rot.Norm();
458  const double delta_twist_norm = std::max(position_error, orientation_error);
459  if (delta_twist_norm <= epsilon_)
460  {
461  success = true;
462  break;
463  }
464 
465  if (delta_twist_norm >= last_delta_twist_norm)
466  {
467  // if the error increased, we are close to a singularity -> reduce step size
468  double old_step_size = step_size;
469  step_size *= std::min(0.2, last_delta_twist_norm / delta_twist_norm); // reduce scale;
470  KDL::Multiply(delta_q, step_size / old_step_size, delta_q);
471  RCLCPP_DEBUG(LOGGER, " error increased: %f -> %f, scale: %f", last_delta_twist_norm, delta_twist_norm,
472  step_size);
473  q_out = q_backup; // restore previous unclipped joint values
474  }
475  else
476  {
477  q_backup = q_out; // remember joint values of last successful step
478  step_size = 1.0; // reset step size
479  last_delta_twist_norm = delta_twist_norm;
480 
481  ik_solver.CartToJnt(q_out, delta_twist, delta_q, extra_joint_weights * joint_weights.array(), cartesian_weights);
482  }
483 
484  clipToJointLimits(q_out, delta_q, extra_joint_weights);
485 
486  const double delta_q_norm = delta_q.data.lpNorm<1>();
487  RCLCPP_DEBUG(LOGGER, "[%3d] pos err: %f rot err: %f delta_q: %f", i, position_error, orientation_error,
488  delta_q_norm);
489  if (delta_q_norm < epsilon_) // stuck in singularity
490  {
491  if (step_size < epsilon_) // cannot reach target
492  break;
493  // wiggle joints
494  last_delta_twist_norm = DBL_MAX;
495  delta_q.data.setRandom();
496  delta_q.data *= std::min(0.1, delta_twist_norm);
497  clipToJointLimits(q_out, delta_q, extra_joint_weights);
498  extra_joint_weights.setOnes();
499  }
500 
501  KDL::Add(q_out, delta_q, q_out);
502 
503  RCLCPP_DEBUG_STREAM(LOGGER, " delta_q: " << delta_q);
504  RCLCPP_DEBUG_STREAM(LOGGER, " q: " << q_out);
505  }
506 
507  int result = (i == max_iter) ? -3 : (success ? 0 : -2);
508  RCLCPP_DEBUG_STREAM(LOGGER, "Result " << result << " after " << i << " iterations: " << q_out);
509 
510  return result;
511 }
512 
513 void KDLKinematicsPlugin::clipToJointLimits(const KDL::JntArray& q, KDL::JntArray& q_delta,
514  Eigen::ArrayXd& weighting) const
515 {
516  weighting.setOnes();
517  for (std::size_t i = 0; i < q.rows(); ++i)
518  {
519  const double delta_max = joint_max_(i) - q(i);
520  const double delta_min = joint_min_(i) - q(i);
521  if (q_delta(i) > delta_max)
522  q_delta(i) = delta_max;
523  else if (q_delta(i) < delta_min)
524  q_delta(i) = delta_min;
525  else
526  continue;
527 
528  weighting[mimic_joints_[i].map_index] = 0.01;
529  }
530 }
531 
532 bool KDLKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
533  const std::vector<double>& joint_angles,
534  std::vector<geometry_msgs::msg::Pose>& poses) const
535 {
536  if (!initialized_)
537  {
538  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
539  return false;
540  }
541  poses.resize(link_names.size());
542  if (joint_angles.size() != dimension_)
543  {
544  RCLCPP_ERROR(LOGGER, "Joint angles vector must have size: %d", dimension_);
545  return false;
546  }
547 
548  KDL::Frame p_out;
549  KDL::JntArray jnt_pos_in(dimension_);
550  jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
551 
552  bool valid = true;
553  for (unsigned int i = 0; i < poses.size(); ++i)
554  {
555  if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
556  {
557  poses[i] = tf2::toMsg(p_out);
558  }
559  else
560  {
561  RCLCPP_ERROR(LOGGER, "Could not compute FK for %s", link_names[i].c_str());
562  valid = false;
563  }
564  }
565  return valid;
566 }
567 
568 const std::vector<std::string>& KDLKinematicsPlugin::getJointNames() const
569 {
570  return solver_info_.joint_names;
571 }
572 
573 const std::vector<std::string>& KDLKinematicsPlugin::getLinkNames() const
574 {
575  return solver_info_.link_names;
576 }
577 
578 } // namespace kdl_kinematics_plugin
579 
580 // register KDLKinematics as a KinematicsBase implementation
581 #include <class_loader/class_loader.hpp>
int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out) override
bool isPositionOnly() const
Return true iff we ignore orientation but only consider position for inverse kinematics.
A model of a mimic joint. Mimic joints are typically unactuated joints that are constrained to follow...
Definition: joint_mimic.hpp:46
double multiplier
Multiplier for this joint value from the joint that it mimics.
Definition: joint_mimic.hpp:56
bool active
If true, this joint is an active DOF and not a mimic joint.
Definition: joint_mimic.hpp:62
std::string joint_name
Name of this joint.
Definition: joint_mimic.hpp:60
void reset(unsigned int index)
Definition: joint_mimic.hpp:64
double offset
Offset for this joint value from the joint that it mimics.
Definition: joint_mimic.hpp:54
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
int CartToJnt(KDL::ChainIkSolverVelMimicSVD &ik_solver, const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const unsigned int max_iter, const Eigen::VectorXd &joint_weights, const Twist &cartesian_weights) const
Solve position IK given initial joint values.
Provides an interface for kinematics solvers.
void storeValues(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
virtual const std::string & getTipFrame() const
Return the name of the tip frame of the chain on which the solver is operating. This is usually a lin...
static const rclcpp::Logger LOGGER
bool lookupParam(const rclcpp::Node::SharedPtr &node, const std::string &param, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
rclcpp::Node::SharedPtr node_
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
moveit::core::RobotModelConstPtr robot_model_
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
bool isChain() const
Check if this group is a linear chain.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::string & getName() const
Get the name of the joint group.
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const
Compute random values for the state of the joint group.
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
bool isSingleDOFJoints() const
Return true if the group consists only of joints that are single DOF.
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
Definition: joint_model.h:384
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
Definition: joint_model.h:378
const JointModel * getMimic() const
Get the joint this one is mimicking.
Definition: joint_model.h:372
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model.h:106
A set of options for the kinematics solver.
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)