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>
43 #include <ros/node_handle.h>
44 
45 #include <boost/function.hpp>
46 #include <string>
47 
48 namespace moveit
49 {
50 namespace core
51 {
55 }
56 }
57 
59 namespace kinematics
60 {
61 /*
62  * @enum DiscretizationMethods
63  *
64  * @brief Flags for choosing the type discretization method applied on the redundant joints during an ik query
65  */
66 namespace DiscretizationMethods
67 {
69 {
78 };
79 }
81 
82 /*
83  * @enum KinematicErrors
84  * @brief Kinematic error codes that occur in a ik query
85  */
86 namespace KinematicErrors
87 {
89 {
90  OK = 1,
100 };
101 }
103 
109 {
111  : lock_redundant_joints(false)
112  , return_approximate_solution(false)
113  , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
114  {
115  }
116 
119  DiscretizationMethod discretization_method;
121 };
122 
123 /*
124  * @struct KinematicsResult
125  * @brief Reports result details of an ik query
126  *
127  * This struct is used as an output argument of the getPositionIK(...) method that returns multiple joint solutions.
128  * It contains the type of error that led to a failure or KinematicErrors::OK when a set of joint solutions is found.
129  * The solution percentage shall provide a ratio of solutions found over solutions searched.
130  *
131  */
133 {
134  KinematicError kinematic_error;
137 };
138 
140 
146 {
147 public:
148  static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */
149  static const double DEFAULT_TIMEOUT; /* = 1.0 */
150 
152  typedef boost::function<void(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_solution,
153  moveit_msgs::MoveItErrorCodes& error_code)>
155 
168  virtual bool
169  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
170  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
172 
194  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
195  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
196  const kinematics::KinematicsQueryOptions& options) const;
197 
210  virtual bool
211  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
212  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
214 
229  virtual bool
230  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
231  const std::vector<double>& consistency_limits, std::vector<double>& solution,
232  moveit_msgs::MoveItErrorCodes& error_code,
234 
248  virtual bool
249  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
250  std::vector<double>& solution, const IKCallbackFn& solution_callback,
251  moveit_msgs::MoveItErrorCodes& error_code,
253 
269  virtual bool
270  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
271  const std::vector<double>& consistency_limits, std::vector<double>& solution,
272  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
274 
296  virtual bool
297  searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
298  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
299  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
301  const moveit::core::RobotState* context_state = NULL) const
302  {
303  // For IK solvers that do not support multiple poses, fall back to single pose call
304  if (ik_poses.size() == 1)
305  {
306  // Check if a solution_callback function was provided and call the corresponding function
307  if (solution_callback)
308  {
309  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
310  error_code, options);
311  }
312  else
313  {
314  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
315  }
316  }
317 
318  // Otherwise throw error because this function should have been implemented
319  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver does not support searchPositionIK with multiple poses");
320  return false;
321  }
322 
330  virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
331  std::vector<geometry_msgs::Pose>& poses) const = 0;
332 
343  /* Replace by tip_frames-based method! */
344  [[deprecated]] virtual void setValues(const std::string& robot_description, const std::string& group_name,
345  const std::string& base_frame, const std::string& tip_frame,
346  double search_discretization);
347 
358  virtual void setValues(const std::string& robot_description, const std::string& group_name,
359  const std::string& base_frame, const std::vector<std::string>& tip_frames,
360  double search_discretization);
361 
376  [[deprecated]] virtual bool initialize(const std::string& robot_description, const std::string& group_name,
377  const std::string& base_frame, const std::string& tip_frame,
378  double search_discretization);
379 
394  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
395  const std::string& base_frame, const std::vector<std::string>& tip_frames,
396  double search_discretization);
397 
412  virtual bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
413  const std::string& base_frame, const std::vector<std::string>& tip_frames,
414  double search_discretization);
415 
420  virtual const std::string& getGroupName() const
421  {
422  return group_name_;
423  }
424 
430  virtual const std::string& getBaseFrame() const
431  {
432  return base_frame_;
433  }
434 
440  virtual const std::string& getTipFrame() const
441  {
442  if (tip_frames_.size() > 1)
443  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver has more than one tip frame, "
444  "do not call getTipFrame()");
445 
446  return tip_frames_[0];
447  }
448 
454  virtual const std::vector<std::string>& getTipFrames() const
455  {
456  return tip_frames_;
457  }
458 
467  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
468 
475  bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
476 
480  virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
481  {
482  redundant_joint_indices = redundant_joint_indices_;
483  }
484 
488  virtual const std::vector<std::string>& getJointNames() const = 0;
489 
493  virtual const std::vector<std::string>& getLinkNames() const = 0;
494 
511  virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = NULL) const;
512 
516  void setSearchDiscretization(double sd)
517  {
518  redundant_joint_discretization_.clear();
519  for (unsigned int index : redundant_joint_indices_)
520  redundant_joint_discretization_[index] = sd;
521  }
522 
530  void setSearchDiscretization(const std::map<int, double>& discretization)
531  {
532  redundant_joint_discretization_.clear();
533  redundant_joint_indices_.clear();
534  for (std::map<int, double>::const_iterator i = discretization.begin(); i != discretization.end(); i++)
535  {
536  redundant_joint_discretization_.insert(*i);
537  redundant_joint_indices_.push_back(i->first);
538  }
539  }
540 
544  double getSearchDiscretization(int joint_index = 0) const
545  {
546  if (redundant_joint_discretization_.count(joint_index) > 0)
547  {
548  return redundant_joint_discretization_.at(joint_index);
549  }
550  else
551  {
552  return 0.0; // returned when there aren't any redundant joints
553  }
554  }
555 
560  std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
561  {
562  return supported_methods_;
563  }
564 
567  void setDefaultTimeout(double timeout)
568  {
569  default_timeout_ = timeout;
570  }
571 
574  double getDefaultTimeout() const
575  {
576  return default_timeout_;
577  }
578 
582  virtual ~KinematicsBase();
583 
584  KinematicsBase();
585 
586 protected:
587  moveit::core::RobotModelConstPtr robot_model_;
588  std::string robot_description_;
589  std::string group_name_;
590  std::string base_frame_;
591  std::vector<std::string> tip_frames_;
592 
593  // The next two variables still exists for backwards compatibility
594  // with previously generated custom ik solvers like IKFast
595  // Replace tip_frame_ -> tip_frames_[0], search_discretization_ -> redundant_joint_discretization_
596  [[deprecated]] std::string tip_frame_;
597  [[deprecated]] double search_discretization_;
598 
600  std::vector<unsigned int> redundant_joint_indices_;
601  std::map<int, double> redundant_joint_discretization_;
602  std::vector<DiscretizationMethod> supported_methods_;
603 
617  template <typename T>
618  inline bool lookupParam(const std::string& param, T& val, const T& default_val) const
619  {
620  ros::NodeHandle pnh("~");
621  if (pnh.hasParam(group_name_ + "/" + param))
622  {
623  val = pnh.param(group_name_ + "/" + param, default_val);
624  return true;
625  }
626 
627  if (pnh.hasParam(param))
628  {
629  val = pnh.param(param, default_val);
630  return true;
631  }
632 
633  ros::NodeHandle nh;
634  if (nh.hasParam("robot_description_kinematics/" + group_name_ + "/" + param))
635  {
636  val = nh.param("robot_description_kinematics/" + group_name_ + "/" + param, default_val);
637  return true;
638  }
639 
640  if (nh.hasParam("robot_description_kinematics/" + param))
641  {
642  val = nh.param("robot_description_kinematics/" + param, default_val);
643  return true;
644  }
645 
646  val = default_val;
647 
648  return false;
649  }
650 
659  void storeValues(const moveit::core::RobotModel& robot_model, const std::string& group_name,
660  const std::string& base_frame, const std::vector<std::string>& tip_frames,
661  double search_discretization);
662 
663 private:
664  std::string removeSlash(const std::string& str) const;
665 };
666 };
667 
668 #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.
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
bool param(const std::string &param_name, T &param_val, const T &default_val) const
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:122
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 Thu Jul 2 2020 03:55:08