pr2_arm_kinematics_utils.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 MOVEIT_PR2_ARM_IK_UTILS_
38 #define MOVEIT_PR2_ARM_IK_UTILS_
39 
40 #include <ros/ros.h>
41 #include <vector>
42 #include <angles/angles.h>
43 #include <Eigen/Core>
44 #include <kdl/frames.hpp>
45 #include <kdl/jntarray.hpp>
46 #include <kdl/tree.hpp>
47 #include <urdf/model.h>
49 #include <tf/tf.h>
50 #include <tf/transform_listener.h>
51 #include <tf_conversions/tf_kdl.h>
52 
53 #include <moveit_msgs/GetPositionFK.h>
54 #include <moveit_msgs/GetPositionIK.h>
55 #include <moveit_msgs/KinematicSolverInfo.h>
56 
57 using namespace angles;
58 
59 namespace pr2_arm_kinematics
60 {
61  Eigen::Matrix4f KDLToEigenMatrix(const KDL::Frame &p);
62 
63  double computeEuclideanDistance(const std::vector<double> &array_1,
64  const KDL::JntArray &array_2);
65 
66  double distance(const urdf::Pose &transform);
67 
68  bool solveQuadratic(const double &a,
69  const double &b,
70  const double &c,
71  double *x1,
72  double *x2);
73 
74  Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g);
75 
76  bool solveCosineEqn(const double &a,
77  const double &b,
78  const double &c,
79  double &soln1,
80  double &soln2);
81 
82  bool loadRobotModel(ros::NodeHandle node_handle,
83  urdf::Model &robot_model,
84  std::string &xml_string);
85 
86  bool getKDLChain(const std::string &xml_string,
87  const std::string &root_name,
88  const std::string &tip_name,
89  KDL::Chain &kdl_chain);
90 
91  bool getKDLTree(const std::string &xml_string,
92  const std::string &root_name,
93  const std::string &tip_name,
94  KDL::Tree &kdl_chain);
95 
96  bool checkJointNames(const std::vector<std::string> &joint_names,
97  const moveit_msgs::KinematicSolverInfo &chain_info);
98 
99  bool checkLinkNames(const std::vector<std::string> &link_names,
100  const moveit_msgs::KinematicSolverInfo &chain_info);
101 
102  bool checkLinkName(const std::string &link_name,
103  const moveit_msgs::KinematicSolverInfo &chain_info);
104 
105  bool checkRobotState(moveit_msgs::RobotState &robot_state,
106  const moveit_msgs::KinematicSolverInfo &chain_info);
107 
108  bool checkFKService(moveit_msgs::GetPositionFK::Request &request,
109  moveit_msgs::GetPositionFK::Response &response,
110  const moveit_msgs::KinematicSolverInfo &chain_info);
111 
112  bool checkIKService(moveit_msgs::GetPositionIK::Request &request,
113  moveit_msgs::GetPositionIK::Response &response,
114  const moveit_msgs::KinematicSolverInfo &chain_info);
115 
116  int getJointIndex(const std::string &name,
117  const moveit_msgs::KinematicSolverInfo &chain_info);
118 
119  bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
120  KDL::Frame &pose_kdl,
121  const std::string &root_frame,
123 
124  bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
125  geometry_msgs::PoseStamped &pose_msg_out,
126  const std::string &root_frame,
128 
129  int getKDLSegmentIndex(const KDL::Chain &chain,
130  const std::string &name);
131 
132  void getKDLChainInfo(const KDL::Chain &chain,
133  moveit_msgs::KinematicSolverInfo &chain_info);
134 }
135 
136 #endif// PR2_ARM_IK_UTILS_H
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
Namespace for the PR2ArmKinematics.
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, geometry_msgs::PoseStamped &pose_msg_out, const std::string &root_frame, tf::TransformListener &tf)
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkLinkName(const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::Affine3f KDLToEigenMatrix(const KDL::Frame &p)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
double distance(const urdf::Pose &transform)
Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g)
bool getKDLTree(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Nov 17 2019 03:24:45