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 #include <tf2/transform_datatypes.h>
42 
43 #include <kdl_parser/kdl_parser.hpp>
44 #include <kdl/chainfksolverpos_recursive.hpp>
45 #include <kdl/frames_io.hpp>
46 #include <kdl/kinfam_io.hpp>
47 
48 namespace kdl_kinematics_plugin
49 {
50 static rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kdl_kinematics_plugin.kdl_kinematics_plugin");
51 
52 rclcpp::Clock KDLKinematicsPlugin::steady_clock_{ RCL_STEADY_TIME };
53 
55 {
56 }
57 
58 void KDLKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array) const
59 {
60  state_->setToRandomPositions(joint_model_group_);
61  state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
62 }
63 
64 void KDLKinematicsPlugin::getRandomConfiguration(const Eigen::VectorXd& seed_state,
65  const std::vector<double>& consistency_limits,
66  Eigen::VectorXd& jnt_array) const
67 {
68  joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), &jnt_array[0],
69  &seed_state[0], consistency_limits);
70 }
71 
72 bool KDLKinematicsPlugin::checkConsistency(const Eigen::VectorXd& seed_state,
73  const std::vector<double>& consistency_limits,
74  const Eigen::VectorXd& solution) const
75 {
76  for (std::size_t i = 0; i < dimension_; ++i)
77  if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
78  return false;
79  return true;
80 }
81 
82 void KDLKinematicsPlugin::getJointWeights()
83 {
84  const std::vector<std::string>& active_names = joint_model_group_->getActiveJointModelNames();
85  std::vector<std::string> names;
86  std::vector<double> weights;
87  if (lookupParam(node_, "joint_weights.weights", weights, weights))
88  {
89  if (!lookupParam(node_, "joint_weights.names", names, names) || (names.size() != weights.size()))
90  {
91  RCLCPP_ERROR(LOGGER, "Expecting list parameter joint_weights.names of same size as list joint_weights.weights");
92  // fall back to default weights
93  weights.clear();
94  }
95  }
96  else if (lookupParam(node_, "joint_weights", weights,
97  weights)) // try reading weight lists (for all active joints) directly
98  {
99  std::size_t num_active = active_names.size();
100  if (weights.size() == num_active)
101  {
102  joint_weights_ = weights;
103  return;
104  }
105  else if (!weights.empty())
106  {
107  RCLCPP_ERROR(LOGGER, "Expecting parameter joint_weights to list weights for all active joints (%zu) in order",
108  num_active);
109  // fall back to default weights
110  weights.clear();
111  }
112  }
113 
114  // by default assign weights of 1.0 to all joints
115  joint_weights_ = std::vector<double>(active_names.size(), 1.0);
116  if (weights.empty()) // indicates default case
117  return;
118 
119  // modify weights of listed joints
120  assert(names.size() == weights.size());
121  for (size_t i = 0; i != names.size(); ++i)
122  {
123  auto it = std::find(active_names.begin(), active_names.end(), names[i]);
124  if (it == active_names.cend())
125  RCLCPP_WARN(LOGGER, "Joint '%s' is not an active joint in group '%s'", names[i].c_str(),
126  joint_model_group_->getName().c_str());
127  else if (weights[i] < 0.0)
128  RCLCPP_WARN(LOGGER, "Negative weight %f for joint '%s' will be ignored", weights[i], names[i].c_str());
129  else
130  joint_weights_[it - active_names.begin()] = weights[i];
131  }
132  RCLCPP_INFO_STREAM(
133  LOGGER, "Joint weights for group '"
134  << getGroupName() << "': \n"
135  << Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()).transpose());
136 }
137 
138 bool KDLKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
139  const std::string& group_name, const std::string& base_frame,
140  const std::vector<std::string>& tip_frames, double search_discretization)
141 {
142  node_ = node;
143  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
144  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
145  if (!joint_model_group_)
146  return false;
147 
148  if (!joint_model_group_->isChain())
149  {
150  RCLCPP_ERROR(LOGGER, "Group '%s' is not a chain", group_name.c_str());
151  return false;
152  }
153  if (!joint_model_group_->isSingleDOFJoints())
154  {
155  RCLCPP_ERROR(LOGGER, "Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
156  return false;
157  }
158 
159  KDL::Tree kdl_tree;
160 
161  if (!kdl_parser::treeFromUrdfModel(*robot_model.getURDF(), kdl_tree))
162  {
163  RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
164  return false;
165  }
166  if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
167  {
168  RCLCPP_ERROR(LOGGER, "Could not initialize chain object");
169  return false;
170  }
171 
172  dimension_ = joint_model_group_->getActiveJointModels().size() + joint_model_group_->getMimicJointModels().size();
173  for (std::size_t i = 0; i < joint_model_group_->getJointModels().size(); ++i)
174  {
175  if (joint_model_group_->getJointModels()[i]->getType() == moveit::core::JointModel::REVOLUTE ||
176  joint_model_group_->getJointModels()[i]->getType() == moveit::core::JointModel::PRISMATIC)
177  {
178  solver_info_.joint_names.push_back(joint_model_group_->getJointModelNames()[i]);
179  const std::vector<moveit_msgs::msg::JointLimits>& jvec =
180  joint_model_group_->getJointModels()[i]->getVariableBoundsMsg();
181  solver_info_.limits.insert(solver_info_.limits.end(), jvec.begin(), jvec.end());
182  }
183  }
184 
185  if (!joint_model_group_->hasLinkModel(getTipFrame()))
186  {
187  RCLCPP_ERROR(LOGGER, "Could not find tip name in joint group '%s'", group_name.c_str());
188  return false;
189  }
190  solver_info_.link_names.push_back(getTipFrame());
191 
192  joint_min_.resize(solver_info_.limits.size());
193  joint_max_.resize(solver_info_.limits.size());
194 
195  for (unsigned int i = 0; i < solver_info_.limits.size(); ++i)
196  {
197  joint_min_(i) = solver_info_.limits[i].min_position;
198  joint_max_(i) = solver_info_.limits[i].max_position;
199  }
200 
201  // Get Solver Parameters
202  lookupParam(node_, "max_solver_iterations", max_solver_iterations_, 500);
203  lookupParam(node_, "epsilon", epsilon_, 1e-5);
204  lookupParam(node_, "orientation_vs_position", orientation_vs_position_weight_, 1.0);
205 
206  bool position_ik;
207  lookupParam(node_, "position_only_ik", position_ik, false);
208  if (position_ik) // position_only_ik overrules orientation_vs_position
209  orientation_vs_position_weight_ = 0.0;
210  if (orientation_vs_position_weight_ == 0.0)
211  RCLCPP_INFO(LOGGER, "Using position only ik");
212 
213  getJointWeights();
214 
215  // Check for mimic joints
216  unsigned int joint_counter = 0;
217  for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
218  {
219  const moveit::core::JointModel* jm = robot_model_->getJointModel(kdl_chain_.segments[i].getJoint().getName());
220 
221  // first check whether it belongs to the set of active joints in the group
222  if (jm->getMimic() == nullptr && jm->getVariableCount() > 0)
223  {
224  JointMimic mimic_joint;
225  mimic_joint.reset(joint_counter);
226  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
227  mimic_joint.active = true;
228  mimic_joints_.push_back(mimic_joint);
229  ++joint_counter;
230  continue;
231  }
232  if (joint_model_group_->hasJointModel(jm->getName()))
233  {
234  if (jm->getMimic() && joint_model_group_->hasJointModel(jm->getMimic()->getName()))
235  {
236  JointMimic mimic_joint;
237  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
238  mimic_joint.offset = jm->getMimicOffset();
239  mimic_joint.multiplier = jm->getMimicFactor();
240  mimic_joints_.push_back(mimic_joint);
241  continue;
242  }
243  }
244  }
245  for (JointMimic& mimic_joint : mimic_joints_)
246  {
247  if (!mimic_joint.active)
248  {
249  const moveit::core::JointModel* joint_model =
250  joint_model_group_->getJointModel(mimic_joint.joint_name)->getMimic();
251  for (JointMimic& mimic_joint_recal : mimic_joints_)
252  {
253  if (mimic_joint_recal.joint_name == joint_model->getName())
254  {
255  mimic_joint.map_index = mimic_joint_recal.map_index;
256  }
257  }
258  }
259  }
260 
261  // Setup the joint state groups that we need
262  state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
263 
264  fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
265 
266  initialized_ = true;
267  RCLCPP_DEBUG(LOGGER, "KDL solver initialized");
268  return true;
269 }
270 
271 bool KDLKinematicsPlugin::timedOut(const rclcpp::Time& start_time, double duration) const
272 {
273  return ((steady_clock_.now() - start_time).seconds() >= duration);
274 }
275 
276 bool KDLKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
277  const std::vector<double>& ik_seed_state, std::vector<double>& solution,
278  moveit_msgs::msg::MoveItErrorCodes& error_code,
280 {
281  std::vector<double> consistency_limits;
282 
283  // limit search to a single attempt by setting a timeout of zero
284  return searchPositionIK(ik_pose, ik_seed_state, 0.0, consistency_limits, solution, IKCallbackFn(), error_code,
285  options);
286 }
287 
288 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
289  const std::vector<double>& ik_seed_state, double timeout,
290  std::vector<double>& solution,
291  moveit_msgs::msg::MoveItErrorCodes& error_code,
293 {
294  std::vector<double> consistency_limits;
295 
296  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
297  options);
298 }
299 
300 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
301  const std::vector<double>& ik_seed_state, double timeout,
302  const std::vector<double>& consistency_limits, std::vector<double>& solution,
303  moveit_msgs::msg::MoveItErrorCodes& error_code,
305 {
306  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
307  options);
308 }
309 
310 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
311  const std::vector<double>& ik_seed_state, double timeout,
312  std::vector<double>& solution, const IKCallbackFn& solution_callback,
313  moveit_msgs::msg::MoveItErrorCodes& error_code,
315 {
316  std::vector<double> consistency_limits;
317  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
318  options);
319 }
320 
321 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
322  const std::vector<double>& ik_seed_state, double timeout,
323  const std::vector<double>& consistency_limits, std::vector<double>& solution,
324  const IKCallbackFn& solution_callback,
325  moveit_msgs::msg::MoveItErrorCodes& error_code,
327 {
328  const rclcpp::Time start_time = steady_clock_.now();
329  if (!initialized_)
330  {
331  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
332  error_code.val = error_code.NO_IK_SOLUTION;
333  return false;
334  }
335 
336  if (ik_seed_state.size() != dimension_)
337  {
338  RCLCPP_ERROR(LOGGER, "Seed state must have size %d instead of size %zu\n", dimension_, ik_seed_state.size());
339  error_code.val = error_code.NO_IK_SOLUTION;
340  return false;
341  }
342 
343  // Resize consistency limits to remove mimic joints
344  std::vector<double> consistency_limits_mimic;
345  if (!consistency_limits.empty())
346  {
347  if (consistency_limits.size() != dimension_)
348  {
349  RCLCPP_ERROR(LOGGER, "Consistency limits must be empty or have size %d instead of size %zu\n", dimension_,
350  consistency_limits.size());
351  error_code.val = error_code.NO_IK_SOLUTION;
352  return false;
353  }
354 
355  for (std::size_t i = 0; i < dimension_; ++i)
356  {
357  if (mimic_joints_[i].active)
358  consistency_limits_mimic.push_back(consistency_limits[i]);
359  }
360  }
361  Eigen::Matrix<double, 6, 1> cartesian_weights;
362  cartesian_weights.topRows<3>().setConstant(1.0);
363  cartesian_weights.bottomRows<3>().setConstant(orientation_vs_position_weight_);
364 
365  KDL::JntArray jnt_seed_state(dimension_);
366  KDL::JntArray jnt_pos_in(dimension_);
367  KDL::JntArray jnt_pos_out(dimension_);
368  jnt_seed_state.data = Eigen::Map<const Eigen::VectorXd>(ik_seed_state.data(), ik_seed_state.size());
369  jnt_pos_in = jnt_seed_state;
370 
371  KDL::ChainIkSolverVelMimicSVD ik_solver_vel(kdl_chain_, mimic_joints_, orientation_vs_position_weight_ == 0.0);
372  solution.resize(dimension_);
373 
374  KDL::Frame pose_desired;
375  tf2::fromMsg(ik_pose, pose_desired);
376 
377  RCLCPP_DEBUG_STREAM(LOGGER, "searchPositionIK: Position request pose is "
378  << ik_pose.position.x << " " << ik_pose.position.y << " " << ik_pose.position.z << " "
379  << ik_pose.orientation.x << " " << ik_pose.orientation.y << " "
380  << ik_pose.orientation.z << " " << ik_pose.orientation.w);
381 
382  unsigned int attempt = 0;
383  do
384  {
385  ++attempt;
386  if (attempt > 1) // randomly re-seed after first attempt
387  {
388  if (!consistency_limits_mimic.empty())
389  getRandomConfiguration(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_in.data);
390  else
391  getRandomConfiguration(jnt_pos_in.data);
392  RCLCPP_DEBUG_STREAM(LOGGER, "New random configuration (" << attempt << "): " << jnt_pos_in);
393  }
394 
395  int ik_valid =
396  CartToJnt(ik_solver_vel, jnt_pos_in, pose_desired, jnt_pos_out, max_solver_iterations_,
397  Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()), cartesian_weights);
398  if (ik_valid == 0 || options.return_approximate_solution) // found acceptable solution
399  {
400  if (!consistency_limits_mimic.empty() &&
401  !checkConsistency(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_out.data))
402  continue;
403 
404  Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
405  if (solution_callback)
406  {
407  solution_callback(ik_pose, solution, error_code);
408  if (error_code.val != error_code.SUCCESS)
409  continue;
410  }
411 
412  // solution passed consistency check and solution callback
413  error_code.val = error_code.SUCCESS;
414  RCLCPP_DEBUG_STREAM(LOGGER, "Solved after " << (steady_clock_.now() - start_time).seconds() << " < " << timeout
415  << "s and " << attempt << " attempts");
416  return true;
417  }
418  } while (!timedOut(start_time, timeout));
419 
420  RCLCPP_DEBUG_STREAM(LOGGER, "IK timed out after " << (steady_clock_.now() - start_time).seconds() << " > " << timeout
421  << "s and " << attempt << " attempts");
422  error_code.val = error_code.TIMED_OUT;
423  return false;
424 }
425 
426 // NOLINTNEXTLINE(readability-identifier-naming)
427 int KDLKinematicsPlugin::CartToJnt(KDL::ChainIkSolverVelMimicSVD& ik_solver, const KDL::JntArray& q_init,
428  const KDL::Frame& p_in, KDL::JntArray& q_out, const unsigned int max_iter,
429  const Eigen::VectorXd& joint_weights, const Twist& cartesian_weights) const
430 {
431  double last_delta_twist_norm = DBL_MAX;
432  double step_size = 1.0;
433  KDL::Frame f;
434  KDL::Twist delta_twist;
435  KDL::JntArray delta_q(q_out.rows()), q_backup(q_out.rows());
436  Eigen::ArrayXd extra_joint_weights(joint_weights.rows());
437  extra_joint_weights.setOnes();
438 
439  q_out = q_init;
440  RCLCPP_DEBUG_STREAM(LOGGER, "Input: " << q_init);
441 
442  unsigned int i;
443  bool success = false;
444  for (i = 0; i < max_iter; ++i)
445  {
446  fk_solver_->JntToCart(q_out, f);
447  delta_twist = diff(f, p_in);
448  RCLCPP_DEBUG_STREAM(LOGGER, "[" << std::setw(3) << i << "] delta_twist: " << delta_twist);
449 
450  // check norms of position and orientation errors
451  const double position_error = delta_twist.vel.Norm();
452  const double orientation_error = ik_solver.isPositionOnly() ? 0 : delta_twist.rot.Norm();
453  const double delta_twist_norm = std::max(position_error, orientation_error);
454  if (delta_twist_norm <= epsilon_)
455  {
456  success = true;
457  break;
458  }
459 
460  if (delta_twist_norm >= last_delta_twist_norm)
461  {
462  // if the error increased, we are close to a singularity -> reduce step size
463  double old_step_size = step_size;
464  step_size *= std::min(0.2, last_delta_twist_norm / delta_twist_norm); // reduce scale;
465  KDL::Multiply(delta_q, step_size / old_step_size, delta_q);
466  RCLCPP_DEBUG(LOGGER, " error increased: %f -> %f, scale: %f", last_delta_twist_norm, delta_twist_norm,
467  step_size);
468  q_out = q_backup; // restore previous unclipped joint values
469  }
470  else
471  {
472  q_backup = q_out; // remember joint values of last successful step
473  step_size = 1.0; // reset step size
474  last_delta_twist_norm = delta_twist_norm;
475 
476  ik_solver.CartToJnt(q_out, delta_twist, delta_q, extra_joint_weights * joint_weights.array(), cartesian_weights);
477  }
478 
479  clipToJointLimits(q_out, delta_q, extra_joint_weights);
480 
481  const double delta_q_norm = delta_q.data.lpNorm<1>();
482  RCLCPP_DEBUG(LOGGER, "[%3d] pos err: %f rot err: %f delta_q: %f", i, position_error, orientation_error,
483  delta_q_norm);
484  if (delta_q_norm < epsilon_) // stuck in singularity
485  {
486  if (step_size < epsilon_) // cannot reach target
487  break;
488  // wiggle joints
489  last_delta_twist_norm = DBL_MAX;
490  delta_q.data.setRandom();
491  delta_q.data *= std::min(0.1, delta_twist_norm);
492  clipToJointLimits(q_out, delta_q, extra_joint_weights);
493  extra_joint_weights.setOnes();
494  }
495 
496  KDL::Add(q_out, delta_q, q_out);
497 
498  RCLCPP_DEBUG_STREAM(LOGGER, " delta_q: " << delta_q);
499  RCLCPP_DEBUG_STREAM(LOGGER, " q: " << q_out);
500  }
501 
502  int result = (i == max_iter) ? -3 : (success ? 0 : -2);
503  RCLCPP_DEBUG_STREAM(LOGGER, "Result " << result << " after " << i << " iterations: " << q_out);
504 
505  return result;
506 }
507 
508 void KDLKinematicsPlugin::clipToJointLimits(const KDL::JntArray& q, KDL::JntArray& q_delta,
509  Eigen::ArrayXd& weighting) const
510 {
511  weighting.setOnes();
512  for (std::size_t i = 0; i < q.rows(); ++i)
513  {
514  const double delta_max = joint_max_(i) - q(i);
515  const double delta_min = joint_min_(i) - q(i);
516  if (q_delta(i) > delta_max)
517  q_delta(i) = delta_max;
518  else if (q_delta(i) < delta_min)
519  q_delta(i) = delta_min;
520  else
521  continue;
522 
523  weighting[mimic_joints_[i].map_index] = 0.01;
524  }
525 }
526 
527 bool KDLKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
528  const std::vector<double>& joint_angles,
529  std::vector<geometry_msgs::msg::Pose>& poses) const
530 {
531  if (!initialized_)
532  {
533  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
534  return false;
535  }
536  poses.resize(link_names.size());
537  if (joint_angles.size() != dimension_)
538  {
539  RCLCPP_ERROR(LOGGER, "Joint angles vector must have size: %d", dimension_);
540  return false;
541  }
542 
543  KDL::Frame p_out;
544  KDL::JntArray jnt_pos_in(dimension_);
545  jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
546 
547  bool valid = true;
548  for (unsigned int i = 0; i < poses.size(); ++i)
549  {
550  if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
551  {
552  poses[i] = tf2::toMsg(p_out);
553  }
554  else
555  {
556  RCLCPP_ERROR(LOGGER, "Could not compute FK for %s", link_names[i].c_str());
557  valid = false;
558  }
559  }
560  return valid;
561 }
562 
563 const std::vector<std::string>& KDLKinematicsPlugin::getJointNames() const
564 {
565  return solver_info_.joint_names;
566 }
567 
568 const std::vector<std::string>& KDLKinematicsPlugin::getLinkNames() const
569 {
570  return solver_info_.link_names;
571 }
572 
573 } // namespace kdl_kinematics_plugin
574 
575 // register KDLKinematics as a KinematicsBase implementation
576 #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)