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 #ifndef PR2_ARM_IK_NODE_H
38 #define PR2_ARM_IK_NODE_H
39 
40 #include <kdl/config.h>
41 #include <kdl/frames.hpp>
42 #include <kdl/jntarray.hpp>
43 #include <kdl/tree.hpp>
45 
47 #include <moveit_msgs/GetPositionFK.h>
48 #include <moveit_msgs/GetPositionIK.h>
49 #include <moveit_msgs/KinematicSolverInfo.h>
50 #include <moveit_msgs/MoveItErrorCodes.h>
51 
52 #include <kdl/chainfksolverpos_recursive.hpp>
53 
54 #include <urdf/model.h>
55 
57 
58 #include <memory>
59 
60 #include "pr2_arm_ik.h"
61 
62 namespace pr2_arm_kinematics
63 {
64 static const int NO_IK_SOLUTION = -1;
65 static const int TIMED_OUT = -2;
66 
68 
69 // minimal stuff necessary
71 {
72 public:
74 
83  PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
84  const std::string& tip_frame_name, const double& search_discretization_angle, const int& free_angle);
85 
86  ~PR2ArmIKSolver() override{};
87 
88 // TODO: simplify after kinetic support is dropped
89 #define KDL_VERSION_LESS(a, b, c) ((KDL_VERSION) < ((a << 16) | (b << 8) | c))
90 #if KDL_VERSION_LESS(1, 4, 0)
92 #else
93  void updateInternalDataStructures() override;
94 #endif
95 #undef KDL_VERSION_LESS
96 
101 
105  bool active_;
106 
107  int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out) override;
108 
109  int cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, const double& timeout);
110 
111  void getSolverInfo(moveit_msgs::KinematicSolverInfo& response)
112  {
113  pr2_arm_ik_.getSolverInfo(response);
114  }
115 
116 private:
117  bool getCount(int& count, const int& max_count, const int& min_count);
118 
120 
122 
123  std::string root_frame_name_;
124 };
125 
126 Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame& p);
127 double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2);
128 void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::KinematicSolverInfo& chain_info);
129 
131 
133 {
134 public:
139 
144  bool isActive();
145 
153  bool
154  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
155  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
157 
166  bool searchPositionIK(
167  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
168  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
179  bool searchPositionIK(
180  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
181  const std::vector<double>& consistency_limits, std::vector<double>& solution,
182  moveit_msgs::MoveItErrorCodes& error_code,
184 
193  bool searchPositionIK(
194  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
195  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
197 
208  bool searchPositionIK(
209  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
210  const std::vector<double>& consistency_limits, std::vector<double>& solution,
211  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
213 
221  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
222  std::vector<geometry_msgs::Pose>& poses) const override;
223 
228  bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
229  const std::string& base_frame, const std::vector<std::string>& tip_frames,
230  double search_discretization) override;
231 
235  const std::vector<std::string>& getJointNames() const override;
236 
240  const std::vector<std::string>& getLinkNames() const override;
241 
242 protected:
243  bool active_;
245  pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_;
246  std::string root_name_;
248  std::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
250  moveit_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
251 
254 
255  void desiredPoseCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
256  moveit_msgs::MoveItErrorCodes& error_code) const;
257 
258  void jointSolutionCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
259  moveit_msgs::MoveItErrorCodes& error_code) const;
260 };
261 } // namespace pr2_arm_kinematics
262 
263 #endif
A set of options for the kinematics solver.
Core components of MoveIt!
MOVEIT_CLASS_FORWARD(PR2ArmIKSolver)
ROSCONSOLE_DECL void initialize()
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
bool getCount(int &count, const int &max_count, const int &min_count)
static const int NO_IK_SOLUTION
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:67
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
Provides an interface for kinematics solvers.
options
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
bool active_
Indicates whether the solver has been successfully initialized.
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking...
moveit_msgs::KinematicSolverInfo ik_solver_info_
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
Definition: pr2_arm_ik.cpp:192
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)
int cartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &response)
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Tue Sep 8 2020 04:12:45