pr2_arm_kinematics.cpp
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 
38 #include <geometry_msgs/PoseStamped.h>
40 #include <tf_conversions/tf_kdl.h>
41 #include "ros/ros.h"
42 #include <algorithm>
43 #include <numeric>
44 
45 
46 using namespace KDL;
47 using namespace tf;
48 using namespace std;
49 using namespace ros;
50 
51 namespace pr2_arm_kinematics {
52 
53 static const std::string IK_SERVICE = "get_ik";
54 static const std::string FK_SERVICE = "get_fk";
55 static const std::string IK_INFO_SERVICE = "get_ik_solver_info";
56 static const std::string FK_INFO_SERVICE = "get_fk_solver_info";
57 
58 PR2ArmKinematics::PR2ArmKinematics(bool create_tf_listener): node_handle_("~"),dimension_(7)
59 {
60  urdf::Model robot_model;
61  std::string tip_name, xml_string;
62 
63  while(!loadRobotModel(node_handle_,robot_model, xml_string) && node_handle_.ok())
64  {
65  ROS_ERROR("Could not load robot model. Are you sure the robot model is on the parameter server?");
66  ros::Duration(0.5).sleep();
67  }
68 
69  if (!node_handle_.getParam("root_name", root_name_)){
70  ROS_FATAL("PR2IK: No root name found on parameter server");
71  exit(-1);
72  }
73  if (!node_handle_.getParam("tip_name", tip_name)){
74  ROS_FATAL("PR2IK: No tip name found on parameter server");
75  exit(-1);
76  }
77 
78  ROS_DEBUG("Loading KDL Tree");
79  if(!getKDLChain(xml_string,root_name_,tip_name,kdl_chain_))
80  {
81  active_ = false;
82  ROS_ERROR("Could not load kdl tree");
83  }
84  if(create_tf_listener) {
85  tf_ = new TransformListener();
86  } else {
87  tf_ = NULL;
88  }
89 
90  ROS_DEBUG("Advertising services");
92  node_handle_.param<int>("free_angle",free_angle_,2);
93 
94  node_handle_.param<double>("search_discretization",search_discretization_,0.01);
95  pr2_arm_ik_solver_.reset(new pr2_arm_kinematics::PR2ArmIKSolver(robot_model,root_name_,tip_name, search_discretization_,free_angle_));
96  if(!pr2_arm_ik_solver_->active_)
97  {
98  ROS_ERROR("Could not load ik");
99  active_ = false;
100  }
101  else
102  {
103 
104  pr2_arm_ik_solver_->getSolverInfo(ik_solver_info_);
106  fk_solver_info_.joint_names = ik_solver_info_.joint_names;
107 
108  for(unsigned int i=0; i < ik_solver_info_.joint_names.size(); i++)
109  {
110  ROS_DEBUG("PR2Kinematics:: joint name: %s",ik_solver_info_.joint_names[i].c_str());
111  }
112  for(unsigned int i=0; i < ik_solver_info_.link_names.size(); i++)
113  {
114  ROS_DEBUG("PR2Kinematics can solve IK for %s",ik_solver_info_.link_names[i].c_str());
115  }
116  for(unsigned int i=0; i < fk_solver_info_.link_names.size(); i++)
117  {
118  ROS_DEBUG("PR2Kinematics can solve FK for %s",fk_solver_info_.link_names[i].c_str());
119  }
120  ROS_DEBUG("PR2Kinematics::active");
121  active_ = true;
124 
125  }
126 }
127 
129 {
130  if(tf_ != NULL) {
131  delete tf_;
132  }
133 }
134 
136 {
137  if(active_)
138  return true;
139  return false;
140 }
141 
142 bool PR2ArmKinematics::getPositionIK(moveit_msgs::GetPositionIK::Request &request,
143  moveit_msgs::GetPositionIK::Response &response)
144 {
145  if(!active_)
146  {
147  ROS_ERROR("IK service not active");
148  return false;
149  }
150 
151  if(!checkIKService(request,response,ik_solver_info_))
152  return false;
153 
154  geometry_msgs::PoseStamped pose_msg_in = request.ik_request.pose_stamped;
155  geometry_msgs::PoseStamped pose_msg_out;
156  if(tf_ != NULL) {
157  if(!convertPoseToRootFrame(pose_msg_in,pose_msg_out,root_name_, *tf_))
158  {
159  response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
160  return true;
161  }
162  } else {
163  ROS_WARN_STREAM("No tf listener. Can't transform anything");
164  response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
165  return false;
166  }
167  request.ik_request.pose_stamped = pose_msg_out;
168  return getPositionIKHelper(request, response);
169 }
170 
171 //this assumes that everything has been checked and is in the correct frame
172 bool PR2ArmKinematics::getPositionIKHelper(moveit_msgs::GetPositionIK::Request &request,
173  moveit_msgs::GetPositionIK::Response &response)
174 {
175  KDL::Frame pose_desired;
176  tf::poseMsgToKDL(request.ik_request.pose_stamped.pose, pose_desired);
177 
178  //Do the IK
179  KDL::JntArray jnt_pos_in;
180  KDL::JntArray jnt_pos_out;
181  jnt_pos_in.resize(dimension_);
182  for(int i=0; i < dimension_; i++)
183  {
184  int tmp_index = getJointIndex(request.ik_request.robot_state.joint_state.name[i],ik_solver_info_);
185  if(tmp_index >=0)
186  {
187  jnt_pos_in(tmp_index) = request.ik_request.robot_state.joint_state.position[i];
188  }
189  else
190  {
191  ROS_ERROR("i: %d, No joint index for %s",i,request.ik_request.robot_state.joint_state.name[i].c_str());
192  }
193  }
194 
195  std::vector<KDL::JntArray> jnt_array;
196  jnt_array.push_back(jnt_pos_out);
197  int ik_valid = pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in,
198  pose_desired,
199  jnt_array,
200  (const double)(request.ik_request.timeout.toSec()));
201  if(ik_valid == pr2_arm_kinematics::TIMED_OUT)
202  response.error_code.val = response.error_code.TIMED_OUT;
203  if(ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
204  response.error_code.val = response.error_code.NO_IK_SOLUTION;
205 
206  response.solution.joint_state.header = request.ik_request.pose_stamped.header;
207 
208  if(ik_valid >= 0)
209  {
210  response.solution.joint_state.name = ik_solver_info_.joint_names;
211  response.solution.joint_state.position.resize(dimension_);
212  for(int i=0; i < dimension_; i++)
213  {
214  response.solution.joint_state.position[i] = jnt_array[0](i);
215  ROS_DEBUG("IK Solution: %s %d: %f",response.solution.joint_state.name[i].c_str(),i,jnt_array[0](i));
216  }
217  response.error_code.val = response.error_code.SUCCESS;
218  return true;
219  }
220  else
221  {
222  ROS_DEBUG("An IK solution could not be found");
223  return false;
224  }
225 }
226 
227 bool PR2ArmKinematics::getPositionFK(moveit_msgs::GetPositionFK::Request &request,
228  moveit_msgs::GetPositionFK::Response &response)
229 {
230  if(!active_)
231  {
232  ROS_ERROR("FK service not active");
233  return false;
234  }
235 
236  if(!checkFKService(request,response,fk_solver_info_))
237  return false;
238 
239  KDL::Frame p_out;
240  KDL::JntArray jnt_pos_in;
241  geometry_msgs::PoseStamped pose;
242  tf::Stamped<tf::Pose> tf_pose;
243 
244  jnt_pos_in.resize(dimension_);
245  for(int i=0; i < (int) request.robot_state.joint_state.position.size(); i++)
246  {
247  int tmp_index = getJointIndex(request.robot_state.joint_state.name[i],fk_solver_info_);
248  if(tmp_index >=0)
249  jnt_pos_in(tmp_index) = request.robot_state.joint_state.position[i];
250  }
251 
252  response.pose_stamped.resize(request.fk_link_names.size());
253  response.fk_link_names.resize(request.fk_link_names.size());
254 
255  for(unsigned int i=0; i < request.fk_link_names.size(); i++)
256  {
257  ROS_DEBUG("End effector index: %d",pr2_arm_kinematics::getKDLSegmentIndex(kdl_chain_,request.fk_link_names[i]));
258  ROS_DEBUG("Chain indices: %d",kdl_chain_.getNrOfSegments());
259  if(jnt_to_pose_solver_->JntToCart(jnt_pos_in,p_out,pr2_arm_kinematics::getKDLSegmentIndex(kdl_chain_,request.fk_link_names[i])) >=0)
260  {
261  tf_pose.frame_id_ = root_name_;
262  tf_pose.stamp_ = ros::Time();
263  tf::poseKDLToTF(p_out,tf_pose);
264  tf::poseStampedTFToMsg(tf_pose,pose);
265  if(!transformPose(request.header.frame_id, pose, response.pose_stamped[i])) {
266  response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
267  return false;
268  }
269  response.fk_link_names[i] = request.fk_link_names[i];
270  response.error_code.val = response.error_code.SUCCESS;
271  }
272  else
273  {
274  ROS_ERROR("Could not compute FK for %s",request.fk_link_names[i].c_str());
275  response.error_code.val = response.error_code.NO_IK_SOLUTION;
276  return false;
277  }
278  }
279  return true;
280 }
281 bool PR2ArmKinematics::transformPose(const std::string& des_frame,
282  const geometry_msgs::PoseStamped& pose_in,
283  geometry_msgs::PoseStamped& pose_out)
284 {
285  if(tf_ != NULL) {
286  try {
287  tf_->transformPose(des_frame,pose_in,pose_out);
288  }
289  catch(...) {
290  ROS_ERROR("Could not transform FK pose to frame: %s",des_frame.c_str());
291  return false;
292  }
293  } else if(des_frame != root_name_){
294  ROS_WARN_STREAM("No tf listener, can't transform to frame " << des_frame);
295  return false;
296  }
297  return true;
298 }
299 } // namespace
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
#define ROS_FATAL(...)
bool getPositionIKHelper(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
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 sleep() const
unsigned int getNrOfSegments() const
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static const int NO_IK_SOLUTION
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool getPositionFK(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response)
This is the basic forward kinematics service that will return information about the kinematics node...
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
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)
virtual bool getPositionIK(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
This is the basic IK service method that will compute and return an IK solution.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
def xml_string(rootXml, addHeader=True)
moveit_msgs::KinematicSolverInfo fk_solver_info_
#define ROS_WARN_STREAM(args)
static const std::string IK_SERVICE
static const std::string FK_INFO_SERVICE
void resize(unsigned int newSize)
ros::Time stamp_
static const std::string IK_INFO_SERVICE
std::string frame_id_
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
virtual bool transformPose(const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)
bool getParam(const std::string &key, std::string &s) const
static const int TIMED_OUT
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool ok() const
bool isActive()
Specifies if the node is active or not.
static const std::string FK_SERVICE
#define ROS_ERROR(...)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
moveit_msgs::KinematicSolverInfo ik_solver_info_
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
#define ROS_DEBUG(...)


pr2_arm_kinematics
Author(s): Sachin Chitta
autogenerated on Wed Jun 5 2019 21:35:32