pr2_arm_ik_solver.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 
39 using namespace Eigen;
40 using namespace pr2_arm_kinematics;
41 
42 PR2ArmIKSolver::PR2ArmIKSolver(const urdf::Model& robot_model, const std::string& root_frame_name,
43  const std::string& tip_frame_name, const double& search_discretization_angle,
44  const int& free_angle)
45  : ChainIkSolverPos()
46 {
47  pr2_arm_ik_ = new PR2ArmIK();
48  search_discretization_angle_ = search_discretization_angle;
49  free_angle_ = free_angle;
50  root_frame_name_ = root_frame_name;
51  if (!pr2_arm_ik_->init(robot_model, root_frame_name, tip_frame_name))
52  active_ = false;
53  else
54  active_ = true;
55 }
56 
57 void PR2ArmIKSolver::getSolverInfo(moveit_msgs::KinematicSolverInfo& response)
58 {
59  pr2_arm_ik_->getSolverInfo(response);
60 }
61 
62 int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out)
63 {
64  Eigen::Matrix4f b = KDLToEigenMatrix(p_in);
65  std::vector<std::vector<double> > solution_ik;
66  if (free_angle_ == 0)
67  {
68  ROS_DEBUG("Solving with free angle: %d", free_angle_);
69  pr2_arm_ik_->computeIKShoulderPan(b, q_init(0), solution_ik);
70  }
71  else
72  {
73  pr2_arm_ik_->computeIKShoulderRoll(b, q_init(2), solution_ik);
74  }
75 
76  if (solution_ik.empty())
77  return -1;
78 
79  double min_distance = 1e6;
80  int min_index = -1;
81 
82  for (int i = 0; i < (int)solution_ik.size(); ++i)
83  {
84  ROS_DEBUG("Solution : %d", (int)solution_ik.size());
85  for (int j = 0; j < (int)solution_ik[i].size(); j++)
86  {
87  ROS_DEBUG("Joint %d: %f", j, solution_ik[i][j]);
88  }
89 
90  double tmp_distance = computeEuclideanDistance(solution_ik[i], q_init);
91  if (tmp_distance < min_distance)
92  {
93  min_distance = tmp_distance;
94  min_index = i;
95  }
96  }
97 
98  if (min_index > -1)
99  {
100  q_out.resize((int)solution_ik[min_index].size());
101  for (int i = 0; i < (int)solution_ik[min_index].size(); ++i)
102  {
103  q_out(i) = solution_ik[min_index][i];
104  }
105  return 1;
106  }
107  else
108  return -1;
109 }
110 
111 int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, std::vector<KDL::JntArray>& q_out)
112 {
113  Eigen::Matrix4f b = KDLToEigenMatrix(p_in);
114  std::vector<std::vector<double> > solution_ik;
115  KDL::JntArray q;
116 
117  if (free_angle_ == 0)
118  {
119  pr2_arm_ik_->computeIKShoulderPan(b, q_init(0), solution_ik);
120  }
121  else
122  {
123  pr2_arm_ik_->computeIKShoulderRoll(b, q_init(2), solution_ik);
124  }
125 
126  if (solution_ik.empty())
127  return -1;
128 
129  q.resize(7);
130  q_out.clear();
131  for (int i = 0; i < (int)solution_ik.size(); ++i)
132  {
133  for (int j = 0; j < 7; j++)
134  {
135  q(j) = solution_ik[i][j];
136  }
137  q_out.push_back(q);
138  }
139  return 1;
140 }
141 
142 bool PR2ArmIKSolver::getCount(int& count, const int& max_count, const int& min_count)
143 {
144  if (count > 0)
145  {
146  if (-count >= min_count)
147  {
148  count = -count;
149  return true;
150  }
151  else if (count + 1 <= max_count)
152  {
153  count = count + 1;
154  return true;
155  }
156  else
157  {
158  return false;
159  }
160  }
161  else
162  {
163  if (1 - count <= max_count)
164  {
165  count = 1 - count;
166  return true;
167  }
168  else if (count - 1 >= min_count)
169  {
170  count = count - 1;
171  return true;
172  }
173  else
174  return false;
175  }
176 }
177 
178 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in,
179  std::vector<KDL::JntArray>& q_out, const double& timeout)
180 {
181  KDL::JntArray q_init = q_in;
182  double initial_guess = q_init(free_angle_);
183 
184  ros::WallTime start_time = ros::WallTime::now();
185  double loop_time = 0;
186  int count = 0;
187 
188  int num_positive_increments = (int)((pr2_arm_ik_->solver_info_.limits[free_angle_].max_position - initial_guess) /
190  int num_negative_increments = (int)((initial_guess - pr2_arm_ik_->solver_info_.limits[free_angle_].min_position) /
192  ROS_DEBUG("positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
193  while (loop_time < timeout)
194  {
195  if (CartToJnt(q_init, p_in, q_out) > 0)
196  return 1;
197  if (!getCount(count, num_positive_increments, -num_negative_increments))
198  return -1;
199  q_init(free_angle_) = initial_guess + search_discretization_angle_ * count;
200  ROS_DEBUG("%d, %f", count, q_init(free_angle_));
201  loop_time = (ros::WallTime::now() - start_time).toSec();
202  }
203  if (loop_time >= timeout)
204  {
205  ROS_DEBUG("IK Timed out in %f seconds", timeout);
206  return TIMED_OUT;
207  }
208  else
209  {
210  ROS_DEBUG("No IK solution was found");
211  return NO_IK_SOLUTION;
212  }
213  return NO_IK_SOLUTION;
214 }
215 
216 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
217  const double& timeout, const double& consistency_limit)
218 {
219  moveit_msgs::MoveItErrorCodes error_code;
220  static kinematics::KinematicsBase::IKCallbackFn solution_callback = 0;
221  return CartToJntSearch(q_in, p_in, q_out, timeout, true, consistency_limit, error_code, solution_callback);
222 }
223 
224 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
225  const double& timeout, moveit_msgs::MoveItErrorCodes& error_code,
226  const kinematics::KinematicsBase::IKCallbackFn& solution_callback)
227 {
228  return CartToJntSearch(q_in, p_in, q_out, timeout, false, 0.0, error_code, solution_callback);
229 }
230 
231 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
232  const double& timeout, const double& consistency_limit,
233  moveit_msgs::MoveItErrorCodes& error_code,
234  const kinematics::KinematicsBase::IKCallbackFn& solution_callback)
235 {
236  return CartToJntSearch(q_in, p_in, q_out, timeout, true, consistency_limit, error_code, solution_callback);
237 }
238 
239 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
240  const double& timeout, bool use_consistency_limit, const double& max_consistency,
241  moveit_msgs::MoveItErrorCodes& error_code,
242  const kinematics::KinematicsBase::IKCallbackFn& solution_callback)
243 {
244  KDL::JntArray q_init = q_in;
245  double initial_guess = q_init(free_angle_);
246 
247  ros::WallTime start_time = ros::WallTime::now();
248  double loop_time = 0;
249  int count = 0;
250 
251  double max_limit, min_limit;
252  if (use_consistency_limit)
253  {
254  max_limit = fmin(pr2_arm_ik_->solver_info_.limits[free_angle_].max_position, initial_guess + max_consistency);
255  min_limit = fmax(pr2_arm_ik_->solver_info_.limits[free_angle_].min_position, initial_guess - max_consistency);
256  }
257  else
258  {
259  max_limit = pr2_arm_ik_->solver_info_.limits[free_angle_].max_position;
260  min_limit = pr2_arm_ik_->solver_info_.limits[free_angle_].min_position;
261  }
262 
263  int num_positive_increments = (int)((max_limit - initial_guess) / search_discretization_angle_);
264  int num_negative_increments = (int)((initial_guess - min_limit) / search_discretization_angle_);
265 
266  if (use_consistency_limit)
267  {
268  ROS_DEBUG("Consistency[Joint: %d]: Initial guess %f, consistency %f", free_angle_, initial_guess, max_consistency);
269  ROS_DEBUG("Max limit %f = max(%f, %f)", max_limit, pr2_arm_ik_->solver_info_.limits[free_angle_].max_position,
270  initial_guess + max_consistency);
271  ROS_DEBUG("Min limit %f = min(%f, %f)", min_limit, pr2_arm_ik_->solver_info_.limits[free_angle_].min_position,
272  initial_guess - max_consistency);
273  }
274  else
275  {
276  ROS_DEBUG("Consistency[Joint: %d]: Initial guess %f", free_angle_, initial_guess);
277  ROS_DEBUG("Max limit %f", max_limit);
278  ROS_DEBUG("Min limit %f", min_limit);
279  }
280 
281  ROS_DEBUG("positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
282 
283  unsigned int testnum = 0;
284  geometry_msgs::Pose ik_pose_msg;
285  tf::poseKDLToMsg(p_in, ik_pose_msg);
286 
288 
289  while (loop_time < timeout)
290  {
291  testnum++;
292  if (CartToJnt(q_init, p_in, q_out) > 0)
293  {
294  if (solution_callback)
295  {
296  std::vector<double> ik_solution(7, 0.0);
297  for (int i = 0; i < 7; ++i)
298  ik_solution[i] = q_out(i);
299 
300  solution_callback(ik_pose_msg, ik_solution, error_code);
301  if (error_code.val == error_code.SUCCESS)
302  {
303  ROS_DEBUG("Difference is %f %f", q_in(free_angle_), q_out(free_angle_));
304  ROS_DEBUG("Success with %d in %f", testnum, (ros::WallTime::now() - s).toSec());
305  return 1;
306  }
307  }
308  else
309  {
310  error_code.val = error_code.SUCCESS;
311  return 1;
312  }
313  }
314  if (!getCount(count, num_positive_increments, -num_negative_increments))
315  {
316  ROS_DEBUG("Failure with %d in %f", testnum, (ros::WallTime::now() - s).toSec());
317  error_code.val = error_code.NO_IK_SOLUTION;
318  return -1;
319  }
320  q_init(free_angle_) = initial_guess + search_discretization_angle_ * count;
321  ROS_DEBUG("Redundancy search, index:%d, free angle value: %f", count, q_init(free_angle_));
322  loop_time = (ros::WallTime::now() - start_time).toSec();
323  }
324  if (loop_time >= timeout)
325  {
326  ROS_DEBUG("IK Timed out in %f seconds", timeout);
327  error_code.val = error_code.TIMED_OUT;
328  }
329  else
330  {
331  error_code.val = error_code.NO_IK_SOLUTION;
332  }
333  return -1;
334 }
335 
336 std::string PR2ArmIKSolver::getFrameId()
337 {
338  return root_frame_name_;
339 }
340 
342 {
343 }
Namespace for the PR2ArmKinematics.
XmlRpcServer s
bool getCount(int &count, const int &max_count, const int &min_count)
static const int NO_IK_SOLUTION
#define ROS_DEBUG(...)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
void resize(unsigned int newSize)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
Definition: pr2_arm_ik.cpp:190
static WallTime now()
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
static const int TIMED_OUT
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
Definition: pr2_arm_ik.h:97
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)


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