40 #include <tf2_kdl/tf2_kdl.hpp>
42 #if __has_include(<tf2/transform_datatypes.hpp>)
43 #include <tf2/transform_datatypes.hpp>
45 #include <tf2/transform_datatypes.h>
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>
55 static rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_kdl_kinematics_plugin.kdl_kinematics_plugin");
57 rclcpp::Clock KDLKinematicsPlugin::steady_clock_{ RCL_STEADY_TIME };
63 void KDLKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array)
const
65 state_->setToRandomPositions(joint_model_group_);
66 state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
69 void KDLKinematicsPlugin::getRandomConfiguration(
const Eigen::VectorXd& seed_state,
70 const std::vector<double>& consistency_limits,
71 Eigen::VectorXd& jnt_array)
const
74 &seed_state[0], consistency_limits);
77 bool KDLKinematicsPlugin::checkConsistency(
const Eigen::VectorXd& seed_state,
78 const std::vector<double>& consistency_limits,
79 const Eigen::VectorXd& solution)
const
81 for (std::size_t i = 0; i < dimension_; ++i)
82 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
87 void KDLKinematicsPlugin::getJointWeights()
90 std::vector<std::string> names;
91 std::vector<double> weights;
94 if (!
lookupParam(
node_,
"joint_weights.names", names, names) || (names.size() != weights.size()))
96 RCLCPP_ERROR(
LOGGER,
"Expecting list parameter joint_weights.names of same size as list joint_weights.weights");
104 std::size_t num_active = active_names.size();
105 if (weights.size() == num_active)
107 joint_weights_ = weights;
110 else if (!weights.empty())
112 RCLCPP_ERROR(
LOGGER,
"Expecting parameter joint_weights to list weights for all active joints (%zu) in order",
120 joint_weights_ = std::vector<double>(active_names.size(), 1.0);
125 assert(names.size() == weights.size());
126 for (
size_t i = 0; i != names.size(); ++i)
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());
135 joint_weights_[it - active_names.begin()] = weights[i];
138 LOGGER,
"Joint weights for group '"
140 << Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()).transpose());
144 const std::string& group_name,
const std::string& base_frame,
145 const std::vector<std::string>& tip_frames,
double search_discretization)
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_)
153 if (!joint_model_group_->
isChain())
155 RCLCPP_ERROR(
LOGGER,
"Group '%s' is not a chain", group_name.c_str());
160 RCLCPP_ERROR(
LOGGER,
"Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
166 if (!kdl_parser::treeFromUrdfModel(*robot_model.
getURDF(), kdl_tree))
168 RCLCPP_ERROR(
LOGGER,
"Could not initialize tree object");
173 RCLCPP_ERROR(
LOGGER,
"Could not initialize chain object");
178 for (std::size_t i = 0; i < joint_model_group_->
getJointModels().size(); ++i)
184 const std::vector<moveit_msgs::msg::JointLimits>& jvec =
186 solver_info_.limits.insert(solver_info_.limits.end(), jvec.begin(), jvec.end());
192 RCLCPP_ERROR(
LOGGER,
"Could not find tip name in joint group '%s'", group_name.c_str());
197 joint_min_.resize(solver_info_.limits.size());
198 joint_max_.resize(solver_info_.limits.size());
200 for (
unsigned int i = 0; i < solver_info_.limits.size(); ++i)
202 joint_min_(i) = solver_info_.limits[i].min_position;
203 joint_max_(i) = solver_info_.limits[i].max_position;
209 lookupParam(
node_,
"orientation_vs_position", orientation_vs_position_weight_, 1.0);
214 orientation_vs_position_weight_ = 0.0;
215 if (orientation_vs_position_weight_ == 0.0)
216 RCLCPP_INFO(
LOGGER,
"Using position only ik");
221 unsigned int joint_counter = 0;
222 for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
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);
242 mimic_joint.
joint_name = kdl_chain_.segments[i].getJoint().getName();
245 mimic_joints_.push_back(mimic_joint);
252 if (!mimic_joint.active)
256 for (
JointMimic& mimic_joint_recal : mimic_joints_)
258 if (mimic_joint_recal.joint_name == joint_model->
getName())
260 mimic_joint.map_index = mimic_joint_recal.map_index;
267 state_ = std::make_shared<moveit::core::RobotState>(
robot_model_);
269 fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
272 RCLCPP_DEBUG(
LOGGER,
"KDL solver initialized");
276 bool KDLKinematicsPlugin::timedOut(
const rclcpp::Time& start_time,
double duration)
const
278 return ((steady_clock_.now() - start_time).seconds() >= duration);
282 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
283 moveit_msgs::msg::MoveItErrorCodes& error_code,
286 std::vector<double> consistency_limits;
294 const std::vector<double>& ik_seed_state,
double timeout,
295 std::vector<double>& solution,
296 moveit_msgs::msg::MoveItErrorCodes& error_code,
299 std::vector<double> consistency_limits;
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,
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,
321 std::vector<double> consistency_limits;
322 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
327 const std::vector<double>& ik_seed_state,
double timeout,
328 const std::vector<double>& consistency_limits, std::vector<double>& solution,
330 moveit_msgs::msg::MoveItErrorCodes& error_code,
333 const rclcpp::Time start_time = steady_clock_.now();
336 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
337 error_code.val = error_code.NO_IK_SOLUTION;
341 if (ik_seed_state.size() != dimension_)
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;
349 std::vector<double> consistency_limits_mimic;
350 if (!consistency_limits.empty())
352 if (consistency_limits.size() != dimension_)
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;
360 for (std::size_t i = 0; i < dimension_; ++i)
362 if (mimic_joints_[i].active)
363 consistency_limits_mimic.push_back(consistency_limits[i]);
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_);
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;
377 solution.resize(dimension_);
379 KDL::Frame pose_desired;
380 tf2::fromMsg(ik_pose, pose_desired);
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);
387 unsigned int attempt = 0;
393 if (!consistency_limits_mimic.empty())
394 getRandomConfiguration(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_in.data);
396 getRandomConfiguration(jnt_pos_in.data);
397 RCLCPP_DEBUG_STREAM(
LOGGER,
"New random configuration (" << attempt <<
"): " << jnt_pos_in);
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)
405 if (!consistency_limits_mimic.empty() &&
406 !checkConsistency(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_out.data))
409 Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
410 if (solution_callback)
412 solution_callback(ik_pose, solution, error_code);
413 if (error_code.val != error_code.SUCCESS)
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");
423 }
while (!timedOut(start_time, timeout));
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;
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
436 double last_delta_twist_norm = DBL_MAX;
437 double step_size = 1.0;
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();
445 RCLCPP_DEBUG_STREAM(
LOGGER,
"Input: " << q_init);
448 bool success =
false;
449 for (i = 0; i < max_iter; ++i)
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);
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_)
465 if (delta_twist_norm >= last_delta_twist_norm)
468 double old_step_size = step_size;
469 step_size *= std::min(0.2, last_delta_twist_norm / delta_twist_norm);
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,
479 last_delta_twist_norm = delta_twist_norm;
481 ik_solver.
CartToJnt(q_out, delta_twist, delta_q, extra_joint_weights * joint_weights.array(), cartesian_weights);
484 clipToJointLimits(q_out, delta_q, extra_joint_weights);
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,
489 if (delta_q_norm < epsilon_)
491 if (step_size < epsilon_)
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();
501 KDL::Add(q_out, delta_q, q_out);
503 RCLCPP_DEBUG_STREAM(
LOGGER,
" delta_q: " << delta_q);
504 RCLCPP_DEBUG_STREAM(
LOGGER,
" q: " << q_out);
507 int result = (i == max_iter) ? -3 : (success ? 0 : -2);
508 RCLCPP_DEBUG_STREAM(
LOGGER,
"Result " << result <<
" after " << i <<
" iterations: " << q_out);
513 void KDLKinematicsPlugin::clipToJointLimits(
const KDL::JntArray& q, KDL::JntArray& q_delta,
514 Eigen::ArrayXd& weighting)
const
517 for (std::size_t i = 0; i < q.rows(); ++i)
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;
528 weighting[mimic_joints_[i].map_index] = 0.01;
533 const std::vector<double>& joint_angles,
534 std::vector<geometry_msgs::msg::Pose>& poses)
const
538 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
541 poses.resize(link_names.size());
542 if (joint_angles.size() != dimension_)
544 RCLCPP_ERROR(
LOGGER,
"Joint angles vector must have size: %d", dimension_);
549 KDL::JntArray jnt_pos_in(dimension_);
550 jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
553 for (
unsigned int i = 0; i < poses.size(); ++i)
555 if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
557 poses[i] = tf2::toMsg(p_out);
561 RCLCPP_ERROR(
LOGGER,
"Could not compute FK for %s", link_names[i].c_str());
570 return solver_info_.joint_names;
575 return solver_info_.link_names;
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...
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.
KDLKinematicsPlugin()
Default constructor.
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.
Eigen::Matrix< double, 6, 1 > Twist
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 ¶m, 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....
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...
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
A set of options for the kinematics solver.
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)