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