nextage_left_arm_ikfast_moveit_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer IPA
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the all of the author's companies nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  *********************************************************************/
34 
35 /*
36  * IKFast Plugin Template for moveit
37  *
38  * AUTO-GENERATED by create_ikfast_moveit_plugin.py in arm_kinematics_tools
39  * You should run create_ikfast_moveit_plugin.py to generate your own plugin.
40  *
41  * Creates a kinematics plugin using the output of IKFast from OpenRAVE.
42  * This plugin and the move_group node can be used as a general
43  * kinematics service, from within the moveit planning environment, or in
44  * your own ROS node.
45  *
46  */
47 
48 #include <ros/ros.h>
50 #include <urdf/model.h>
51 #include <tf_conversions/tf_kdl.h>
52 
53 // Need a floating point tolerance when checking joint limits, in case the joint starts at limit
54 const double LIMIT_TOLERANCE = .0000001;
57 
59 {
60 
61 #define IKFAST_NO_MAIN // Don't include main() from IKFast
62 
70  IKP_Transform6D=0x67000001,
71  IKP_Rotation3D=0x34000002,
72  IKP_Translation3D=0x33000003,
73  IKP_Direction3D=0x23000004,
74  IKP_Ray4D=0x46000005,
75  IKP_Lookat3D=0x23000006,
77  IKP_TranslationXY2D=0x22000008,
80 
84 
88 
90 
91  IKP_VelocityDataBit = 0x00008000,
108 
109  IKP_UniqueIdMask = 0x0000ffff,
110  IKP_CustomDataBit = 0x00010000,
111 };
112 
113 // Code generated by IKFast56/61
115 
117 {
118  std::vector<std::string> joint_names_;
119  std::vector<double> joint_min_vector_;
120  std::vector<double> joint_max_vector_;
121  std::vector<bool> joint_has_limits_vector_;
122  std::vector<std::string> link_names_;
123  size_t num_joints_;
124  std::vector<int> free_params_;
125  bool active_; // Internal variable that indicates whether solvers are configured and ready
126 
127  const std::vector<std::string>& getJointNames() const { return joint_names_; }
128  const std::vector<std::string>& getLinkNames() const { return link_names_; }
130 public:
131 
135  IKFastKinematicsPlugin():active_(false){}
136 
146  // Returns the first IK solution that is within joint limits, this is called by get_ik() service
147  bool getPositionIK(const geometry_msgs::Pose &ik_pose,
148  const std::vector<double> &ik_seed_state,
149  std::vector<double> &solution,
150  moveit_msgs::MoveItErrorCodes &error_code,
152 
161  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
162  const std::vector<double> &ik_seed_state,
163  double timeout,
164  std::vector<double> &solution,
165  moveit_msgs::MoveItErrorCodes &error_code,
177  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
178  const std::vector<double> &ik_seed_state,
179  double timeout,
180  const std::vector<double> &consistency_limits,
181  std::vector<double> &solution,
182  moveit_msgs::MoveItErrorCodes &error_code,
184 
193  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
194  const std::vector<double> &ik_seed_state,
195  double timeout,
196  std::vector<double> &solution,
197  const IKCallbackFn &solution_callback,
198  moveit_msgs::MoveItErrorCodes &error_code,
200 
211  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
212  const std::vector<double> &ik_seed_state,
213  double timeout,
214  const std::vector<double> &consistency_limits,
215  std::vector<double> &solution,
216  const IKCallbackFn &solution_callback,
217  moveit_msgs::MoveItErrorCodes &error_code,
219 
231  bool getPositionFK(const std::vector<std::string> &link_names,
232  const std::vector<double> &joint_angles,
233  std::vector<geometry_msgs::Pose> &poses) const;
234 
235 private:
236 
237  bool initialize(const std::string &robot_description,
238  const std::string& group_name,
239  const std::string& base_name,
240  const std::string& tip_name,
241  double search_discretization);
242 
247  int solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const;
248 
252  void getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const;
253 
254  double harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
255  //void getOrderedSolutions(const std::vector<double> &ik_seed_state, std::vector<std::vector<double> >& solslist);
256  void getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
257  void fillFreeParams(int count, int *array);
258  bool getCount(int &count, const int &max_count, const int &min_count) const;
259 
260 }; // end class
261 
262 bool IKFastKinematicsPlugin::initialize(const std::string &robot_description,
263  const std::string& group_name,
264  const std::string& base_name,
265  const std::string& tip_name,
266  double search_discretization)
267 {
268  setValues(robot_description, group_name, base_name, tip_name, search_discretization);
269 
270  ros::NodeHandle node_handle("~/"+group_name);
271 
272  std::string robot;
273  node_handle.param("robot",robot,std::string());
274 
275  // IKFast56/61
277  num_joints_ = GetNumJoints();
278 
279  if(free_params_.size() > 1)
280  {
281  ROS_FATAL("Only one free joint paramter supported!");
282  return false;
283  }
284 
285  urdf::Model robot_model;
286  std::string xml_string;
287 
288  std::string urdf_xml,full_urdf_xml;
289  node_handle.param("urdf_xml",urdf_xml,robot_description);
290  node_handle.searchParam(urdf_xml,full_urdf_xml);
291 
292  ROS_DEBUG_NAMED("ikfast","Reading xml file from parameter server");
293  if (!node_handle.getParam(full_urdf_xml, xml_string))
294  {
295  ROS_FATAL_NAMED("ikfast","Could not load the xml from parameter server: %s", urdf_xml.c_str());
296  return false;
297  }
298 
299  node_handle.param(full_urdf_xml,xml_string,std::string());
300  robot_model.initString(xml_string);
301 
302  ROS_DEBUG_STREAM_NAMED("ikfast","Reading joints and links from URDF");
303 
304 #if URDFDOM_1_0_0_API
305  urdf::LinkConstSharedPtr link = robot_model.getLink(getTipFrame());
306 #else
307  boost::shared_ptr<urdf::Link> link = boost::const_pointer_cast<urdf::Link>(robot_model.getLink(getTipFrame()));
308 #endif
309  while(link->name != base_frame_ && joint_names_.size() <= num_joints_)
310  {
311  ROS_DEBUG_NAMED("ikfast","Link %s",link->name.c_str());
312  link_names_.push_back(link->name);
313 #if URDFDOM_1_0_0_API
314  urdf::JointSharedPtr joint = link->parent_joint;
315 #else
316  boost::shared_ptr<urdf::Joint> joint = link->parent_joint;
317 #endif
318  if(joint)
319  {
320  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
321  {
322  ROS_DEBUG_STREAM_NAMED("ikfast","Adding joint " << joint->name );
323 
324  joint_names_.push_back(joint->name);
325  float lower, upper;
326  int hasLimits;
327  if ( joint->type != urdf::Joint::CONTINUOUS )
328  {
329  if(joint->safety)
330  {
331  lower = joint->safety->soft_lower_limit;
332  upper = joint->safety->soft_upper_limit;
333  } else {
334  lower = joint->limits->lower;
335  upper = joint->limits->upper;
336  }
337  hasLimits = 1;
338  }
339  else
340  {
341  lower = -M_PI;
342  upper = M_PI;
343  hasLimits = 0;
344  }
345  if(hasLimits)
346  {
347  joint_has_limits_vector_.push_back(true);
348  joint_min_vector_.push_back(lower);
349  joint_max_vector_.push_back(upper);
350  }
351  else
352  {
353  joint_has_limits_vector_.push_back(false);
354  joint_min_vector_.push_back(-M_PI);
355  joint_max_vector_.push_back(M_PI);
356  }
357  }
358  } else
359  {
360  ROS_WARN_NAMED("ikfast","no joint corresponding to %s",link->name.c_str());
361  }
362  link = link->getParent();
363  }
364 
365  if(joint_names_.size() != num_joints_)
366  {
367  ROS_FATAL_STREAM_NAMED("ikfast","Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has " << num_joints_);
368  return false;
369  }
370 
371  std::reverse(link_names_.begin(),link_names_.end());
372  std::reverse(joint_names_.begin(),joint_names_.end());
373  std::reverse(joint_min_vector_.begin(),joint_min_vector_.end());
374  std::reverse(joint_max_vector_.begin(),joint_max_vector_.end());
375  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
376 
377  for(size_t i=0; i <num_joints_; ++i)
378  ROS_INFO_STREAM_NAMED("ikfast",joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i] << " " << joint_has_limits_vector_[i]);
379 
380  active_ = true;
381  return true;
382 }
383 
384 int IKFastKinematicsPlugin::solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const
385 {
386  // IKFast56/61
387  solutions.Clear();
388 
389  double trans[3];
390  trans[0] = pose_frame.p[0];//-.18;
391  trans[1] = pose_frame.p[1];
392  trans[2] = pose_frame.p[2];
393 
394  KDL::Rotation mult;
395  KDL::Vector direction;
396 
397  switch (GetIkType())
398  {
399  case IKP_Transform6D:
400  case IKP_Translation3D:
401  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
402 
403  mult = pose_frame.M;
404 
405  double vals[9];
406  vals[0] = mult(0,0);
407  vals[1] = mult(0,1);
408  vals[2] = mult(0,2);
409  vals[3] = mult(1,0);
410  vals[4] = mult(1,1);
411  vals[5] = mult(1,2);
412  vals[6] = mult(2,0);
413  vals[7] = mult(2,1);
414  vals[8] = mult(2,2);
415 
416  // IKFast56/61
417  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
418  return solutions.GetNumSolutions();
419 
420  case IKP_Direction3D:
421  case IKP_Ray4D:
423  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction.
424 
425  direction = pose_frame.M * KDL::Vector(0, 0, 1);
426  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
427  return solutions.GetNumSolutions();
428 
432  // For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value represents the angle.
433  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
434  return 0;
435 
437  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end effector coordinate system.
438  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
439  return 0;
440 
441  case IKP_Rotation3D:
442  case IKP_Lookat3D:
443  case IKP_TranslationXY2D:
448  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
449  return 0;
450 
451  default:
452  ROS_ERROR_NAMED("ikfast", "Unknown IkParameterizationType! Was the solver generated with an incompatible version of Openrave?");
453  return 0;
454  }
455 }
456 
457 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const
458 {
459  solution.clear();
460  solution.resize(num_joints_);
461 
462  // IKFast56/61
463  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
464  std::vector<IkReal> vsolfree( sol.GetFree().size() );
465  sol.GetSolution(&solution[0],vsolfree.size()>0?&vsolfree[0]:NULL);
466 
467  // std::cout << "solution " << i << ":" ;
468  // for(int j=0;j<num_joints_; ++j)
469  // std::cout << " " << solution[j];
470  // std::cout << std::endl;
471 
472  //ROS_ERROR("%f %d",solution[2],vsolfree.size());
473 }
474 
475 double IKFastKinematicsPlugin::harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
476 {
477  double dist_sqr = 0;
478  std::vector<double> ss = ik_seed_state;
479  for(size_t i=0; i< ik_seed_state.size(); ++i)
480  {
481  while(ss[i] > 2*M_PI) {
482  ss[i] -= 2*M_PI;
483  }
484  while(ss[i] < 2*M_PI) {
485  ss[i] += 2*M_PI;
486  }
487  while(solution[i] > 2*M_PI) {
488  solution[i] -= 2*M_PI;
489  }
490  while(solution[i] < 2*M_PI) {
491  solution[i] += 2*M_PI;
492  }
493  dist_sqr += fabs(ik_seed_state[i] - solution[i]);
494  }
495  return dist_sqr;
496 }
497 
498 // void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector<double> &ik_seed_state,
499 // std::vector<std::vector<double> >& solslist)
500 // {
501 // std::vector<double>
502 // double mindist = 0;
503 // int minindex = -1;
504 // std::vector<double> sol;
505 // for(size_t i=0;i<solslist.size();++i){
506 // getSolution(i,sol);
507 // double dist = harmonize(ik_seed_state, sol);
508 // //std::cout << "dist[" << i << "]= " << dist << std::endl;
509 // if(minindex == -1 || dist<mindist){
510 // minindex = i;
511 // mindist = dist;
512 // }
513 // }
514 // if(minindex >= 0){
515 // getSolution(minindex,solution);
516 // harmonize(ik_seed_state, solution);
517 // index = minindex;
518 // }
519 // }
520 
521 void IKFastKinematicsPlugin::getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
522 {
523  double mindist = DBL_MAX;
524  int minindex = -1;
525  std::vector<double> sol;
526 
527  // IKFast56/61
528  for(size_t i=0; i < solutions.GetNumSolutions(); ++i)
529  {
530  getSolution(solutions, i,sol);
531  double dist = harmonize(ik_seed_state, sol);
532  ROS_INFO_STREAM_NAMED("ikfast","Dist " << i << " dist " << dist);
533  //std::cout << "dist[" << i << "]= " << dist << std::endl;
534  if(minindex == -1 || dist<mindist){
535  minindex = i;
536  mindist = dist;
537  }
538  }
539  if(minindex >= 0){
540  getSolution(solutions, minindex,solution);
541  harmonize(ik_seed_state, solution);
542  }
543 }
544 
545 void IKFastKinematicsPlugin::fillFreeParams(int count, int *array)
546 {
547  free_params_.clear();
548  for(int i=0; i<count;++i) free_params_.push_back(array[i]);
549 }
550 
551 bool IKFastKinematicsPlugin::getCount(int &count, const int &max_count, const int &min_count) const
552 {
553  if(count > 0)
554  {
555  if(-count >= min_count)
556  {
557  count = -count;
558  return true;
559  }
560  else if(count+1 <= max_count)
561  {
562  count = count+1;
563  return true;
564  }
565  else
566  {
567  return false;
568  }
569  }
570  else
571  {
572  if(1-count <= max_count)
573  {
574  count = 1-count;
575  return true;
576  }
577  else if(count-1 >= min_count)
578  {
579  count = count -1;
580  return true;
581  }
582  else
583  return false;
584  }
585 }
586 
587 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
588  const std::vector<double> &joint_angles,
589  std::vector<geometry_msgs::Pose> &poses) const
590 {
591  if (GetIkType() != IKP_Transform6D) {
592  ROS_ERROR_NAMED("ikfast", "Can only compute FK for IKTYPE_TRANSFORM_6D!");
593  return false;
594  }
595 
596  KDL::Frame p_out;
597  if(link_names.size() == 0) {
598  ROS_WARN_STREAM_NAMED("ikfast","Link names with nothing");
599  return false;
600  }
601 
602  if(link_names.size()!=1 || link_names[0]!=getTipFrame()){
603  ROS_ERROR_NAMED("ikfast","Can compute FK for %s only",getTipFrame().c_str());
604  return false;
605  }
606 
607  bool valid = true;
608 
609  IkReal eerot[9],eetrans[3];
610  IkReal angles[joint_angles.size()];
611  for (unsigned char i=0; i < joint_angles.size(); i++)
612  angles[i] = joint_angles[i];
613 
614  // IKFast56/61
615  ComputeFk(angles,eetrans,eerot);
616 
617  for(int i=0; i<3;++i)
618  p_out.p.data[i] = eetrans[i];
619 
620  for(int i=0; i<9;++i)
621  p_out.M.data[i] = eerot[i];
622 
623  poses.resize(1);
624  tf::poseKDLToMsg(p_out,poses[0]);
625 
626  return valid;
627 }
628 
629 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
630  const std::vector<double> &ik_seed_state,
631  double timeout,
632  std::vector<double> &solution,
633  moveit_msgs::MoveItErrorCodes &error_code,
634  const kinematics::KinematicsQueryOptions &options) const
635 {
636  const IKCallbackFn solution_callback = 0;
637  std::vector<double> consistency_limits;
638 
639  return searchPositionIK(ik_pose,
640  ik_seed_state,
641  timeout,
642  consistency_limits,
643  solution,
644  solution_callback,
645  error_code,
646  options);
647 }
648 
649 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
650  const std::vector<double> &ik_seed_state,
651  double timeout,
652  const std::vector<double> &consistency_limits,
653  std::vector<double> &solution,
654  moveit_msgs::MoveItErrorCodes &error_code,
655  const kinematics::KinematicsQueryOptions &options) const
656 {
657  const IKCallbackFn solution_callback = 0;
658  return searchPositionIK(ik_pose,
659  ik_seed_state,
660  timeout,
661  consistency_limits,
662  solution,
663  solution_callback,
664  error_code,
665  options);
666 }
667 
668 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
669  const std::vector<double> &ik_seed_state,
670  double timeout,
671  std::vector<double> &solution,
672  const IKCallbackFn &solution_callback,
673  moveit_msgs::MoveItErrorCodes &error_code,
674  const kinematics::KinematicsQueryOptions &options) const
675 {
676  std::vector<double> consistency_limits;
677  return searchPositionIK(ik_pose,
678  ik_seed_state,
679  timeout,
680  consistency_limits,
681  solution,
682  solution_callback,
683  error_code,
684  options);
685 }
686 
687 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
688  const std::vector<double> &ik_seed_state,
689  double timeout,
690  const std::vector<double> &consistency_limits,
691  std::vector<double> &solution,
692  const IKCallbackFn &solution_callback,
693  moveit_msgs::MoveItErrorCodes &error_code,
694  const kinematics::KinematicsQueryOptions &options) const
695 {
696  ROS_DEBUG_STREAM_NAMED("ikfast","searchPositionIK");
697 
699  SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
700 
701  // Check if there are no redundant joints
702  if(free_params_.size()==0)
703  {
704  ROS_DEBUG_STREAM_NAMED("ikfast","No need to search since no free params/redundant joints");
705 
706  // Find first IK solution, within joint limits
707  if(!getPositionIK(ik_pose, ik_seed_state, solution, error_code))
708  {
709  ROS_DEBUG_STREAM_NAMED("ikfast","No solution whatsoever");
710  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
711  return false;
712  }
713 
714  // check for collisions if a callback is provided
715  if( !solution_callback.empty() )
716  {
717  solution_callback(ik_pose, solution, error_code);
718  if(error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
719  {
720  ROS_DEBUG_STREAM_NAMED("ikfast","Solution passes callback");
721  return true;
722  }
723  else
724  {
725  ROS_DEBUG_STREAM_NAMED("ikfast","Solution has error code " << error_code);
726  return false;
727  }
728  }
729  else
730  {
731  return true; // no collision check callback provided
732  }
733  }
734 
735  // -------------------------------------------------------------------------------------------------
736  // Error Checking
737  if(!active_)
738  {
739  ROS_ERROR_STREAM_NAMED("ikfast","Kinematics not active");
740  error_code.val = error_code.NO_IK_SOLUTION;
741  return false;
742  }
743 
744  if(ik_seed_state.size() != num_joints_)
745  {
746  ROS_ERROR_STREAM_NAMED("ikfast","Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
747  error_code.val = error_code.NO_IK_SOLUTION;
748  return false;
749  }
750 
751  if(!consistency_limits.empty() && consistency_limits.size() != num_joints_)
752  {
753  ROS_ERROR_STREAM_NAMED("ikfast","Consistency limits be empty or must have size " << num_joints_ << " instead of size " << consistency_limits.size());
754  error_code.val = error_code.NO_IK_SOLUTION;
755  return false;
756  }
757 
758 
759  // -------------------------------------------------------------------------------------------------
760  // Initialize
761 
762  KDL::Frame frame;
763  tf::poseMsgToKDL(ik_pose,frame);
764 
765  std::vector<double> vfree(free_params_.size());
766 
767  ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
768  int counter = 0;
769 
770  double initial_guess = ik_seed_state[free_params_[0]];
771  vfree[0] = initial_guess;
772 
773  // -------------------------------------------------------------------------------------------------
774  // Handle consitency limits if needed
775  int num_positive_increments;
776  int num_negative_increments;
777 
778  if(!consistency_limits.empty())
779  {
780  // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector)
781  // Assume [0]th free_params element for now. Probably wrong.
782  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess+consistency_limits[free_params_[0]]);
783  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess-consistency_limits[free_params_[0]]);
784 
785  num_positive_increments = (int)((max_limit-initial_guess)/search_discretization_);
786  num_negative_increments = (int)((initial_guess-min_limit)/search_discretization_);
787  }
788  else // no consitency limits provided
789  {
790  num_positive_increments = (joint_max_vector_[free_params_[0]]-initial_guess)/search_discretization_;
791  num_negative_increments = (initial_guess-joint_min_vector_[free_params_[0]])/search_discretization_;
792  }
793 
794  // -------------------------------------------------------------------------------------------------
795  // Begin searching
796 
797  ROS_DEBUG_STREAM_NAMED("ikfast","Free param is " << free_params_[0] << " initial guess is " << initial_guess << ", # positive increments: " << num_positive_increments << ", # negative increments: " << num_negative_increments);
798  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
799  ROS_WARN_STREAM_ONCE_NAMED("ikfast", "Large search space, consider increasing the search discretization");
800 
801  double best_costs = -1.0;
802  std::vector<double> best_solution;
803  int nattempts = 0, nvalid = 0;
804 
805  while(true)
806  {
807  IkSolutionList<IkReal> solutions;
808  int numsol = solve(frame,vfree, solutions);
809 
810  ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
811 
812  //ROS_INFO("%f",vfree[0]);
813 
814  if( numsol > 0 )
815  {
816  for(int s = 0; s < numsol; ++s)
817  {
818  nattempts++;
819  std::vector<double> sol;
820  getSolution(solutions,s,sol);
821 
822  bool obeys_limits = true;
823  for(unsigned int i = 0; i < sol.size(); i++)
824  {
825  if(joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
826  {
827  obeys_limits = false;
828  break;
829  }
830  //ROS_INFO_STREAM_NAMED("ikfast","Num " << i << " value " << sol[i] << " has limits " << joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
831  }
832  if(obeys_limits)
833  {
834  getSolution(solutions,s,solution);
835 
836  // This solution is within joint limits, now check if in collision (if callback provided)
837  if(!solution_callback.empty())
838  {
839  solution_callback(ik_pose, solution, error_code);
840  }
841  else
842  {
843  error_code.val = error_code.SUCCESS;
844  }
845 
846  if(error_code.val == error_code.SUCCESS)
847  {
848  nvalid++;
849  if (search_mode & OPTIMIZE_MAX_JOINT)
850  {
851  // Costs for solution: Largest joint motion
852  double costs = 0.0;
853  for(unsigned int i = 0; i < solution.size(); i++)
854  {
855  double d = fabs(ik_seed_state[i] - solution[i]);
856  if (d > costs)
857  costs = d;
858  }
859  if (costs < best_costs || best_costs == -1.0)
860  {
861  best_costs = costs;
862  best_solution = solution;
863  }
864  }
865  else
866  // Return first feasible solution
867  return true;
868  }
869  }
870  }
871  }
872 
873  if(!getCount(counter, num_positive_increments, -num_negative_increments))
874  {
875  // Everything searched
876  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
877  break;
878  }
879 
880  vfree[0] = initial_guess+search_discretization_*counter;
881  //ROS_DEBUG_STREAM_NAMED("ikfast","Attempt " << counter << " with 0th free joint having value " << vfree[0]);
882  }
883 
884  ROS_DEBUG_STREAM_NAMED("ikfast", "Valid solutions: " << nvalid << "/" << nattempts);
885 
886  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
887  {
888  solution = best_solution;
889  error_code.val = error_code.SUCCESS;
890  return true;
891  }
892 
893  // No solution found
894  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
895  return false;
896 }
897 
898 // Used when there are no redundant joints - aka no free params
899 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
900  const std::vector<double> &ik_seed_state,
901  std::vector<double> &solution,
902  moveit_msgs::MoveItErrorCodes &error_code,
903  const kinematics::KinematicsQueryOptions &options) const
904 {
905  ROS_DEBUG_STREAM_NAMED("ikfast","getPositionIK");
906 
907  if(!active_)
908  {
909  ROS_ERROR("kinematics not active");
910  return false;
911  }
912 
913  std::vector<double> vfree(free_params_.size());
914  for(std::size_t i = 0; i < free_params_.size(); ++i)
915  {
916  int p = free_params_[i];
917  ROS_ERROR("%u is %f",p,ik_seed_state[p]); // DTC
918  vfree[i] = ik_seed_state[p];
919  }
920 
921  KDL::Frame frame;
922  tf::poseMsgToKDL(ik_pose,frame);
923 
924  IkSolutionList<IkReal> solutions;
925  int numsol = solve(frame,vfree,solutions);
926 
927  ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
928 
929  if(numsol)
930  {
931  for(int s = 0; s < numsol; ++s)
932  {
933  std::vector<double> sol;
934  getSolution(solutions,s,sol);
935  ROS_DEBUG_NAMED("ikfast","Sol %d: %e %e %e %e %e %e", s, sol[0], sol[1], sol[2], sol[3], sol[4], sol[5]);
936 
937  bool obeys_limits = true;
938  for(unsigned int i = 0; i < sol.size(); i++)
939  {
940  // Add tolerance to limit check
941  if(joint_has_limits_vector_[i] && ( (sol[i] < (joint_min_vector_[i]-LIMIT_TOLERANCE)) ||
942  (sol[i] > (joint_max_vector_[i]+LIMIT_TOLERANCE)) ) )
943  {
944  // One element of solution is not within limits
945  obeys_limits = false;
946  ROS_DEBUG_STREAM_NAMED("ikfast","Not in limits! " << i << " value " << sol[i] << " has limit: " << joint_has_limits_vector_[i] << " being " << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
947  break;
948  }
949  }
950  if(obeys_limits)
951  {
952  // All elements of solution obey limits
953  getSolution(solutions,s,solution);
954  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
955  return true;
956  }
957  }
958  }
959  else
960  {
961  ROS_DEBUG_STREAM_NAMED("ikfast","No IK solution");
962  }
963 
964  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
965  return false;
966 }
967 
968 
969 
970 } // end namespace
971 
972 //register IKFastKinematicsPlugin as a KinematicsBase implementation
d
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:239
IkParameterizationType
The types of inverse kinematics parameterizations supported.
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
#define ROS_FATAL(...)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
#define ROS_WARN_NAMED(name,...)
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:249
direction on end effector coordinate system points to desired 3D position
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...
XmlRpcServer s
The discrete solutions are returned in this structure.
Definition: ikfast.h:65
end effector origin and direction reaches desired 3D translation and direction. Can be thought of as ...
#define ROS_INFO_STREAM_NAMED(name, args)
#define M_PI
virtual void Clear()
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
Definition: ikfast.h:253
virtual const std::vector< int > & GetFree() const =0
Gets the indices of the configuration space that have to be preset before a full solution can be retu...
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.
local point on end effector origin reaches desired 3D global point
void getClosestSolution(const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
Rotation M
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
#define ROS_DEBUG_NAMED(name,...)
end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
direction on end effector coordinate system reaches desired direction
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
void getSolution(const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const
Gets a specific solution from the set.
end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
virtual const std::string & getTipFrame() const
end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to x...
#define ROS_FATAL_STREAM_NAMED(name, args)
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
bit is set if the ikparameterization contains custom data, this is only used when serializing the ik ...
double data[3]
end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
double harmonize(const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to y...
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)
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 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.
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
bool getCount(int &count, const int &max_count, const int &min_count) const
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
2D translation along XY plane and 1D rotation around Z axis. The offset of the rotation is measured s...
SEARCH_MODE
Search modes for searchPositionIK(), see there.
Default implementation of IkSolutionListBase.
Definition: ikfast.h:229
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
static Time now()
int solve(KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
Calls the IK solver from IKFast.
const double LIMIT_TOLERANCE
ray on end effector coordinate system reaches desired global ray
#define ROS_ERROR(...)
end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
PLUGINLIB_EXPORT_CLASS(nextage_left_arm_ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase)
#define ROS_WARN_STREAM_NAMED(name, args)
double data[9]


nextage_ik_plugin
Author(s): TORK Developer 534o <534o@opensouce-robotics.tokyo.jp>
autogenerated on Wed Jun 17 2020 04:14:36