kinematics_base.h
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, Dave Coleman */
36 
37 #ifndef MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_
38 #define MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_
39 
40 #include <geometry_msgs/PoseStamped.h>
41 #include <moveit_msgs/MoveItErrorCodes.h>
44 #include <ros/node_handle.h>
45 
46 #include <boost/function.hpp>
47 #include <string>
48 
49 namespace moveit
50 {
51 namespace core
52 {
56 }
57 }
58 
60 namespace kinematics
61 {
62 /*
63  * @enum DiscretizationMethods
64  *
65  * @brief Flags for choosing the type discretization method applied on the redundant joints during an ik query
66  */
67 namespace DiscretizationMethods
68 {
70 {
79 };
80 }
82 
83 /*
84  * @enum KinematicErrors
85  * @brief Kinematic error codes that occur in a ik query
86  */
87 namespace KinematicErrors
88 {
90 {
91  OK = 1,
101 };
102 }
104 
110 {
112  : lock_redundant_joints(false)
113  , return_approximate_solution(false)
114  , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
115  {
116  }
117 
120  DiscretizationMethod discretization_method;
122 };
123 
124 /*
125  * @struct KinematicsResult
126  * @brief Reports result details of an ik query
127  *
128  * This struct is used as an output argument of the getPositionIK(...) method that returns multiple joint solutions.
129  * It contains the type of error that led to a failure or KinematicErrors::OK when a set of joint solutions is found.
130  * The solution percentage shall provide a ratio of solutions found over solutions searched.
131  *
132  */
134 {
135  KinematicError kinematic_error;
138 };
139 
141 
147 {
148 public:
149  static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */
150  static const double DEFAULT_TIMEOUT; /* = 1.0 */
151 
153  typedef boost::function<void(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_solution,
154  moveit_msgs::MoveItErrorCodes& error_code)>
156 
169  virtual bool
170  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
171  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
173 
189  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
190  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
191  const kinematics::KinematicsQueryOptions& options) const;
192 
205  virtual bool
206  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
207  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
209 
224  virtual bool
225  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
226  const std::vector<double>& consistency_limits, std::vector<double>& solution,
227  moveit_msgs::MoveItErrorCodes& error_code,
229 
243  virtual bool
244  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
245  std::vector<double>& solution, const IKCallbackFn& solution_callback,
246  moveit_msgs::MoveItErrorCodes& error_code,
248 
264  virtual bool
265  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
266  const std::vector<double>& consistency_limits, std::vector<double>& solution,
267  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
269 
291  virtual bool
292  searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
293  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
294  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
296  const moveit::core::RobotState* context_state = NULL) const
297  {
298  // For IK solvers that do not support multiple poses, fall back to single pose call
299  if (ik_poses.size() == 1)
300  {
301  // Check if a solution_callback function was provided and call the corresponding function
302  if (solution_callback)
303  {
304  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
305  error_code, options);
306  }
307  else
308  {
309  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
310  }
311  }
312 
313  // Otherwise throw error because this function should have been implemented
314  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver does not support searchPositionIK with multiple poses");
315  return false;
316  }
317 
325  virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
326  std::vector<geometry_msgs::Pose>& poses) const = 0;
327 
338  /* Replace by tip_frames-based method! */
339  MOVEIT_DEPRECATED virtual void setValues(const std::string& robot_description, const std::string& group_name,
340  const std::string& base_frame, const std::string& tip_frame,
341  double search_discretization);
342 
353  virtual void setValues(const std::string& robot_description, const std::string& group_name,
354  const std::string& base_frame, const std::vector<std::string>& tip_frames,
355  double search_discretization);
356 
371  MOVEIT_DEPRECATED virtual bool initialize(const std::string& robot_description, const std::string& group_name,
372  const std::string& base_frame, const std::string& tip_frame,
373  double search_discretization);
374 
389  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
390  const std::string& base_frame, const std::vector<std::string>& tip_frames,
391  double search_discretization);
392 
407  virtual bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
408  const std::string& base_frame, const std::vector<std::string>& tip_frames,
409  double search_discretization);
410 
415  virtual const std::string& getGroupName() const
416  {
417  return group_name_;
418  }
419 
425  virtual const std::string& getBaseFrame() const
426  {
427  return base_frame_;
428  }
429 
435  virtual const std::string& getTipFrame() const
436  {
437  if (tip_frames_.size() > 1)
438  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver has more than one tip frame, "
439  "do not call getTipFrame()");
440 
441  return tip_frames_[0];
442  }
443 
449  virtual const std::vector<std::string>& getTipFrames() const
450  {
451  return tip_frames_;
452  }
453 
462  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
463 
470  bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
471 
475  virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
476  {
477  redundant_joint_indices = redundant_joint_indices_;
478  }
479 
483  virtual const std::vector<std::string>& getJointNames() const = 0;
484 
488  virtual const std::vector<std::string>& getLinkNames() const = 0;
489 
506  virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = NULL) const;
507 
511  void setSearchDiscretization(double sd)
512  {
513  redundant_joint_discretization_.clear();
514  for (unsigned int index : redundant_joint_indices_)
515  redundant_joint_discretization_[index] = sd;
516  }
517 
525  void setSearchDiscretization(const std::map<int, double>& discretization)
526  {
527  redundant_joint_discretization_.clear();
528  redundant_joint_indices_.clear();
529  for (std::map<int, double>::const_iterator i = discretization.begin(); i != discretization.end(); i++)
530  {
531  redundant_joint_discretization_.insert(*i);
532  redundant_joint_indices_.push_back(i->first);
533  }
534  }
535 
539  double getSearchDiscretization(int joint_index = 0) const
540  {
541  if (redundant_joint_discretization_.count(joint_index) > 0)
542  {
543  return redundant_joint_discretization_.at(joint_index);
544  }
545  else
546  {
547  return 0.0; // returned when there aren't any redundant joints
548  }
549  }
550 
555  std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
556  {
557  return supported_methods_;
558  }
559 
562  void setDefaultTimeout(double timeout)
563  {
564  default_timeout_ = timeout;
565  }
566 
569  double getDefaultTimeout() const
570  {
571  return default_timeout_;
572  }
573 
577  virtual ~KinematicsBase();
578 
579  KinematicsBase();
580 
581 protected:
582  moveit::core::RobotModelConstPtr robot_model_;
583  std::string robot_description_;
584  std::string group_name_;
585  std::string base_frame_;
586  std::vector<std::string> tip_frames_;
587 
588  // The next two variables still exists for backwards compatibility
589  // with previously generated custom ik solvers like IKFast
590  // Replace tip_frame_ -> tip_frames_[0], search_discretization_ -> redundant_joint_discretization_
593 
595  std::vector<unsigned int> redundant_joint_indices_;
596  std::map<int, double> redundant_joint_discretization_;
597  std::vector<DiscretizationMethod> supported_methods_;
598 
612  template <typename T>
613  inline bool lookupParam(const std::string& param, T& val, const T& default_val) const
614  {
615  ros::NodeHandle pnh("~");
616  if (pnh.hasParam(group_name_ + "/" + param))
617  {
618  val = pnh.param(group_name_ + "/" + param, default_val);
619  return true;
620  }
621 
622  if (pnh.hasParam(param))
623  {
624  val = pnh.param(param, default_val);
625  return true;
626  }
627 
628  ros::NodeHandle nh;
629  if (nh.hasParam("robot_description_kinematics/" + group_name_ + "/" + param))
630  {
631  val = nh.param("robot_description_kinematics/" + group_name_ + "/" + param, default_val);
632  return true;
633  }
634 
635  if (nh.hasParam("robot_description_kinematics/" + param))
636  {
637  val = nh.param("robot_description_kinematics/" + param, default_val);
638  return true;
639  }
640 
641  val = default_val;
642 
643  return false;
644  }
645 
654  void storeValues(const moveit::core::RobotModel& robot_model, const std::string& group_name,
655  const std::string& base_frame, const std::vector<std::string>& tip_frames,
656  double search_discretization);
657 
658 private:
659  std::string removeSlash(const std::string& str) const;
660 };
661 };
662 
663 #endif
std::vector< unsigned int > redundant_joint_indices_
A set of options for the kinematics solver.
Core components of MoveIt!
void setDefaultTimeout(double timeout)
For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT)
ROSCONSOLE_DECL void initialize()
virtual const std::string & getTipFrame() const
Return the name of the tip frame of the chain on which the solver is operating. This is usually a lin...
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
#define MOVEIT_DEPRECATED
Definition: deprecation.h:48
std::vector< std::string > tip_frames_
moveit::core::RobotModelConstPtr robot_model_
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
static const double DEFAULT_TIMEOUT
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:67
virtual const std::string & getBaseFrame() const
Return the name of the frame in which the solver is operating. This is usually a link name...
DiscretizationMethods::DiscretizationMethod DiscretizationMethod
Provides an interface for kinematics solvers.
unsigned int index
MOVEIT_DEPRECATED std::string tip_frame_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
MOVEIT_DEPRECATED double search_discretization_
virtual bool searchPositionIK(const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=NULL) const
Given a set of desired poses for a planning group with multiple end-effectors, search for the joint a...
MOVEIT_CLASS_FORWARD(RobotModel)
options
bool lookupParam(const std::string &param, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
double getDefaultTimeout() const
For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.
DiscretizationMethod discretization_method
std::vector< DiscretizationMethod > supported_methods_
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking...
std::vector< DiscretizationMethod > getSupportedDiscretizationMethods() const
Returns the set of supported kinematics discretization search types. This implementation only support...
bool hasParam(const std::string &key) const
std::map< int, double > redundant_joint_discretization_
static const double DEFAULT_SEARCH_DISCRETIZATION
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets individual discretization values for each redundant joint.
API for forward and inverse kinematics.
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
#define ROS_ERROR_NAMED(name,...)
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
Main namespace for MoveIt!
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
KinematicErrors::KinematicError KinematicError


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 17 2019 02:51:53