41 #include <tf2_kdl/tf2_kdl.hpp>
43 #if __has_include(<tf2/transform_datatypes.hpp>)
44 #include <tf2/transform_datatypes.hpp>
46 #include <tf2/transform_datatypes.h>
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>
64 static rclcpp::Clock steady_clock = rclcpp::Clock(RCL_ROS_TIME);
70 void KDLKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array)
const
72 state_->setToRandomPositions(joint_model_group_);
73 state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
76 void KDLKinematicsPlugin::getRandomConfiguration(
const Eigen::VectorXd& seed_state,
77 const std::vector<double>& consistency_limits,
78 Eigen::VectorXd& jnt_array)
const
81 &seed_state[0], consistency_limits);
84 bool KDLKinematicsPlugin::checkConsistency(
const Eigen::VectorXd& seed_state,
85 const std::vector<double>& consistency_limits,
86 const Eigen::VectorXd& solution)
const
88 for (std::size_t i = 0; i < dimension_; ++i)
90 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
96 void KDLKinematicsPlugin::getJointWeights()
100 joint_weights_ = std::vector<double>(joint_names.size(), 1.0);
104 for (
const auto& joint_weight : params_.joints_map)
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())
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());
117 joint_weights_.at(it - joint_names.begin()) = joint_weight.second.weight;
123 << Eigen::Map<const Eigen::VectorXd>(joint_weights_.data(), joint_weights_.size()).transpose());
127 const std::string& group_name,
const std::string& base_frame,
128 const std::vector<std::string>& tip_frames,
double search_discretization)
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();
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_)
142 if (!joint_model_group_->
isChain())
144 RCLCPP_ERROR(
getLogger(),
"Group '%s' is not a chain", group_name.c_str());
149 RCLCPP_ERROR(
getLogger(),
"Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
155 if (!kdl_parser::treeFromUrdfModel(*robot_model.
getURDF(), kdl_tree))
157 RCLCPP_ERROR(
getLogger(),
"Could not initialize tree object");
162 RCLCPP_ERROR(
getLogger(),
"Could not initialize chain object");
167 for (std::size_t i = 0; i < joint_model_group_->
getJointModels().size(); ++i)
173 const std::vector<moveit_msgs::msg::JointLimits>& jvec =
175 solver_info_.limits.insert(solver_info_.limits.end(), jvec.begin(), jvec.end());
181 RCLCPP_ERROR(
getLogger(),
"Could not find tip name in joint group '%s'", group_name.c_str());
186 joint_min_.resize(solver_info_.limits.size());
187 joint_max_.resize(solver_info_.limits.size());
189 for (
unsigned int i = 0; i < solver_info_.limits.size(); ++i)
191 joint_min_(i) = solver_info_.limits[i].min_position;
192 joint_max_(i) = solver_info_.limits[i].max_position;
198 unsigned int joint_counter = 0;
199 for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
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);
219 mimic_joint.
joint_name = kdl_chain_.segments[i].getJoint().getName();
222 mimic_joints_.push_back(mimic_joint);
229 if (!mimic_joint.active)
233 for (
JointMimic& mimic_joint_recal : mimic_joints_)
235 if (mimic_joint_recal.joint_name == joint_model->
getName())
237 mimic_joint.map_index = mimic_joint_recal.map_index;
244 state_ = std::make_shared<moveit::core::RobotState>(
robot_model_);
246 fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
249 RCLCPP_DEBUG(
getLogger(),
"KDL solver initialized");
253 bool KDLKinematicsPlugin::timedOut(
const rclcpp::Time& start_time,
double duration)
const
255 return ((steady_clock.now() - start_time).seconds() >= duration);
259 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
260 moveit_msgs::msg::MoveItErrorCodes& error_code,
263 std::vector<double> consistency_limits;
271 const std::vector<double>& ik_seed_state,
double timeout,
272 std::vector<double>& solution,
273 moveit_msgs::msg::MoveItErrorCodes& error_code,
276 std::vector<double> consistency_limits;
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,
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,
298 std::vector<double> consistency_limits;
299 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
304 const std::vector<double>& ik_seed_state,
double timeout,
305 const std::vector<double>& consistency_limits, std::vector<double>& solution,
307 moveit_msgs::msg::MoveItErrorCodes& error_code,
310 const rclcpp::Time start_time = steady_clock.now();
313 RCLCPP_ERROR(
getLogger(),
"kinematics solver not initialized");
314 error_code.val = error_code.NO_IK_SOLUTION;
318 if (ik_seed_state.size() != dimension_)
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;
326 std::vector<double> consistency_limits_mimic;
327 if (!consistency_limits.empty())
329 if (consistency_limits.size() != dimension_)
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;
337 for (std::size_t i = 0; i < dimension_; ++i)
339 if (mimic_joints_[i].active)
340 consistency_limits_mimic.push_back(consistency_limits[i]);
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");
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);
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;
359 solution.resize(dimension_);
361 KDL::Frame pose_desired;
362 tf2::fromMsg(ik_pose, pose_desired);
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);
369 unsigned int attempt = 0;
375 if (!consistency_limits_mimic.empty())
377 getRandomConfiguration(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_in.data);
381 getRandomConfiguration(jnt_pos_in.data);
383 RCLCPP_DEBUG_STREAM(
getLogger(),
"New random configuration (" << attempt <<
"): " << jnt_pos_in);
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)
391 if (!consistency_limits_mimic.empty() &&
392 !checkConsistency(jnt_seed_state.data, consistency_limits_mimic, jnt_pos_out.data))
395 Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
396 if (solution_callback)
398 solution_callback(ik_pose, solution, error_code);
399 if (error_code.val != error_code.SUCCESS)
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");
409 }
while (!timedOut(start_time, timeout));
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;
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
422 double last_delta_twist_norm = DBL_MAX;
423 double step_size = 1.0;
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();
431 RCLCPP_DEBUG_STREAM(
getLogger(),
"Input: " << q_init);
434 bool success =
false;
435 for (i = 0; i < max_iter; ++i)
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);
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)
451 if (delta_twist_norm >= last_delta_twist_norm)
454 double old_step_size = step_size;
455 step_size *= std::min(0.2, last_delta_twist_norm / delta_twist_norm);
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,
465 last_delta_twist_norm = delta_twist_norm;
467 ik_solver.
CartToJnt(q_out, delta_twist, delta_q, extra_joint_weights * joint_weights.array(), cartesian_weights);
470 clipToJointLimits(q_out, delta_q, extra_joint_weights);
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,
475 if (delta_q_norm < params_.epsilon)
477 if (step_size < params_.epsilon)
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();
487 KDL::Add(q_out, delta_q, q_out);
489 RCLCPP_DEBUG_STREAM(
getLogger(),
" delta_q: " << delta_q);
490 RCLCPP_DEBUG_STREAM(
getLogger(),
" q: " << q_out);
493 int result = (i == max_iter) ? -3 : (success ? 0 : -2);
494 RCLCPP_DEBUG_STREAM(
getLogger(),
"Result " << result <<
" after " << i <<
" iterations: " << q_out);
499 void KDLKinematicsPlugin::clipToJointLimits(
const KDL::JntArray& q, KDL::JntArray& q_delta,
500 Eigen::ArrayXd& weighting)
const
503 for (std::size_t i = 0; i < q.rows(); ++i)
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)
509 q_delta(i) = delta_max;
511 else if (q_delta(i) < delta_min)
513 q_delta(i) = delta_min;
520 weighting[mimic_joints_[i].map_index] = 0.01;
525 const std::vector<double>& joint_angles,
526 std::vector<geometry_msgs::msg::Pose>& poses)
const
530 RCLCPP_ERROR(
getLogger(),
"kinematics solver not initialized");
533 poses.resize(link_names.size());
534 if (joint_angles.size() != dimension_)
536 RCLCPP_ERROR(
getLogger(),
"Joint angles vector must have size: %d", dimension_);
541 KDL::JntArray jnt_pos_in(dimension_);
542 jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
545 for (
unsigned int i = 0; i < poses.size(); ++i)
547 if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
549 poses[i] = tf2::toMsg(p_out);
553 RCLCPP_ERROR(
getLogger(),
"Could not compute FK for %s", link_names[i].c_str());
562 return solver_info_.joint_names;
567 return solver_info_.link_names;
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...
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...
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.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)
A set of options for the kinematics solver.