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