40 #include <tf2_kdl/tf2_kdl.hpp>
41 #include <tf2/transform_datatypes.h>
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>
50 static rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_kdl_kinematics_plugin.kdl_kinematics_plugin");
52 rclcpp::Clock KDLKinematicsPlugin::steady_clock_{ RCL_STEADY_TIME };
58 void KDLKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array)
const
60 state_->setToRandomPositions(joint_model_group_);
61 state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
64 void KDLKinematicsPlugin::getRandomConfiguration(
const Eigen::VectorXd& seed_state,
65 const std::vector<double>& consistency_limits,
66 Eigen::VectorXd& jnt_array)
const
69 &seed_state[0], consistency_limits);
72 bool KDLKinematicsPlugin::checkConsistency(
const Eigen::VectorXd& seed_state,
73 const std::vector<double>& consistency_limits,
74 const Eigen::VectorXd& solution)
const
76 for (std::size_t i = 0; i < dimension_; ++i)
77 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
82 void KDLKinematicsPlugin::getJointWeights()
85 std::vector<std::string> names;
86 std::vector<double> weights;
89 if (!
lookupParam(
node_,
"joint_weights.names", names, names) || (names.size() != weights.size()))
91 RCLCPP_ERROR(
LOGGER,
"Expecting list parameter joint_weights.names of same size as list joint_weights.weights");
99 std::size_t num_active = active_names.size();
100 if (weights.size() == num_active)
102 joint_weights_ = weights;
105 else if (!weights.empty())
107 RCLCPP_ERROR(
LOGGER,
"Expecting parameter joint_weights to list weights for all active joints (%zu) in order",
115 joint_weights_ = std::vector<double>(active_names.size(), 1.0);
120 assert(names.size() == weights.size());
121 for (
size_t i = 0; i != names.size(); ++i)
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());
130 joint_weights_[it - active_names.begin()] = weights[i];
133 LOGGER,
"Joint weights for group '"
135 << Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()).transpose());
139 const std::string& group_name,
const std::string& base_frame,
140 const std::vector<std::string>& tip_frames,
double search_discretization)
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_)
148 if (!joint_model_group_->
isChain())
150 RCLCPP_ERROR(
LOGGER,
"Group '%s' is not a chain", group_name.c_str());
155 RCLCPP_ERROR(
LOGGER,
"Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
161 if (!kdl_parser::treeFromUrdfModel(*robot_model.
getURDF(), kdl_tree))
163 RCLCPP_ERROR(
LOGGER,
"Could not initialize tree object");
168 RCLCPP_ERROR(
LOGGER,
"Could not initialize chain object");
173 for (std::size_t i = 0; i < joint_model_group_->
getJointModels().size(); ++i)
179 const std::vector<moveit_msgs::msg::JointLimits>& jvec =
181 solver_info_.limits.insert(solver_info_.limits.end(), jvec.begin(), jvec.end());
187 RCLCPP_ERROR(
LOGGER,
"Could not find tip name in joint group '%s'", group_name.c_str());
192 joint_min_.resize(solver_info_.limits.size());
193 joint_max_.resize(solver_info_.limits.size());
195 for (
unsigned int i = 0; i < solver_info_.limits.size(); ++i)
197 joint_min_(i) = solver_info_.limits[i].min_position;
198 joint_max_(i) = solver_info_.limits[i].max_position;
204 lookupParam(
node_,
"orientation_vs_position", orientation_vs_position_weight_, 1.0);
209 orientation_vs_position_weight_ = 0.0;
210 if (orientation_vs_position_weight_ == 0.0)
211 RCLCPP_INFO(
LOGGER,
"Using position only ik");
216 unsigned int joint_counter = 0;
217 for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
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);
237 mimic_joint.
joint_name = kdl_chain_.segments[i].getJoint().getName();
240 mimic_joints_.push_back(mimic_joint);
247 if (!mimic_joint.active)
251 for (
JointMimic& mimic_joint_recal : mimic_joints_)
253 if (mimic_joint_recal.joint_name == joint_model->
getName())
255 mimic_joint.map_index = mimic_joint_recal.map_index;
262 state_ = std::make_shared<moveit::core::RobotState>(
robot_model_);
264 fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
267 RCLCPP_DEBUG(
LOGGER,
"KDL solver initialized");
271 bool KDLKinematicsPlugin::timedOut(
const rclcpp::Time& start_time,
double duration)
const
273 return ((steady_clock_.now() - start_time).seconds() >= duration);
277 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
278 moveit_msgs::msg::MoveItErrorCodes& error_code,
281 std::vector<double> consistency_limits;
289 const std::vector<double>& ik_seed_state,
double timeout,
290 std::vector<double>& solution,
291 moveit_msgs::msg::MoveItErrorCodes& error_code,
294 std::vector<double> consistency_limits;
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,
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,
316 std::vector<double> consistency_limits;
317 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
322 const std::vector<double>& ik_seed_state,
double timeout,
323 const std::vector<double>& consistency_limits, std::vector<double>& solution,
325 moveit_msgs::msg::MoveItErrorCodes& error_code,
328 const rclcpp::Time start_time = steady_clock_.now();
331 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
332 error_code.val = error_code.NO_IK_SOLUTION;
336 if (ik_seed_state.size() != dimension_)
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;
344 std::vector<double> consistency_limits_mimic;
345 if (!consistency_limits.empty())
347 if (consistency_limits.size() != dimension_)
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;
355 for (std::size_t i = 0; i < dimension_; ++i)
357 if (mimic_joints_[i].active)
358 consistency_limits_mimic.push_back(consistency_limits[i]);
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_);
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;
372 solution.resize(dimension_);
374 KDL::Frame pose_desired;
375 tf2::fromMsg(ik_pose, pose_desired);
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);
382 unsigned int attempt = 0;
388 if (!consistency_limits_mimic.empty())
389 getRandomConfiguration(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_in.data);
391 getRandomConfiguration(jnt_pos_in.data);
392 RCLCPP_DEBUG_STREAM(
LOGGER,
"New random configuration (" << attempt <<
"): " << jnt_pos_in);
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)
400 if (!consistency_limits_mimic.empty() &&
401 !checkConsistency(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_out.data))
404 Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
405 if (solution_callback)
407 solution_callback(ik_pose, solution, error_code);
408 if (error_code.val != error_code.SUCCESS)
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");
418 }
while (!timedOut(start_time, timeout));
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;
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
431 double last_delta_twist_norm = DBL_MAX;
432 double step_size = 1.0;
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();
440 RCLCPP_DEBUG_STREAM(
LOGGER,
"Input: " << q_init);
443 bool success =
false;
444 for (i = 0; i < max_iter; ++i)
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);
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_)
460 if (delta_twist_norm >= last_delta_twist_norm)
463 double old_step_size = step_size;
464 step_size *= std::min(0.2, last_delta_twist_norm / delta_twist_norm);
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,
474 last_delta_twist_norm = delta_twist_norm;
476 ik_solver.
CartToJnt(q_out, delta_twist, delta_q, extra_joint_weights * joint_weights.array(), cartesian_weights);
479 clipToJointLimits(q_out, delta_q, extra_joint_weights);
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,
484 if (delta_q_norm < epsilon_)
486 if (step_size < epsilon_)
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();
496 KDL::Add(q_out, delta_q, q_out);
498 RCLCPP_DEBUG_STREAM(
LOGGER,
" delta_q: " << delta_q);
499 RCLCPP_DEBUG_STREAM(
LOGGER,
" q: " << q_out);
502 int result = (i == max_iter) ? -3 : (success ? 0 : -2);
503 RCLCPP_DEBUG_STREAM(
LOGGER,
"Result " << result <<
" after " << i <<
" iterations: " << q_out);
508 void KDLKinematicsPlugin::clipToJointLimits(
const KDL::JntArray& q, KDL::JntArray& q_delta,
509 Eigen::ArrayXd& weighting)
const
512 for (std::size_t i = 0; i < q.rows(); ++i)
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;
523 weighting[mimic_joints_[i].map_index] = 0.01;
528 const std::vector<double>& joint_angles,
529 std::vector<geometry_msgs::msg::Pose>& poses)
const
533 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
536 poses.resize(link_names.size());
537 if (joint_angles.size() != dimension_)
539 RCLCPP_ERROR(
LOGGER,
"Joint angles vector must have size: %d", dimension_);
544 KDL::JntArray jnt_pos_in(dimension_);
545 jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
548 for (
unsigned int i = 0; i < poses.size(); ++i)
550 if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
552 poses[i] = tf2::toMsg(p_out);
556 RCLCPP_ERROR(
LOGGER,
"Could not compute FK for %s", link_names[i].c_str());
565 return solver_info_.joint_names;
570 return solver_info_.link_names;
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...
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)