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  std::vector<std::string> tip_names = {tip_name};
52  setValues(robot_description, group_name, base_name, tip_names, search_discretization);
53 
54  ros::NodeHandle node_handle("~");
55 
56  urdf::Model robot_model;
57  std::string xml_string;
58 
59  std::string urdf_xml, full_urdf_xml;
60  node_handle.param("urdf_xml", urdf_xml, robot_description);
61  node_handle.searchParam(urdf_xml, full_urdf_xml);
62 
63  ROS_DEBUG_NAMED("trac_ik", "Reading xml file from parameter server");
64  if (!node_handle.getParam(full_urdf_xml, xml_string))
65  {
66  ROS_FATAL_NAMED("trac_ik", "Could not load the xml from parameter server: %s", urdf_xml.c_str());
67  return false;
68  }
69 
70  node_handle.param(full_urdf_xml, xml_string, std::string());
71  robot_model.initString(xml_string);
72 
73  ROS_DEBUG_STREAM_NAMED("trac_ik", "Reading joints and links from URDF");
74 
75  KDL::Tree tree;
76 
77  if (!kdl_parser::treeFromUrdfModel(robot_model, tree))
78  {
79  ROS_FATAL("Failed to extract kdl tree from xml robot description");
80  return false;
81  }
82 
83  if (!tree.getChain(base_name, tip_name, chain))
84  {
85  ROS_FATAL("Couldn't find chain %s to %s", base_name.c_str(), tip_name.c_str());
86  return false;
87  }
88 
90 
91  std::vector<KDL::Segment> chain_segs = chain.segments;
92 
93  urdf::JointConstSharedPtr joint;
94 
95  std::vector<double> l_bounds, u_bounds;
96 
99 
100  uint joint_num = 0;
101  for (unsigned int i = 0; i < chain_segs.size(); ++i)
102  {
103 
104  link_names_.push_back(chain_segs[i].getName());
105  joint = robot_model.getJoint(chain_segs[i].getJoint().getName());
106  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
107  {
108  joint_num++;
109  assert(joint_num <= num_joints_);
110  float lower, upper;
111  int hasLimits;
112  joint_names_.push_back(joint->name);
113  if (joint->type != urdf::Joint::CONTINUOUS)
114  {
115  if (joint->safety)
116  {
117  lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
118  upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
119  }
120  else
121  {
122  lower = joint->limits->lower;
123  upper = joint->limits->upper;
124  }
125  hasLimits = 1;
126  }
127  else
128  {
129  hasLimits = 0;
130  }
131  if (hasLimits)
132  {
133  joint_min(joint_num - 1) = lower;
134  joint_max(joint_num - 1) = upper;
135  }
136  else
137  {
138  joint_min(joint_num - 1) = std::numeric_limits<float>::lowest();
139  joint_max(joint_num - 1) = std::numeric_limits<float>::max();
140  }
141  ROS_INFO_STREAM("IK Using joint " << chain_segs[i].getName() << " " << joint_min(joint_num - 1) << " " << joint_max(joint_num - 1));
142  }
143  }
144 
145  ROS_INFO_NAMED("trac-ik plugin", "Looking in common namespaces for param name: %s", (group_name + "/position_only_ik").c_str());
146  lookupParam(group_name + "/position_only_ik", position_ik_, false);
147  ROS_INFO_NAMED("trac-ik plugin", "Looking in common namespaces for param name: %s", (group_name + "/solve_type").c_str());
148  lookupParam(group_name + "/solve_type", solve_type, std::string("Speed"));
149  ROS_INFO_NAMED("trac_ik plugin", "Using solve type %s", solve_type.c_str());
150 
151  active_ = true;
152  return true;
153 }
154 
155 
156 int TRAC_IKKinematicsPlugin::getKDLSegmentIndex(const std::string &name) const
157 {
158  int i = 0;
159  while (i < (int)chain.getNrOfSegments())
160  {
161  if (chain.getSegment(i).getName() == name)
162  {
163  return i + 1;
164  }
165  i++;
166  }
167  return -1;
168 }
169 
170 
171 bool TRAC_IKKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
172  const std::vector<double> &joint_angles,
173  std::vector<geometry_msgs::Pose> &poses) const
174 {
175  if (!active_)
176  {
177  ROS_ERROR_NAMED("trac_ik", "kinematics not active");
178  return false;
179  }
180  poses.resize(link_names.size());
181  if (joint_angles.size() != num_joints_)
182  {
183  ROS_ERROR_NAMED("trac_ik", "Joint angles vector must have size: %d", num_joints_);
184  return false;
185  }
186 
187  KDL::Frame p_out;
188  geometry_msgs::PoseStamped pose;
189  tf::Stamped<tf::Pose> tf_pose;
190 
191  KDL::JntArray jnt_pos_in(num_joints_);
192  for (unsigned int i = 0; i < num_joints_; i++)
193  {
194  jnt_pos_in(i) = joint_angles[i];
195  }
196 
198 
199  bool valid = true;
200  for (unsigned int i = 0; i < poses.size(); i++)
201  {
202  ROS_DEBUG_NAMED("trac_ik", "End effector index: %d", getKDLSegmentIndex(link_names[i]));
203  if (fk_solver.JntToCart(jnt_pos_in, p_out, getKDLSegmentIndex(link_names[i])) >= 0)
204  {
205  tf::poseKDLToMsg(p_out, poses[i]);
206  }
207  else
208  {
209  ROS_ERROR_NAMED("trac_ik", "Could not compute FK for %s", link_names[i].c_str());
210  valid = false;
211  }
212  }
213 
214  return valid;
215 }
216 
217 
218 bool TRAC_IKKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
219  const std::vector<double> &ik_seed_state,
220  std::vector<double> &solution,
221  moveit_msgs::MoveItErrorCodes &error_code,
222  const kinematics::KinematicsQueryOptions &options) const
223 {
224  const IKCallbackFn solution_callback = 0;
225  std::vector<double> consistency_limits;
226 
227  return searchPositionIK(ik_pose,
228  ik_seed_state,
230  solution,
231  solution_callback,
232  error_code,
233  consistency_limits,
234  options);
235 }
236 
237 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
238  const std::vector<double> &ik_seed_state,
239  double timeout,
240  std::vector<double> &solution,
241  moveit_msgs::MoveItErrorCodes &error_code,
242  const kinematics::KinematicsQueryOptions &options) const
243 {
244  const IKCallbackFn solution_callback = 0;
245  std::vector<double> consistency_limits;
246 
247  return searchPositionIK(ik_pose,
248  ik_seed_state,
249  timeout,
250  solution,
251  solution_callback,
252  error_code,
253  consistency_limits,
254  options);
255 }
256 
257 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
258  const std::vector<double> &ik_seed_state,
259  double timeout,
260  const std::vector<double> &consistency_limits,
261  std::vector<double> &solution,
262  moveit_msgs::MoveItErrorCodes &error_code,
263  const kinematics::KinematicsQueryOptions &options) const
264 {
265  const IKCallbackFn solution_callback = 0;
266  return searchPositionIK(ik_pose,
267  ik_seed_state,
268  timeout,
269  solution,
270  solution_callback,
271  error_code,
272  consistency_limits,
273  options);
274 }
275 
276 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
277  const std::vector<double> &ik_seed_state,
278  double timeout,
279  std::vector<double> &solution,
280  const IKCallbackFn &solution_callback,
281  moveit_msgs::MoveItErrorCodes &error_code,
282  const kinematics::KinematicsQueryOptions &options) const
283 {
284  std::vector<double> consistency_limits;
285  return searchPositionIK(ik_pose,
286  ik_seed_state,
287  timeout,
288  solution,
289  solution_callback,
290  error_code,
291  consistency_limits,
292  options);
293 }
294 
295 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
296  const std::vector<double> &ik_seed_state,
297  double timeout,
298  const std::vector<double> &consistency_limits,
299  std::vector<double> &solution,
300  const IKCallbackFn &solution_callback,
301  moveit_msgs::MoveItErrorCodes &error_code,
302  const kinematics::KinematicsQueryOptions &options) const
303 {
304  return searchPositionIK(ik_pose,
305  ik_seed_state,
306  timeout,
307  solution,
308  solution_callback,
309  error_code,
310  consistency_limits,
311  options);
312 }
313 
314 bool TRAC_IKKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
315  const std::vector<double> &ik_seed_state,
316  double timeout,
317  std::vector<double> &solution,
318  const IKCallbackFn &solution_callback,
319  moveit_msgs::MoveItErrorCodes &error_code,
320  const std::vector<double> &consistency_limits,
321  const kinematics::KinematicsQueryOptions &options) const
322 {
323  ROS_DEBUG_STREAM_NAMED("trac_ik", "getPositionIK");
324 
325  if (!active_)
326  {
327  ROS_ERROR("kinematics not active");
328  error_code.val = error_code.NO_IK_SOLUTION;
329  return false;
330  }
331 
332  if (ik_seed_state.size() != num_joints_)
333  {
334  ROS_ERROR_STREAM_NAMED("trac_ik", "Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
335  error_code.val = error_code.NO_IK_SOLUTION;
336  return false;
337  }
338 
339  KDL::Frame frame;
340  tf::poseMsgToKDL(ik_pose, frame);
341 
343 
344  for (uint z = 0; z < num_joints_; z++)
345  in(z) = ik_seed_state[z];
346 
347  KDL::Twist bounds = KDL::Twist::Zero();
348 
349  if (position_ik_)
350  {
351  bounds.rot.x(std::numeric_limits<float>::max());
352  bounds.rot.y(std::numeric_limits<float>::max());
353  bounds.rot.z(std::numeric_limits<float>::max());
354  }
355 
356  double epsilon = 1e-5; //Same as MoveIt's KDL plugin
357 
358  TRAC_IK::SolveType solvetype;
359 
360  if (solve_type == "Manipulation1")
361  solvetype = TRAC_IK::Manip1;
362  else if (solve_type == "Manipulation2")
363  solvetype = TRAC_IK::Manip2;
364  else if (solve_type == "Distance")
365  solvetype = TRAC_IK::Distance;
366  else
367  {
368  if (solve_type != "Speed")
369  {
370  ROS_WARN_STREAM_NAMED("trac_ik", solve_type << " is not a valid solve_type; setting to default: Speed");
371  }
372  solvetype = TRAC_IK::Speed;
373  }
374 
375  TRAC_IK::TRAC_IK ik_solver(chain, joint_min, joint_max, timeout, epsilon, solvetype);
376 
377  int rc = ik_solver.CartToJnt(in, frame, out, bounds);
378 
379 
380  solution.resize(num_joints_);
381 
382  if (rc >= 0)
383  {
384  for (uint z = 0; z < num_joints_; z++)
385  solution[z] = out(z);
386 
387  // check for collisions if a callback is provided
388  if (!solution_callback.empty())
389  {
390  solution_callback(ik_pose, solution, error_code);
391  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
392  {
393  ROS_DEBUG_STREAM_NAMED("trac_ik", "Solution passes callback");
394  return true;
395  }
396  else
397  {
398  ROS_DEBUG_STREAM_NAMED("trac_ik", "Solution has error code " << error_code);
399  return false;
400  }
401  }
402  else
403  return true; // no collision check callback provided
404  }
405 
406  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
407  return false;
408 }
409 
410 
411 
412 } // end namespace
413 
414 //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 Jun 1 2021 02:38:39