hand_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Sachin Chitta
36 * Modified by Guillaume WALCK (UPMC) 2012
37 *
38 *********************************************************************/
39 
40 #ifndef HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H
41 #define HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H
42 
43 #include <ros/ros.h>
44 #include <angles/angles.h>
45 
47 
48 #include <tf/tf.h>
49 #include <tf/transform_listener.h>
50 #include <tf/transform_datatypes.h>
51 
52 #include <kdl/jntarray.hpp>
54 #include <kdl/chainfksolverpos_recursive.hpp>
57 #include <moveit_msgs/KinematicSolverInfo.h>
58 #include <urdf/model.h>
59 #include <string>
60 #include <vector>
61 
62 #include <tf_conversions/tf_kdl.h>
63 #include <moveit_msgs/MoveItErrorCodes.h>
64 #include <boost/shared_ptr.hpp>
66 
67 namespace hand_kinematics
68 {
71 {
72 public:
77 
82 bool isActive();
83 
88 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
89  const std::vector<double> &ik_seed_state,
90  std::vector<double> &solution,
91  moveit_msgs::MoveItErrorCodes &error_code,
94 
95 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
96  const std::vector<double> &ik_seed_state,
97  double timeout,
98  std::vector<double> &solution,
99  moveit_msgs::MoveItErrorCodes &error_code,
102 
103 
104 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
105  const std::vector<double> &ik_seed_state,
106  double timeout,
107  const std::vector<double> &consistency_limits,
108  std::vector<double> &solution,
109  moveit_msgs::MoveItErrorCodes &error_code,
112 
113 
119 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
120  const std::vector<double> &ik_seed_state,
121  double timeout,
122  std::vector<double> &solution,
123  const IKCallbackFn &solution_callback,
124  moveit_msgs::MoveItErrorCodes &error_code,
127 
133 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
134  const std::vector<double> &ik_seed_state,
135  double timeout,
136  const std::vector<double> &consistency_limits,
137  std::vector<double> &solution,
138  const IKCallbackFn &solution_callback,
139  moveit_msgs::MoveItErrorCodes &error_code,
142 
143 
151 virtual bool getPositionFK(const std::vector<std::string> &link_names,
152  const std::vector<double> &joint_angles,
153  std::vector<geometry_msgs::Pose> &poses) const;
154 
155 
160 virtual bool initialize(const std::string &robot_description,
161  const std::string &group_name,
162  const std::string &base_frame,
163  const std::string &tip_frame,
164  double search_discretization);
165 
166 
170 const std::vector<std::string> &getJointNames() const;
171 
175 const std::vector<std::string> &getLinkNames() const;
176 
177 protected:
178 bool active_;
182 
186 moveit_msgs::KinematicSolverInfo solver_info_;
187 
188 std::string finger_base_name;
191 
193 
195 
196 moveit_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
197 
202 void generateRandomJntSeed(KDL::JntArray &jnt_pos_in) const;
203 };
204 } // namespace hand_kinematics
205 
206 #endif // HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
moveit_msgs::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
virtual 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.
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Initialization function for the kinematics.
KDL::ChainIkSolverPos_NR_JL_coupling * ik_solver_pos
void generateRandomJntSeed(KDL::JntArray &jnt_pos_in) const
This method generates a random joint array vector between the joint limits so that local minima in IK...
moveit_msgs::KinematicSolverInfo solver_info_
KDL::ChainFkSolverPos_recursive * fk_solver
virtual 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.
options
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo fk_solver_info_
bool isActive()
Specifies if the node is active or not.
KDL::ChainIkSolverVel_wdls_coupling * ik_solver_vel
virtual 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
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_


hand_kinematics
Author(s): Juan Antonio Corrales Ramon (UPMC),, Guillaume Walck (CITEC)
autogenerated on Wed Oct 14 2020 04:05:07