moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#include <kdl_kinematics_parameters.hpp>
43
44// ROS msgs
45#include <geometry_msgs/msg/pose_stamped.hpp>
46#include <moveit_msgs/srv/get_position_fk.hpp>
47#include <moveit_msgs/srv/get_position_ik.hpp>
48#include <moveit_msgs/msg/kinematic_solver_info.hpp>
49#include <moveit_msgs/msg/move_it_error_codes.hpp>
50
51// KDL
52#include <kdl/config.h>
53#include <kdl/chainfksolver.hpp>
54#include <kdl/chainiksolver.hpp>
55
56// MoveIt
61
62#include <cfloat>
63
64namespace KDL
65{
66class ChainIkSolverVelMimicSVD;
67}
68
70{
76{
77public:
82
83 bool
84 getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
85 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
87
89 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
90 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
92
94 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
95 const std::vector<double>& consistency_limits, std::vector<double>& solution,
96 moveit_msgs::msg::MoveItErrorCodes& error_code,
98
100 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
101 std::vector<double>& solution, const IKCallbackFn& solution_callback,
102 moveit_msgs::msg::MoveItErrorCodes& error_code,
104
105 bool searchPositionIK(
106 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
107 const std::vector<double>& consistency_limits, std::vector<double>& solution,
108 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
110
111 bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
112 std::vector<geometry_msgs::msg::Pose>& poses) const override;
113
114 bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
115 const std::string& group_name, const std::string& base_frame,
116 const std::vector<std::string>& tip_frames, double search_discretization) override;
117
121 const std::vector<std::string>& getJointNames() const override;
122
126 const std::vector<std::string>& getLinkNames() const override;
127
128protected:
129 typedef Eigen::Matrix<double, 6, 1> Twist;
130
132 // NOLINTNEXTLINE(readability-identifier-naming)
133 int CartToJnt(KDL::ChainIkSolverVelMimicSVD& ik_solver, const KDL::JntArray& q_init, const KDL::Frame& p_in,
134 KDL::JntArray& q_out, const unsigned int max_iter, const Eigen::VectorXd& joint_weights,
135 const Twist& cartesian_weights) const;
136
137private:
138 void getJointWeights();
139 bool timedOut(const rclcpp::Time& start_time, double duration) const;
140
147 bool checkConsistency(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
148 const Eigen::VectorXd& solution) const;
149
150 void getRandomConfiguration(Eigen::VectorXd& jnt_array) const;
151
157 void getRandomConfiguration(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
158 Eigen::VectorXd& jnt_array) const;
159
161 void clipToJointLimits(const KDL::JntArray& q, KDL::JntArray& q_delta, Eigen::ArrayXd& weighting) const;
162
163 bool initialized_;
164
165 unsigned int dimension_;
166 moveit_msgs::msg::KinematicSolverInfo solver_info_;
167
168 const moveit::core::JointModelGroup* joint_model_group_;
169 moveit::core::RobotStatePtr state_;
170 KDL::Chain kdl_chain_;
171 std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
172 std::vector<JointMimic> mimic_joints_;
173 std::vector<double> joint_weights_;
174 Eigen::VectorXd joint_min_, joint_max_;
175
176 std::shared_ptr<kdl_kinematics::ParamListener> param_listener_;
177 kdl_kinematics::Params params_;
178};
179} // 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.