38 #include <kdl/chainfksolverpos_recursive.hpp>
39 #include <kdl/chainiksolverpos_lma.hpp>
41 #include <tf2_kdl/tf2_kdl.hpp>
42 #include <kdl_parser/kdl_parser.hpp>
43 #include <kdl/frames_io.hpp>
44 #include <kdl/kinfam_io.hpp>
47 #include <class_loader/class_loader.hpp>
52 static const rclcpp::Logger LOGGER =
rclcpp::get_logger(
"moveit_lma_kinematics_plugin.lma_kinematics_plugin");
58 void LMAKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array)
const
60 state_->setToRandomPositions(joint_model_group_);
61 state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
64 void LMAKinematicsPlugin::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 LMAKinematicsPlugin::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)
78 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
85 const std::string& group_name,
const std::string& base_frame,
86 const std::vector<std::string>& tip_frames,
double search_discretization)
91 std::string kinematics_param_prefix =
"robot_description_kinematics." + group_name;
92 param_listener_ = std::make_shared<lma_kinematics::ParamListener>(node, kinematics_param_prefix);
93 params_ = param_listener_->get_params();
95 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
96 joint_model_group_ =
robot_model_->getJointModelGroup(group_name);
97 if (!joint_model_group_)
100 if (!joint_model_group_->
isChain())
102 RCLCPP_ERROR(
LOGGER,
"Group '%s' is not a chain", group_name.c_str());
107 RCLCPP_ERROR(
LOGGER,
"Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
113 if (!kdl_parser::treeFromUrdfModel(*robot_model.
getURDF(), kdl_tree))
115 RCLCPP_ERROR(
LOGGER,
"Could not initialize tree object");
120 RCLCPP_ERROR(
LOGGER,
"Could not initialize chain object");
128 joints_.push_back(jm);
129 joint_names_.push_back(jm->getName());
132 dimension_ = joints_.size();
135 state_ = std::make_shared<moveit::core::RobotState>(
robot_model_);
137 fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
140 RCLCPP_DEBUG(
LOGGER,
"LMA solver initialized");
144 bool LMAKinematicsPlugin::timedOut(
const rclcpp::Time& start_time,
double duration)
const
146 return ((node_->now() - start_time).seconds() >= duration);
150 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
151 moveit_msgs::msg::MoveItErrorCodes& error_code,
154 std::vector<double> consistency_limits;
162 const std::vector<double>& ik_seed_state,
double timeout,
163 std::vector<double>& solution,
164 moveit_msgs::msg::MoveItErrorCodes& error_code,
167 std::vector<double> consistency_limits;
174 const std::vector<double>& ik_seed_state,
double timeout,
175 const std::vector<double>& consistency_limits, std::vector<double>& solution,
176 moveit_msgs::msg::MoveItErrorCodes& error_code,
184 const std::vector<double>& ik_seed_state,
double timeout,
185 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
186 moveit_msgs::msg::MoveItErrorCodes& error_code,
189 std::vector<double> consistency_limits;
190 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
194 void LMAKinematicsPlugin::harmonize(Eigen::VectorXd& values)
const
197 for (
auto* jm : joints_)
198 jm->harmonizePosition(&values[i++]);
201 bool LMAKinematicsPlugin::obeysLimits(
const Eigen::VectorXd& values)
const
204 for (
const auto& jm : joints_)
206 if (!jm->satisfiesPositionBounds(&values[i++]))
213 const std::vector<double>& ik_seed_state,
double timeout,
214 const std::vector<double>& consistency_limits, std::vector<double>& solution,
216 moveit_msgs::msg::MoveItErrorCodes& error_code,
219 rclcpp::Time start_time = node_->now();
222 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
223 error_code.val = error_code.NO_IK_SOLUTION;
227 if (ik_seed_state.size() != dimension_)
229 RCLCPP_ERROR(
LOGGER,
"Seed state must have size %d instead of size %zu", dimension_, ik_seed_state.size());
230 error_code.val = error_code.NO_IK_SOLUTION;
234 if (!consistency_limits.empty() && consistency_limits.size() != dimension_)
236 RCLCPP_ERROR_STREAM(
LOGGER,
"Consistency limits be empty or must have size " << dimension_ <<
" instead of size "
237 << consistency_limits.size());
238 error_code.val = error_code.NO_IK_SOLUTION;
242 const auto orientation_vs_position_weight = params_.position_only_ik ? 0.0 : params_.orientation_vs_position;
243 if (orientation_vs_position_weight == 0.0)
244 RCLCPP_INFO(
LOGGER,
"Using position only ik");
246 Eigen::Matrix<double, 6, 1> cartesian_weights;
247 cartesian_weights(0) = 1;
248 cartesian_weights(1) = 1;
249 cartesian_weights(2) = 1;
250 cartesian_weights(3) = orientation_vs_position_weight;
251 cartesian_weights(4) = orientation_vs_position_weight;
252 cartesian_weights(5) = orientation_vs_position_weight;
254 KDL::JntArray jnt_seed_state(dimension_);
255 KDL::JntArray jnt_pos_in(dimension_);
256 KDL::JntArray jnt_pos_out(dimension_);
257 jnt_seed_state.data = Eigen::Map<const Eigen::VectorXd>(ik_seed_state.data(), ik_seed_state.size());
258 jnt_pos_in = jnt_seed_state;
260 KDL::ChainIkSolverPos_LMA ik_solver_pos(kdl_chain_, cartesian_weights, params_.epsilon, params_.max_solver_iterations);
261 solution.resize(dimension_);
263 KDL::Frame pose_desired;
264 tf2::fromMsg(ik_pose, pose_desired);
266 RCLCPP_DEBUG_STREAM(
LOGGER,
"searchPositionIK2: Position request pose is "
267 << ik_pose.position.x <<
' ' << ik_pose.position.y <<
' ' << ik_pose.position.z <<
' '
268 << ik_pose.orientation.x <<
' ' << ik_pose.orientation.y <<
' '
269 << ik_pose.orientation.z <<
' ' << ik_pose.orientation.w);
270 unsigned int attempt = 0;
276 if (!consistency_limits.empty())
278 getRandomConfiguration(jnt_seed_state.data, consistency_limits, jnt_pos_in.data);
282 getRandomConfiguration(jnt_pos_in.data);
284 RCLCPP_DEBUG_STREAM(
LOGGER,
"New random configuration (" << attempt <<
"): " << jnt_pos_in);
287 int ik_valid = ik_solver_pos.CartToJnt(jnt_pos_in, pose_desired, jnt_pos_out);
288 if (ik_valid == 0 ||
options.return_approximate_solution)
290 harmonize(jnt_pos_out.data);
291 if (!consistency_limits.empty() && !checkConsistency(jnt_seed_state.data, consistency_limits, jnt_pos_out.data))
293 if (!obeysLimits(jnt_pos_out.data))
296 Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
297 if (solution_callback)
299 solution_callback(ik_pose, solution, error_code);
300 if (error_code.val != error_code.SUCCESS)
305 error_code.val = error_code.SUCCESS;
306 RCLCPP_DEBUG_STREAM(
LOGGER,
"Solved after " << (node_->now() - start_time).seconds() <<
" < " << timeout
307 <<
"s and " << attempt <<
" attempts");
310 }
while (!timedOut(start_time, timeout));
312 RCLCPP_DEBUG_STREAM(
LOGGER,
"IK timed out after " << (node_->now() - start_time).seconds() <<
" > " << timeout
313 <<
"s and " << attempt <<
" attempts");
314 error_code.val = error_code.TIMED_OUT;
319 const std::vector<double>& joint_angles,
320 std::vector<geometry_msgs::msg::Pose>& poses)
const
324 RCLCPP_ERROR(
LOGGER,
"kinematics solver not initialized");
327 poses.resize(link_names.size());
328 if (joint_angles.size() != dimension_)
330 RCLCPP_ERROR(
LOGGER,
"Joint angles vector must have size: %d", dimension_);
335 KDL::JntArray jnt_pos_in(dimension_);
336 jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
339 for (
unsigned int i = 0; i < poses.size(); ++i)
341 if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
343 poses[i] = tf2::toMsg(p_out);
347 RCLCPP_ERROR(
LOGGER,
"Could not compute FK for %s", link_names[i].c_str());
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
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating....
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_
Implementation of kinematics using Levenberg-Marquardt (LMA) solver from KDL. This version supports a...
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
LMAKinematicsPlugin()
Default constructor.
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 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 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.
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 > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool isChain() const
Check if this group is a linear chain.
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< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
bool isSingleDOFJoints() const
Return true if the group consists only of joints that are single DOF.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
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 get_logger()
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
A set of options for the kinematics solver.