trac_ik_kinematics_plugin.hpp
Go to the documentation of this file.
1 /********************************************************************************
2 Copyright (c) 2015, TRACLabs, Inc.
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software
17  without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
22 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
23 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
26 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
27 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
28 OF THE POSSIBILITY OF SUCH DAMAGE.
29 ********************************************************************************/
30 
31 #ifndef TRAC_IK_KINEMATICS_PLUGIN_
32 #define TRAC_IK_KINEMATICS_PLUGIN_
33 
35 #include <kdl/chain.hpp>
36 
38 {
39 
41 {
42  std::vector<std::string> joint_names_;
43  std::vector<std::string> link_names_;
44 
46  bool active_; // Internal variable that indicates whether solvers are configured and ready
47 
50 
52 
53  std::string solve_type;
54 
55 public:
56  const std::vector<std::string>& getJointNames() const
57  {
58  return joint_names_;
59  }
60  const std::vector<std::string>& getLinkNames() const
61  {
62  return link_names_;
63  }
64 
65 
69  TRAC_IKKinematicsPlugin(): active_(false), position_ik_(false) {}
70 
72  {
73  }
74 
84  // Returns the first IK solution that is within joint limits, this is called by get_ik() service
85  bool getPositionIK(const geometry_msgs::Pose &ik_pose,
86  const std::vector<double> &ik_seed_state,
87  std::vector<double> &solution,
88  moveit_msgs::MoveItErrorCodes &error_code,
90 
99  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
100  const std::vector<double> &ik_seed_state,
101  double timeout,
102  std::vector<double> &solution,
103  moveit_msgs::MoveItErrorCodes &error_code,
105 
115  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
116  const std::vector<double> &ik_seed_state,
117  double timeout,
118  const std::vector<double> &consistency_limits,
119  std::vector<double> &solution,
120  moveit_msgs::MoveItErrorCodes &error_code,
122 
131  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
132  const std::vector<double> &ik_seed_state,
133  double timeout,
134  std::vector<double> &solution,
135  const IKCallbackFn &solution_callback,
136  moveit_msgs::MoveItErrorCodes &error_code,
138 
149  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
150  const std::vector<double> &ik_seed_state,
151  double timeout,
152  const std::vector<double> &consistency_limits,
153  std::vector<double> &solution,
154  const IKCallbackFn &solution_callback,
155  moveit_msgs::MoveItErrorCodes &error_code,
157 
158  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
159  const std::vector<double> &ik_seed_state,
160  double timeout,
161  std::vector<double> &solution,
162  const IKCallbackFn &solution_callback,
163  moveit_msgs::MoveItErrorCodes &error_code,
164  const std::vector<double> &consistency_limits,
166 
167 
179  bool getPositionFK(const std::vector<std::string> &link_names,
180  const std::vector<double> &joint_angles,
181  std::vector<geometry_msgs::Pose> &poses) const;
182 
183 
184  bool initialize(const std::string &robot_description,
185  const std::string& group_name,
186  const std::string& base_name,
187  const std::string& tip_name,
188  double search_discretization);
189 
190 private:
191 
192  int getKDLSegmentIndex(const std::string &name) const;
193 
194 }; // end class
195 }
196 
197 #endif
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, compute the joint angles to reach it.
options
const std::vector< std::string > & getJointNames() const
bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
const std::vector< std::string > & getLinkNames() const
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, search for the joint angles required to reach it...


trac_ik_kinematics_plugin
Author(s): Patrick Beeson
autogenerated on Tue Jun 1 2021 02:38:39