pr2_arm_kinematics_plugin.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 
46 
47 using namespace KDL;
48 using namespace tf;
49 using namespace std;
50 using namespace ros;
51 
52 // register PR2ArmKinematics as a KinematicsBase implementation
54 
55 namespace pr2_arm_kinematics
56 {
57 PR2ArmKinematicsPlugin::PR2ArmKinematicsPlugin() : active_(false)
58 {
59 }
60 
62 {
63  if (active_)
64  return true;
65  return false;
66 }
67 
68 bool PR2ArmKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name,
69  const std::string& base_frame, const std::string& tip_frame,
70  double search_discretization)
71 {
72  setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
73  urdf::Model robot_model;
74  std::string xml_string;
75  ros::NodeHandle private_handle("~/" + group_name);
76  dimension_ = 7;
77  while (!loadRobotModel(private_handle, robot_model, xml_string) && private_handle.ok())
78  {
79  ROS_ERROR("Could not load robot model. Are you sure the robot model is on the parameter server?");
80  ros::Duration(0.5).sleep();
81  }
82 
83  ROS_DEBUG("Loading KDL Tree");
84  if (!getKDLChain(xml_string, base_frame_, tip_frame_, kdl_chain_))
85  {
86  active_ = false;
87  ROS_ERROR("Could not load kdl tree");
88  }
89  ROS_DEBUG("Advertising services");
91  private_handle.param<int>("free_angle", free_angle_, 2);
92 
94  search_discretization_, free_angle_));
95  if (!pr2_arm_ik_solver_->active_)
96  {
97  ROS_ERROR("Could not load ik");
98  active_ = false;
99  }
100  else
101  {
102  pr2_arm_ik_solver_->getSolverInfo(ik_solver_info_);
104  fk_solver_info_.joint_names = ik_solver_info_.joint_names;
105 
106  for (unsigned int i = 0; i < ik_solver_info_.joint_names.size(); i++)
107  {
108  ROS_DEBUG("PR2Kinematics:: joint name: %s", ik_solver_info_.joint_names[i].c_str());
109  }
110  for (unsigned int i = 0; i < ik_solver_info_.link_names.size(); i++)
111  {
112  ROS_DEBUG("PR2Kinematics can solve IK for %s", ik_solver_info_.link_names[i].c_str());
113  }
114  for (unsigned int i = 0; i < fk_solver_info_.link_names.size(); i++)
115  {
116  ROS_DEBUG("PR2Kinematics can solve FK for %s", fk_solver_info_.link_names[i].c_str());
117  }
118  ROS_DEBUG("PR2KinematicsPlugin::active for %s", group_name.c_str());
119  active_ = true;
120  }
121  pr2_arm_ik_solver_->setFreeAngle(2);
122  return active_;
123 }
124 
125 bool PR2ArmKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
126  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
127  const kinematics::KinematicsQueryOptions& options) const
128 {
129  if (!active_)
130  {
131  ROS_ERROR("kinematics not active");
132  error_code.val = error_code.NO_IK_SOLUTION;
133  return false;
134  }
135 
136  KDL::Frame pose_desired;
137  tf::poseMsgToKDL(ik_pose, pose_desired);
138 
139  // Do the IK
140  KDL::JntArray jnt_pos_in;
141  KDL::JntArray jnt_pos_out;
142  jnt_pos_in.resize(dimension_);
143  for (int i = 0; i < dimension_; i++)
144  {
145  jnt_pos_in(i) = ik_seed_state[i];
146  }
147 
148  int ik_valid = pr2_arm_ik_solver_->CartToJnt(jnt_pos_in, pose_desired, jnt_pos_out);
149  if (ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
150  {
151  error_code.val = error_code.NO_IK_SOLUTION;
152  return false;
153  }
154 
155  if (ik_valid >= 0)
156  {
157  solution.resize(dimension_);
158  for (int i = 0; i < dimension_; i++)
159  {
160  solution[i] = jnt_pos_out(i);
161  }
162  error_code.val = error_code.SUCCESS;
163  return true;
164  }
165  else
166  {
167  ROS_DEBUG("An IK solution could not be found");
168  error_code.val = error_code.NO_IK_SOLUTION;
169  return false;
170  }
171 }
172 
173 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
174  const std::vector<double>& ik_seed_state, double timeout,
175  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
176  const kinematics::KinematicsQueryOptions& options) const
177 {
178  static IKCallbackFn solution_callback = 0;
179  static std::vector<double> consistency_limits;
180  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
181 }
182 
183 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
184  const std::vector<double>& ik_seed_state, double timeout,
185  const std::vector<double>& consistency_limits,
186  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
187  const kinematics::KinematicsQueryOptions& options) const
188 {
189  static IKCallbackFn solution_callback = 0;
190  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
191 }
192 
193 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
194  const std::vector<double>& ik_seed_state, double timeout,
195  std::vector<double>& solution, const IKCallbackFn& solution_callback,
196  moveit_msgs::MoveItErrorCodes& error_code,
197  const kinematics::KinematicsQueryOptions& options) const
198 {
199  static std::vector<double> consistency_limits;
200  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
201 }
202 
203 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
204  const std::vector<double>& ik_seed_state, double timeout,
205  const std::vector<double>& consistency_limits,
206  std::vector<double>& solution, const IKCallbackFn& solution_callback,
207  moveit_msgs::MoveItErrorCodes& error_code,
208  const kinematics::KinematicsQueryOptions& options) const
209 {
210  if (!active_)
211  {
212  ROS_ERROR("kinematics not active");
213  error_code.val = error_code.FAILURE;
214  return false;
215  }
216  if (!consistency_limits.empty() && consistency_limits.size() != dimension_)
217  {
218  ROS_ERROR("Consistency limits should be of size: %d", dimension_);
219  error_code.val = error_code.FAILURE;
220  return false;
221  }
222 
223  KDL::Frame pose_desired;
224  tf::poseMsgToKDL(ik_pose, pose_desired);
225 
226  // Do the IK
227  KDL::JntArray jnt_pos_in;
228  KDL::JntArray jnt_pos_out;
229  jnt_pos_in.resize(dimension_);
230  for (int i = 0; i < dimension_; i++)
231  {
232  jnt_pos_in(i) = ik_seed_state[i];
233  }
234 
235  int ik_valid;
236  if (consistency_limits.empty())
237  {
238  ik_valid = pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in, pose_desired, jnt_pos_out, timeout, error_code,
239  solution_callback ? boost::bind(solution_callback, _1, _2, _3) :
240  IKCallbackFn());
241  }
242  else
243  {
244  ik_valid = pr2_arm_ik_solver_->CartToJntSearch(
245  jnt_pos_in, pose_desired, jnt_pos_out, timeout, consistency_limits[free_angle_], error_code,
246  solution_callback ? boost::bind(solution_callback, _1, _2, _3) : IKCallbackFn());
247  }
248 
249  if (ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
250  return false;
251 
252  if (ik_valid >= 0)
253  {
254  solution.resize(dimension_);
255  for (int i = 0; i < dimension_; i++)
256  {
257  solution[i] = jnt_pos_out(i);
258  }
259  return true;
260  }
261  else
262  {
263  ROS_DEBUG("An IK solution could not be found");
264  return false;
265  }
266 }
267 
268 bool PR2ArmKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
269  const std::vector<double>& joint_angles,
270  std::vector<geometry_msgs::Pose>& poses) const
271 {
272  if (!active_)
273  {
274  ROS_ERROR("kinematics not active");
275  return false;
276  }
277 
278  KDL::Frame p_out;
279  KDL::JntArray jnt_pos_in;
280  geometry_msgs::PoseStamped pose;
281  tf::Stamped<tf::Pose> tf_pose;
282 
283  jnt_pos_in.resize(dimension_);
284  for (int i = 0; i < dimension_; i++)
285  {
286  jnt_pos_in(i) = joint_angles[i];
287  // ROS_DEBUG("Joint angle: %d %f",i,joint_angles[i]);
288  }
289 
290  poses.resize(link_names.size());
291 
292  bool valid = true;
293  for (unsigned int i = 0; i < poses.size(); i++)
294  {
295  // ROS_DEBUG("End effector index: %d",pr2_arm_kinematics::getKDLSegmentIndex(kdl_chain_,link_names[i]));
296  if (jnt_to_pose_solver_->JntToCart(jnt_pos_in, p_out,
298  {
299  tf::poseKDLToMsg(p_out, poses[i]);
300  }
301  else
302  {
303  ROS_ERROR("Could not compute FK for %s", link_names[i].c_str());
304  valid = false;
305  }
306  }
307  return valid;
308 }
309 
310 const std::vector<std::string>& PR2ArmKinematicsPlugin::getJointNames() const
311 {
312  if (!active_)
313  {
314  ROS_ERROR("kinematics not active");
315  }
316  return ik_solver_info_.joint_names;
317 }
318 
319 const std::vector<std::string>& PR2ArmKinematicsPlugin::getLinkNames() const
320 {
321  if (!active_)
322  {
323  ROS_ERROR("kinematics not active");
324  }
325  return fk_solver_info_.link_names;
326 }
327 
328 } // namespace
Namespace for the PR2ArmKinematics.
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
#define ROS_ERROR(...)
moveit_msgs::KinematicSolverInfo fk_solver_info_
static const int NO_IK_SOLUTION
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
PLUGINLIB_EXPORT_CLASS(pr2_arm_kinematics::PR2ArmKinematicsPlugin, kinematics::KinematicsBase)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
#define ROS_DEBUG(...)
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 override
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
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 override
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
def xml_string(rootXml, addHeader=True)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const override
void resize(unsigned int newSize)
bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
const std::vector< std::string > & getLinkNames() const override
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
bool sleep() const
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)


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