trac_ik_kinematics_plugin.cpp
Go to the documentation of this file.
1 /********************************************************************************
2 Copyright (c) 2015, TRACLabs, Inc.
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software
17  without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
22 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
23 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
26 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
27 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
28 OF THE POSSIBILITY OF SUCH DAMAGE.
29 ********************************************************************************/
30 
31 
32 #include <ros/ros.h>
33 #include <urdf/model.h>
34 #include <tf_conversions/tf_kdl.h>
35 #include <algorithm>
36 #include <kdl/tree.hpp>
38 #include <trac_ik/trac_ik.hpp>
40 #include <limits>
41 
43 {
44 
45 bool TRAC_IKKinematicsPlugin::initialize(const std::string &robot_description,
46  const std::string& group_name,
47  const std::string& base_name,
48  const std::string& tip_name,
49  double search_discretization)
50 {
51  setValues(robot_description, group_name, base_name, tip_name, search_discretization);
52 
53  ros::NodeHandle node_handle("~");
54 
55  urdf::Model robot_model;
56  std::string xml_string;
57 
58  std::string urdf_xml, full_urdf_xml;
59  node_handle.param("urdf_xml", urdf_xml, robot_description);
60  node_handle.searchParam(urdf_xml, full_urdf_xml);
61 
62  ROS_DEBUG_NAMED("trac_ik", "Reading xml file from parameter server");
63  if (!node_handle.getParam(full_urdf_xml, xml_string))
64  {
65  ROS_FATAL_NAMED("trac_ik", "Could not load the xml from parameter server: %s", urdf_xml.c_str());
66  return false;
67  }
68 
69  node_handle.param(full_urdf_xml, xml_string, std::string());
70  robot_model.initString(xml_string);
71 
72  ROS_DEBUG_STREAM_NAMED("trac_ik", "Reading joints and links from URDF");
73 
74  KDL::Tree tree;
75 
76  if (!kdl_parser::treeFromUrdfModel(robot_model, tree))
77  {
78  ROS_FATAL("Failed to extract kdl tree from xml robot description");
79  return false;
80  }
81 
82  if (!tree.getChain(base_name, tip_name, chain))
83  {
84  ROS_FATAL("Couldn't find chain %s to %s", base_name.c_str(), tip_name.c_str());
85  return false;
86  }
87 
89 
90  std::vector<KDL::Segment> chain_segs = chain.segments;
91 
92  urdf::JointConstSharedPtr joint;
93 
94  std::vector<double> l_bounds, u_bounds;
95 
98 
99  uint joint_num = 0;
100  for (unsigned int i = 0; i < chain_segs.size(); ++i)
101  {
102 
103  link_names_.push_back(chain_segs[i].getName());
104  joint = robot_model.getJoint(chain_segs[i].getJoint().getName());
105  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
106  {
107  joint_num++;
108  assert(joint_num <= num_joints_);
109  float lower, upper;
110  int hasLimits;
111  joint_names_.push_back(joint->name);
112  if (joint->type != urdf::Joint::CONTINUOUS)
113  {
114  if (joint->safety)
115  {
116  lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
117  upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
118  }
119  else
120  {
121  lower = joint->limits->lower;
122  upper = joint->limits->upper;
123  }
124  hasLimits = 1;
125  }
126  else
127  {
128  hasLimits = 0;
129  }
130  if (hasLimits)
131  {
132  joint_min(joint_num - 1) = lower;
133  joint_max(joint_num - 1) = upper;
134  }
135  else
136  {
137  joint_min(joint_num - 1) = std::numeric_limits<float>::lowest();
138  joint_max(joint_num - 1) = std::numeric_limits<float>::max();
139  }
140  ROS_INFO_STREAM("IK Using joint " << chain_segs[i].getName() << " " << joint_min(joint_num - 1) << " " << joint_max(joint_num - 1));
141  }
142  }
143 
144  ROS_INFO_NAMED("trac-ik plugin", "Looking in common namespaces for param name: %s", (group_name + "/position_only_ik").c_str());
145  lookupParam(group_name + "/position_only_ik", position_ik_, false);
146  ROS_INFO_NAMED("trac-ik plugin", "Looking in common namespaces for param name: %s", (group_name + "/solve_type").c_str());
147  lookupParam(group_name + "/solve_type", solve_type, std::string("Speed"));
148  ROS_INFO_NAMED("trac_ik plugin", "Using solve type %s", solve_type.c_str());
149 
150  active_ = true;
151  return true;
152 }
153 
154 
155 int TRAC_IKKinematicsPlugin::getKDLSegmentIndex(const std::string &name) const
156 {
157  int i = 0;
158  while (i < (int)chain.getNrOfSegments())
159  {
160  if (chain.getSegment(i).getName() == name)
161  {
162  return i + 1;
163  }
164  i++;
165  }
166  return -1;
167 }
168 
169 
170 bool TRAC_IKKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
171  const std::vector<double> &joint_angles,
172  std::vector<geometry_msgs::Pose> &poses) const
173 {
174  if (!active_)
175  {
176  ROS_ERROR_NAMED("trac_ik", "kinematics not active");
177  return false;
178  }
179  poses.resize(link_names.size());
180  if (joint_angles.size() != num_joints_)
181  {
182  ROS_ERROR_NAMED("trac_ik", "Joint angles vector must have size: %d", num_joints_);
183  return false;
184  }
185 
186  KDL::Frame p_out;
187  geometry_msgs::PoseStamped pose;
188  tf::Stamped<tf::Pose> tf_pose;
189 
190  KDL::JntArray jnt_pos_in(num_joints_);
191  for (unsigned int i = 0; i < num_joints_; i++)
192  {
193  jnt_pos_in(i) = joint_angles[i];
194  }
195 
197 
198  bool valid = true;
199  for (unsigned int i = 0; i < poses.size(); i++)
200  {
201  ROS_DEBUG_NAMED("trac_ik", "End effector index: %d", getKDLSegmentIndex(link_names[i]));
202  if (fk_solver.JntToCart(jnt_pos_in, p_out, getKDLSegmentIndex(link_names[i])) >= 0)
203  {
204  tf::poseKDLToMsg(p_out, poses[i]);
205  }
206  else
207  {
208  ROS_ERROR_NAMED("trac_ik", "Could not compute FK for %s", link_names[i].c_str());
209  valid = false;
210  }
211  }
212 
213  return valid;
214 }
215 
216 
217 bool TRAC_IKKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
218  const std::vector<double> &ik_seed_state,
219  std::vector<double> &solution,
220  moveit_msgs::MoveItErrorCodes &error_code,
221  const kinematics::KinematicsQueryOptions &options) const
222 {
223  const IKCallbackFn solution_callback = 0;
224  std::vector<double> consistency_limits;
225 
226  return searchPositionIK(ik_pose,
227  ik_seed_state,
229  solution,
230  solution_callback,
231  error_code,
232  consistency_limits,
233  options);
234 }
235 
236 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
237  const std::vector<double> &ik_seed_state,
238  double timeout,
239  std::vector<double> &solution,
240  moveit_msgs::MoveItErrorCodes &error_code,
241  const kinematics::KinematicsQueryOptions &options) const
242 {
243  const IKCallbackFn solution_callback = 0;
244  std::vector<double> consistency_limits;
245 
246  return searchPositionIK(ik_pose,
247  ik_seed_state,
248  timeout,
249  solution,
250  solution_callback,
251  error_code,
252  consistency_limits,
253  options);
254 }
255 
256 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
257  const std::vector<double> &ik_seed_state,
258  double timeout,
259  const std::vector<double> &consistency_limits,
260  std::vector<double> &solution,
261  moveit_msgs::MoveItErrorCodes &error_code,
262  const kinematics::KinematicsQueryOptions &options) const
263 {
264  const IKCallbackFn solution_callback = 0;
265  return searchPositionIK(ik_pose,
266  ik_seed_state,
267  timeout,
268  solution,
269  solution_callback,
270  error_code,
271  consistency_limits,
272  options);
273 }
274 
275 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
276  const std::vector<double> &ik_seed_state,
277  double timeout,
278  std::vector<double> &solution,
279  const IKCallbackFn &solution_callback,
280  moveit_msgs::MoveItErrorCodes &error_code,
281  const kinematics::KinematicsQueryOptions &options) const
282 {
283  std::vector<double> consistency_limits;
284  return searchPositionIK(ik_pose,
285  ik_seed_state,
286  timeout,
287  solution,
288  solution_callback,
289  error_code,
290  consistency_limits,
291  options);
292 }
293 
294 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
295  const std::vector<double> &ik_seed_state,
296  double timeout,
297  const std::vector<double> &consistency_limits,
298  std::vector<double> &solution,
299  const IKCallbackFn &solution_callback,
300  moveit_msgs::MoveItErrorCodes &error_code,
301  const kinematics::KinematicsQueryOptions &options) const
302 {
303  return searchPositionIK(ik_pose,
304  ik_seed_state,
305  timeout,
306  solution,
307  solution_callback,
308  error_code,
309  consistency_limits,
310  options);
311 }
312 
313 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
314  const std::vector<double> &ik_seed_state,
315  double timeout,
316  std::vector<double> &solution,
317  const IKCallbackFn &solution_callback,
318  moveit_msgs::MoveItErrorCodes &error_code,
319  const std::vector<double> &consistency_limits,
320  const kinematics::KinematicsQueryOptions &options) const
321 {
322  ROS_DEBUG_STREAM_NAMED("trac_ik", "getPositionIK");
323 
324  if (!active_)
325  {
326  ROS_ERROR("kinematics not active");
327  error_code.val = error_code.NO_IK_SOLUTION;
328  return false;
329  }
330 
331  if (ik_seed_state.size() != num_joints_)
332  {
333  ROS_ERROR_STREAM_NAMED("trac_ik", "Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
334  error_code.val = error_code.NO_IK_SOLUTION;
335  return false;
336  }
337 
338  KDL::Frame frame;
339  tf::poseMsgToKDL(ik_pose, frame);
340 
342 
343  for (uint z = 0; z < num_joints_; z++)
344  in(z) = ik_seed_state[z];
345 
346  KDL::Twist bounds = KDL::Twist::Zero();
347 
348  if (position_ik_)
349  {
350  bounds.rot.x(std::numeric_limits<float>::max());
351  bounds.rot.y(std::numeric_limits<float>::max());
352  bounds.rot.z(std::numeric_limits<float>::max());
353  }
354 
355  double epsilon = 1e-5; //Same as MoveIt's KDL plugin
356 
357  TRAC_IK::SolveType solvetype;
358 
359  if (solve_type == "Manipulation1")
360  solvetype = TRAC_IK::Manip1;
361  else if (solve_type == "Manipulation2")
362  solvetype = TRAC_IK::Manip2;
363  else if (solve_type == "Distance")
364  solvetype = TRAC_IK::Distance;
365  else
366  {
367  if (solve_type != "Speed")
368  {
369  ROS_WARN_STREAM_NAMED("trac_ik", solve_type << " is not a valid solve_type; setting to default: Speed");
370  }
371  solvetype = TRAC_IK::Speed;
372  }
373 
374  TRAC_IK::TRAC_IK ik_solver(chain, joint_min, joint_max, timeout, epsilon, solvetype);
375 
376  int rc = ik_solver.CartToJnt(in, frame, out, bounds);
377 
378 
379  solution.resize(num_joints_);
380 
381  if (rc >= 0)
382  {
383  for (uint z = 0; z < num_joints_; z++)
384  solution[z] = out(z);
385 
386  // check for collisions if a callback is provided
387  if (!solution_callback.empty())
388  {
389  solution_callback(ik_pose, solution, error_code);
390  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
391  {
392  ROS_DEBUG_STREAM_NAMED("trac_ik", "Solution passes callback");
393  return true;
394  }
395  else
396  {
397  ROS_DEBUG_STREAM_NAMED("trac_ik", "Solution has error code " << error_code);
398  return false;
399  }
400  }
401  else
402  return true; // no collision check callback provided
403  }
404 
405  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
406  return false;
407 }
408 
409 
410 
411 } // end namespace
412 
413 //register TRAC_IKKinematicsPlugin as a KinematicsBase implementation
static Twist Zero()
#define ROS_FATAL(...)
#define ROS_INFO_NAMED(name,...)
const Segment & getSegment(unsigned int nr) const
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
unsigned int getNrOfSegments() const
std::string getName(void *handle)
double z() const
#define ROS_DEBUG_NAMED(name,...)
const std::string & getName() const
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
Given a desired pose of the end-effector, compute the joint angles to reach it.
Vector rot
double y() const
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds=KDL::Twist::Zero())
double x() const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
double epsilon
bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
double z
unsigned int getNrOfJoints() const
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)
bool lookupParam(const std::string &param, T &val, const T &default_val) const
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)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
#define ROS_INFO_STREAM(args)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
bool getParam(const std::string &key, std::string &s) const
std::vector< Segment > segments
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
PLUGINLIB_EXPORT_CLASS(trac_ik_kinematics_plugin::TRAC_IKKinematicsPlugin, kinematics::KinematicsBase)
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
Given a desired pose of the end-effector, search for the joint angles required to reach it...
#define ROS_ERROR(...)
#define ROS_WARN_STREAM_NAMED(name, args)


trac_ik_kinematics_plugin
Author(s): Patrick Beeson
autogenerated on Tue Apr 23 2019 02:39:17