moveit2
The MoveIt Motion Planning Framework for ROS 2.
pr2_arm_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, 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 */
36 
37 #pragma once
38 
39 #include <kdl/config.h>
40 #include <kdl/frames.hpp>
41 #include <kdl/jntarray.hpp>
42 #include <kdl/tree.hpp>
43 #include <kdl_parser/kdl_parser.hpp>
44 
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 #include <kdl/chainfksolverpos_recursive.hpp>
52 
53 #include <urdf/model.h>
54 
56 
57 #include <memory>
58 
59 #include "pr2_arm_ik.h"
60 
61 namespace pr2_arm_kinematics
62 {
63 static const int NO_IK_SOLUTION = -1;
64 static const int TIMED_OUT = -2;
65 
67 
68 // minimal stuff necessary
69 class PR2ArmIKSolver : public KDL::ChainIkSolverPos
70 {
71 public:
73 
82  PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
83  const std::string& tip_frame_name, const double& search_discretization_angle, const int& free_angle);
84 
85  ~PR2ArmIKSolver() override{};
86 
87  void updateInternalDataStructures() override;
88 
93 
97  bool active_;
98 
99  int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out) override;
100 
101  int cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, const double& timeout);
102 
103  void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& response)
104  {
105  pr2_arm_ik_.getSolverInfo(response);
106  }
107 
108 private:
109  bool getCount(int& count, const int& max_count, const int& min_count);
110 
111  double search_discretization_angle_;
112 
113  int free_angle_;
114 
115  std::string root_frame_name_;
116 };
117 
118 Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame& p);
119 double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2);
120 void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info);
121 
123 
125 {
126 public:
131 
136  bool isActive();
137 
145  bool
146  getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
147  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
149 
158  bool searchPositionIK(
159  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
160  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
171  bool searchPositionIK(
172  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
173  const std::vector<double>& consistency_limits, std::vector<double>& solution,
174  moveit_msgs::msg::MoveItErrorCodes& error_code,
176 
185  bool searchPositionIK(
186  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
187  std::vector<double>& solution, const IKCallbackFn& solution_callback,
188  moveit_msgs::msg::MoveItErrorCodes& error_code,
190 
201  bool searchPositionIK(
202  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
203  const std::vector<double>& consistency_limits, std::vector<double>& solution,
204  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
206 
214  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
215  std::vector<geometry_msgs::msg::Pose>& poses) const override;
216 
221  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
222  const std::string& group_name, const std::string& base_frame,
223  const std::vector<std::string>& tip_frames, double search_discretization) override;
224 
228  const std::vector<std::string>& getJointNames() const override;
229 
233  const std::vector<std::string>& getLinkNames() const override;
234 
235 protected:
236  bool active_;
238  pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_;
239  std::string root_name_;
241  std::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
242  KDL::Chain kdl_chain_;
243  moveit_msgs::msg::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
244 
247 
248  void desiredPoseCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
249  moveit_msgs::msg::MoveItErrorCodes& error_code) const;
250 
251  void jointSolutionCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
252  moveit_msgs::msg::MoveItErrorCodes& error_code) const;
253 };
254 } // namespace pr2_arm_kinematics
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
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
int cartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &response)
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
PR2ArmIKSolver(const urdf::ModelInterface &robot_model, const std::string &root_frame_name, const std::string &tip_frame_name, const double &search_discretization_angle, const int &free_angle)
bool active_
Indicates whether the solver has been successfully initialized.
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
Definition: pr2_arm_ik.cpp:196
bool isActive()
Specifies if the node is active or not.
void desiredPoseCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::msg::MoveItErrorCodes &error_code) const
moveit_msgs::msg::KinematicSolverInfo ik_solver_info_
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.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
moveit_msgs::msg::KinematicSolverInfo fk_solver_info_
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.
void jointSolutionCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::msg::MoveItErrorCodes &error_code) const
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.
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
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....
p
Definition: pick.py:62
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::msg::KinematicSolverInfo &chain_info)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
MOVEIT_CLASS_FORWARD(PR2ArmIKSolver)
A set of options for the kinematics solver.