pr2_arm_kinematics.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 <ros/ros.h>
41 #include <tf/tf.h>
42 #include <tf/transform_listener.h>
43 
44 #include <angles/angles.h>
46 #include <tf_conversions/tf_kdl.h>
47 
48 #include <kinematics_msgs/GetPositionFK.h>
49 #include <kinematics_msgs/GetPositionIK.h>
50 #include <kinematics_msgs/GetKinematicSolverInfo.h>
51 #include <moveit_msgs/MoveItErrorCodes.h>
52 
53 #include <kdl/chainfksolverpos_recursive.hpp>
54 
55 #include <boost/shared_ptr.hpp>
56 
57 namespace pr2_arm_kinematics
58 {
60 {
61 public:
75  PR2ArmKinematics(bool create_transform_listener = true);
76 
77  virtual ~PR2ArmKinematics();
78 
83  bool isActive();
84 
90  virtual bool getPositionIK(kinematics_msgs::GetPositionIK::Request& request,
91  kinematics_msgs::GetPositionIK::Response& response);
92 
99  bool getIKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request& request,
100  kinematics_msgs::GetKinematicSolverInfo::Response& response);
101 
108  bool getFKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request& request,
109  kinematics_msgs::GetKinematicSolverInfo::Response& response);
110 
116  bool getPositionFK(kinematics_msgs::GetPositionFK::Request& request,
117  kinematics_msgs::GetPositionFK::Response& response);
118 
119 protected:
120  // Helper function that assumes that everything is in the correct frame
121  bool getPositionIKHelper(kinematics_msgs::GetPositionIK::Request& request,
122  kinematics_msgs::GetPositionIK::Response& response);
123 
124  virtual bool transformPose(const std::string& des_frame, const geometry_msgs::PoseStamped& pose_in,
125  geometry_msgs::PoseStamped& pose_out);
126 
127  bool active_;
135  std::string root_name_;
139  kinematics_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
140 };
141 }
142 
143 #endif
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
bool getPositionFK(kinematics_msgs::GetPositionFK::Request &request, kinematics_msgs::GetPositionFK::Response &response)
This is the basic forward kinematics service that will return information about the kinematics node...
Namespace for the PR2ArmKinematics.
bool getIKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response)
This is the basic kinematics info service that will return information about the kinematics node...
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
kinematics_msgs::KinematicSolverInfo fk_solver_info_
PR2ArmKinematics(bool create_transform_listener=true)
bool getFKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response)
This is the basic kinematics info service that will return information about the kinematics node...
bool getPositionIKHelper(kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response)
kinematics_msgs::KinematicSolverInfo ik_solver_info_
virtual bool transformPose(const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)
virtual bool getPositionIK(kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response)
This is the basic IK service method that will compute and return an IK solution.
bool isActive()
Specifies if the node is active or not.
const std::string response


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Feb 28 2022 22:51:25