hand_kinematics_utils.h
Go to the documentation of this file.
1 // Software License Agreement (BSD License)
2 
3 // Copyright (c) 2008, Willow Garage, Inc.
4 // All rights reserved.
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of Willow Garage, Inc. nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 // Modified by Guillaume WALCK (UPMC) 2012
34 
35 
36 #ifndef HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H
37 #define HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H
38 
39 #include <ros/ros.h>
40 #include <vector>
41 #include <string>
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 namespace hand_kinematics
58 {
59  bool loadRobotModel(ros::NodeHandle node_handle,
60  urdf::Model &robot_model,
61  std::string &root_name,
62  std::string &tip_name,
63  std::string &xml_string);
64 
65  bool getKDLChain(const std::string &xml_string,
66  const std::string &root_name,
67  const std::string &tip_name,
68  KDL::Chain &kdl_chain);
69 
70  bool getKDLTree(const std::string &xml_string,
71  const std::string &root_name,
72  const std::string &tip_name,
73  KDL::Tree &kdl_chain);
74 
75  bool checkJointNames(const std::vector<std::string> &joint_names,
76  const moveit_msgs::KinematicSolverInfo &chain_info);
77 
78  bool checkLinkNames(const std::vector<std::string> &link_names,
79  const moveit_msgs::KinematicSolverInfo &chain_info);
80 
81  bool checkLinkName(const std::string &link_name,
82  const moveit_msgs::KinematicSolverInfo &chain_info);
83 
84  bool checkRobotState(moveit_msgs::RobotState &robot_state,
85  const moveit_msgs::KinematicSolverInfo &chain_info);
86 
87  bool checkFKService(moveit_msgs::GetPositionFK::Request &request,
88  moveit_msgs::GetPositionFK::Response &response,
89  const moveit_msgs::KinematicSolverInfo &chain_info);
90 
91  bool checkIKService(moveit_msgs::GetPositionIK::Request &request,
92  moveit_msgs::GetPositionIK::Response &response,
93  const moveit_msgs::KinematicSolverInfo &chain_info);
94 
95  int getJointIndex(const std::string &name,
96  const moveit_msgs::KinematicSolverInfo &chain_info);
97 
98  bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
99  KDL::Frame &pose_kdl,
100  const std::string &root_frame,
102 
103  bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
104  geometry_msgs::PoseStamped &pose_msg_out,
105  const std::string &root_frame,
107 
108  int getKDLSegmentIndex(const KDL::Chain &chain,
109  const std::string &name);
110 
111  void getKDLChainInfo(const KDL::Chain &chain,
112  moveit_msgs::KinematicSolverInfo &chain_info);
113 
114  bool init_ik(urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name,
115  KDL::JntArray &joint_min, KDL::JntArray &joint_max, moveit_msgs::KinematicSolverInfo &info);
116 
117  // coupling matrices
118  Eigen::MatrixXd updateCouplingFF(const KDL::JntArray &q);
119 
120  Eigen::MatrixXd updateCouplingMF(const KDL::JntArray &q);
121 
122  Eigen::MatrixXd updateCouplingRF(const KDL::JntArray &q);
123 
124  Eigen::MatrixXd updateCouplingLF(const KDL::JntArray &q);
125 
126  Eigen::MatrixXd updateCouplingTH(const KDL::JntArray &q);
127 } // namespace hand_kinematics
128 
129 #endif // HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H
bool checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingRF(const KDL::JntArray &q)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool getKDLTree(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingMF(const KDL::JntArray &q)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingTH(const KDL::JntArray &q)
bool getKDLChain(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &root_name, std::string &tip_name, std::string &xml_string)
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingLF(const KDL::JntArray &q)
bool checkLinkName(const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingFF(const KDL::JntArray &q)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
bool init_ik(urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name, KDL::JntArray &joint_min, KDL::JntArray &joint_max, moveit_msgs::KinematicSolverInfo &info)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)


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