moveit2
The MoveIt Motion Planning Framework for ROS 2.
lma_kinematics_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, CRI group, NTU, Singapore
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 CRI group 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: Francisco Suarez-Ruiz */
36 
38 #include <kdl/chainfksolverpos_recursive.hpp>
39 #include <kdl/chainiksolverpos_lma.hpp>
40 
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>
45 
46 // register as a KinematicsBase implementation
47 #include <class_loader/class_loader.hpp>
49 
50 namespace lma_kinematics_plugin
51 {
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_lma_kinematics_plugin.lma_kinematics_plugin");
53 
55 {
56 }
57 
58 void LMAKinematicsPlugin::getRandomConfiguration(Eigen::VectorXd& jnt_array) const
59 {
60  state_->setToRandomPositions(joint_model_group_);
61  state_->copyJointGroupPositions(joint_model_group_, &jnt_array[0]);
62 }
63 
64 void LMAKinematicsPlugin::getRandomConfiguration(const Eigen::VectorXd& seed_state,
65  const std::vector<double>& consistency_limits,
66  Eigen::VectorXd& jnt_array) const
67 {
68  joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), &jnt_array[0],
69  &seed_state[0], consistency_limits);
70 }
71 
72 bool LMAKinematicsPlugin::checkConsistency(const Eigen::VectorXd& seed_state,
73  const std::vector<double>& consistency_limits,
74  const Eigen::VectorXd& solution) const
75 {
76  for (std::size_t i = 0; i < dimension_; ++i)
77  {
78  if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
79  return false;
80  }
81  return true;
82 }
83 
84 bool LMAKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
85  const std::string& group_name, const std::string& base_frame,
86  const std::vector<std::string>& tip_frames, double search_discretization)
87 {
88  node_ = node;
89 
90  // Get Solver Parameters
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();
94 
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_)
98  return false;
99 
100  if (!joint_model_group_->isChain())
101  {
102  RCLCPP_ERROR(LOGGER, "Group '%s' is not a chain", group_name.c_str());
103  return false;
104  }
105  if (!joint_model_group_->isSingleDOFJoints())
106  {
107  RCLCPP_ERROR(LOGGER, "Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
108  return false;
109  }
110 
111  KDL::Tree kdl_tree;
112 
113  if (!kdl_parser::treeFromUrdfModel(*robot_model.getURDF(), kdl_tree))
114  {
115  RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
116  return false;
117  }
118  if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
119  {
120  RCLCPP_ERROR(LOGGER, "Could not initialize chain object");
121  return false;
122  }
123 
124  for (const moveit::core::JointModel* jm : joint_model_group_->getJointModels())
125  {
126  if (jm->getType() == moveit::core::JointModel::REVOLUTE || jm->getType() == moveit::core::JointModel::PRISMATIC)
127  {
128  joints_.push_back(jm);
129  joint_names_.push_back(jm->getName());
130  }
131  }
132  dimension_ = joints_.size();
133 
134  // Setup the joint state groups that we need
135  state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
136 
137  fk_solver_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
138 
139  initialized_ = true;
140  RCLCPP_DEBUG(LOGGER, "LMA solver initialized");
141  return true;
142 }
143 
144 bool LMAKinematicsPlugin::timedOut(const rclcpp::Time& start_time, double duration) const
145 {
146  return ((node_->now() - start_time).seconds() >= duration);
147 }
148 
149 bool LMAKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
150  const std::vector<double>& ik_seed_state, std::vector<double>& solution,
151  moveit_msgs::msg::MoveItErrorCodes& error_code,
153 {
154  std::vector<double> consistency_limits;
155 
156  // limit search to a single attempt by setting a timeout of zero
157  return searchPositionIK(ik_pose, ik_seed_state, 0.0, consistency_limits, solution, IKCallbackFn(), error_code,
158  options);
159 }
160 
161 bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
162  const std::vector<double>& ik_seed_state, double timeout,
163  std::vector<double>& solution,
164  moveit_msgs::msg::MoveItErrorCodes& error_code,
166 {
167  std::vector<double> consistency_limits;
168 
169  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
170  options);
171 }
172 
173 bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
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,
178 {
179  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
180  options);
181 }
182 
183 bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
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,
188 {
189  std::vector<double> consistency_limits;
190  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
191  options);
192 }
193 
194 void LMAKinematicsPlugin::harmonize(Eigen::VectorXd& values) const
195 {
196  size_t i = 0;
197  for (auto* jm : joints_)
198  jm->harmonizePosition(&values[i++]);
199 }
200 
201 bool LMAKinematicsPlugin::obeysLimits(const Eigen::VectorXd& values) const
202 {
203  size_t i = 0;
204  for (const auto& jm : joints_)
205  {
206  if (!jm->satisfiesPositionBounds(&values[i++]))
207  return false;
208  }
209  return true;
210 }
211 
212 bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
213  const std::vector<double>& ik_seed_state, double timeout,
214  const std::vector<double>& consistency_limits, std::vector<double>& solution,
215  const IKCallbackFn& solution_callback,
216  moveit_msgs::msg::MoveItErrorCodes& error_code,
218 {
219  rclcpp::Time start_time = node_->now();
220  if (!initialized_)
221  {
222  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
223  error_code.val = error_code.NO_IK_SOLUTION;
224  return false;
225  }
226 
227  if (ik_seed_state.size() != dimension_)
228  {
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;
231  return false;
232  }
233 
234  if (!consistency_limits.empty() && consistency_limits.size() != dimension_)
235  {
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;
239  return false;
240  }
241 
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");
245 
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;
253 
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;
259 
260  KDL::ChainIkSolverPos_LMA ik_solver_pos(kdl_chain_, cartesian_weights, params_.epsilon, params_.max_solver_iterations);
261  solution.resize(dimension_);
262 
263  KDL::Frame pose_desired;
264  tf2::fromMsg(ik_pose, pose_desired);
265 
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;
271  do
272  {
273  ++attempt;
274  if (attempt > 1) // randomly re-seed after first attempt
275  {
276  if (!consistency_limits.empty())
277  {
278  getRandomConfiguration(jnt_seed_state.data, consistency_limits, jnt_pos_in.data);
279  }
280  else
281  {
282  getRandomConfiguration(jnt_pos_in.data);
283  }
284  RCLCPP_DEBUG_STREAM(LOGGER, "New random configuration (" << attempt << "): " << jnt_pos_in);
285  }
286 
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) // found acceptable solution
289  {
290  harmonize(jnt_pos_out.data);
291  if (!consistency_limits.empty() && !checkConsistency(jnt_seed_state.data, consistency_limits, jnt_pos_out.data))
292  continue;
293  if (!obeysLimits(jnt_pos_out.data))
294  continue;
295 
296  Eigen::Map<Eigen::VectorXd>(solution.data(), solution.size()) = jnt_pos_out.data;
297  if (solution_callback)
298  {
299  solution_callback(ik_pose, solution, error_code);
300  if (error_code.val != error_code.SUCCESS)
301  continue;
302  }
303 
304  // solution passed consistency check and solution callback
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");
308  return true;
309  }
310  } while (!timedOut(start_time, timeout));
311 
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;
315  return false;
316 }
317 
318 bool LMAKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
319  const std::vector<double>& joint_angles,
320  std::vector<geometry_msgs::msg::Pose>& poses) const
321 {
322  if (!initialized_)
323  {
324  RCLCPP_ERROR(LOGGER, "kinematics solver not initialized");
325  return false;
326  }
327  poses.resize(link_names.size());
328  if (joint_angles.size() != dimension_)
329  {
330  RCLCPP_ERROR(LOGGER, "Joint angles vector must have size: %d", dimension_);
331  return false;
332  }
333 
334  KDL::Frame p_out;
335  KDL::JntArray jnt_pos_in(dimension_);
336  jnt_pos_in.data = Eigen::Map<const Eigen::VectorXd>(joint_angles.data(), joint_angles.size());
337 
338  bool valid = true;
339  for (unsigned int i = 0; i < poses.size(); ++i)
340  {
341  if (fk_solver_->JntToCart(jnt_pos_in, p_out) >= 0)
342  {
343  poses[i] = tf2::toMsg(p_out);
344  }
345  else
346  {
347  RCLCPP_ERROR(LOGGER, "Could not compute FK for %s", link_names[i].c_str());
348  valid = false;
349  }
350  }
351  return valid;
352 }
353 
354 const std::vector<std::string>& LMAKinematicsPlugin::getJointNames() const
355 {
356  return joint_names_;
357 }
358 
359 const std::vector<std::string>& LMAKinematicsPlugin::getLinkNames() const
360 {
361  return getTipFrames();
362 }
363 
364 } // namespace lma_kinematics_plugin
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.
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: joint_model.h:117
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.
Definition: robot_model.h:106
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
A set of options for the kinematics solver.