moveit2
The MoveIt Motion Planning Framework for ROS 2.
kdl_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Sachin Chitta, David Lu!!, Ugo Cupcic */
36 
37 #pragma once
38 
39 // ROS
40 #include <rclcpp/rclcpp.hpp>
41 #include <random_numbers/random_numbers.h>
42 
43 // ROS msgs
44 #include <geometry_msgs/msg/pose_stamped.hpp>
45 #include <moveit_msgs/srv/get_position_fk.hpp>
46 #include <moveit_msgs/srv/get_position_ik.hpp>
47 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
48 #include <moveit_msgs/msg/move_it_error_codes.hpp>
49 
50 // KDL
51 #include <kdl/config.h>
52 #include <kdl/chainfksolver.hpp>
53 #include <kdl/chainiksolver.hpp>
54 
55 // MoveIt
60 
61 #include <cfloat>
62 
63 namespace KDL
64 {
65 class ChainIkSolverVelMimicSVD;
66 }
67 
68 namespace kdl_kinematics_plugin
69 {
75 {
76 public:
81 
82  bool
83  getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
84  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
86 
87  bool searchPositionIK(
88  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
89  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
91 
92  bool searchPositionIK(
93  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
94  const std::vector<double>& consistency_limits, std::vector<double>& solution,
95  moveit_msgs::msg::MoveItErrorCodes& error_code,
97 
98  bool searchPositionIK(
99  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
100  std::vector<double>& solution, const IKCallbackFn& solution_callback,
101  moveit_msgs::msg::MoveItErrorCodes& error_code,
103 
104  bool searchPositionIK(
105  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
106  const std::vector<double>& consistency_limits, std::vector<double>& solution,
107  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
109 
110  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
111  std::vector<geometry_msgs::msg::Pose>& poses) const override;
112 
113  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
114  const std::string& group_name, const std::string& base_frame,
115  const std::vector<std::string>& tip_frames, double search_discretization) override;
116 
120  const std::vector<std::string>& getJointNames() const override;
121 
125  const std::vector<std::string>& getLinkNames() const override;
126 
127 protected:
128  typedef Eigen::Matrix<double, 6, 1> Twist;
129 
131  // NOLINTNEXTLINE(readability-identifier-naming)
132  int CartToJnt(KDL::ChainIkSolverVelMimicSVD& ik_solver, const KDL::JntArray& q_init, const KDL::Frame& p_in,
133  KDL::JntArray& q_out, const unsigned int max_iter, const Eigen::VectorXd& joint_weights,
134  const Twist& cartesian_weights) const;
135 
136 private:
137  void getJointWeights();
138  bool timedOut(const rclcpp::Time& start_time, double duration) const;
139 
146  bool checkConsistency(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
147  const Eigen::VectorXd& solution) const;
148 
149  void getRandomConfiguration(Eigen::VectorXd& jnt_array) const;
150 
156  void getRandomConfiguration(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
157  Eigen::VectorXd& jnt_array) const;
158 
160  void clipToJointLimits(const KDL::JntArray& q, KDL::JntArray& q_delta, Eigen::ArrayXd& weighting) const;
161 
162  static rclcpp::Clock steady_clock_;
163 
164  bool initialized_;
165 
166  unsigned int dimension_;
167  moveit_msgs::msg::KinematicSolverInfo solver_info_;
168 
169  const moveit::core::JointModelGroup* joint_model_group_;
170  moveit::core::RobotStatePtr state_;
171  KDL::Chain kdl_chain_;
172  std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
173  std::vector<JointMimic> mimic_joints_;
174  std::vector<double> joint_weights_;
175  Eigen::VectorXd joint_min_, joint_max_;
176 
177  int max_solver_iterations_;
178  double epsilon_;
184  double orientation_vs_position_weight_;
185 };
186 } // namespace kdl_kinematics_plugin
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.
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.
Provides an interface for kinematics solvers.
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.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
A set of options for the kinematics solver.