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 {
52 class JointModelGroup;
53 class RobotState;
54 }
55 }
56 
58 namespace kinematics
59 {
60 /*
61  * @enum DiscretizationMethods
62  *
63  * @brief Flags for choosing the type discretization method applied on the redundant joints during an ik query
64  */
65 namespace DiscretizationMethods
66 {
68 {
77 };
78 }
80 
81 /*
82  * @enum KinematicErrors
83  * @brief Kinematic error codes that occur in a ik query
84  */
85 namespace KinematicErrors
86 {
88 {
89  OK = 1,
99 };
100 }
102 
108 {
110  : lock_redundant_joints(false)
111  , return_approximate_solution(false)
112  , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
113  {
114  }
115 
118  DiscretizationMethod discretization_method;
120 };
121 
122 /*
123  * @struct KinematicsResult
124  * @brief Reports result details of an ik query
125  *
126  * This struct is used as an output argument of the getPositionIK(...) method that returns multiple joint solutions.
127  * It contains the type of error that led to a failure or KinematicErrors::OK when a set of joint solutions is found.
128  * The solution percentage shall provide a ration of solutions found over solutions searched.
129  *
130  */
132 {
133  KinematicError kinematic_error;
136 };
137 
139 
145 {
146 public:
147  static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */
148  static const double DEFAULT_TIMEOUT; /* = 1.0 */
149 
151  typedef boost::function<void(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_solution,
152  moveit_msgs::MoveItErrorCodes& error_code)>
154 
165  virtual bool
166  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
167  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
169 
185  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
186  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
187  const kinematics::KinematicsQueryOptions& options) const;
188 
202  virtual bool
203  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
204  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
206 
222  virtual bool
223  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
224  const std::vector<double>& consistency_limits, std::vector<double>& solution,
225  moveit_msgs::MoveItErrorCodes& error_code,
227 
242  virtual bool
243  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
244  std::vector<double>& solution, const IKCallbackFn& solution_callback,
245  moveit_msgs::MoveItErrorCodes& error_code,
247 
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 
295  virtual bool
296  searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
297  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
298  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
300  const moveit::core::RobotState* context_state = NULL) const
301  {
302  // For IK solvers that do not support multiple poses, fall back to single pose call
303  if (ik_poses.size() == 1)
304  {
305  // Check if a solution_callback function was provided and call the corresponding function
306  if (solution_callback)
307  {
308  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
309  error_code, options);
310  }
311  else
312  {
313  return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
314  }
315  }
316 
317  // Otherwise throw error because this function should have been implemented
318  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver does not support searchPositionIK with multiple poses");
319  return false;
320  }
321 
329  virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
330  std::vector<geometry_msgs::Pose>& poses) const = 0;
331 
342  virtual void setValues(const std::string& robot_description, const std::string& group_name,
343  const std::string& base_frame, const std::string& tip_frame, double search_discretization);
344 
355  virtual void setValues(const std::string& robot_description, const std::string& group_name,
356  const std::string& base_frame, const std::vector<std::string>& tip_frames,
357  double search_discretization);
358 
370  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
371  const std::string& base_frame, const std::string& tip_frame,
372  double search_discretization) = 0;
373 
385  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
386  const std::string& base_frame, const std::vector<std::string>& tip_frames,
387  double search_discretization)
388  {
389  // For IK solvers that do not support multiple tip frames, fall back to single pose call
390  if (tip_frames.size() == 1)
391  {
392  return initialize(robot_description, group_name, base_frame, tip_frames[0], search_discretization);
393  }
394 
395  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver does not support initialization "
396  "with more than one tip frames");
397  return false;
398  }
399 
404  virtual const std::string& getGroupName() const
405  {
406  return group_name_;
407  }
408 
414  virtual const std::string& getBaseFrame() const
415  {
416  return base_frame_;
417  }
418 
426  virtual const std::string& getTipFrame() const
427  {
428  if (tip_frames_.size() > 1)
429  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver has more than one tip frame, "
430  "do not call getTipFrame()");
431 
432  return tip_frame_; // for backwards-compatibility. should actually use tip_frames_[0]
433  }
434 
440  virtual const std::vector<std::string>& getTipFrames() const
441  {
442  return tip_frames_;
443  }
444 
454  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
455 
463  bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
464 
468  virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
469  {
470  redundant_joint_indices = redundant_joint_indices_;
471  }
472 
476  virtual const std::vector<std::string>& getJointNames() const = 0;
477 
481  virtual const std::vector<std::string>& getLinkNames() const = 0;
482 
499  virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = NULL) const;
500 
504  void setSearchDiscretization(double sd)
505  {
506  redundant_joint_discretization_.clear();
507  for (std::vector<unsigned int>::iterator i = redundant_joint_indices_.begin(); i != redundant_joint_indices_.end();
508  i++)
509  {
510  redundant_joint_discretization_[*i] = sd;
511  }
512  }
513 
521  void setSearchDiscretization(const std::map<int, double>& discretization)
522  {
523  redundant_joint_discretization_.clear();
524  redundant_joint_indices_.clear();
525  for (std::map<int, double>::const_iterator i = discretization.begin(); i != discretization.end(); i++)
526  {
527  redundant_joint_discretization_.insert(*i);
528  redundant_joint_indices_.push_back(i->first);
529  }
530  }
531 
535  double getSearchDiscretization(int joint_index = 0) const
536  {
537  if (redundant_joint_discretization_.count(joint_index) > 0)
538  {
539  return redundant_joint_discretization_.at(joint_index);
540  }
541  else
542  {
543  return 0.0; // returned when there aren't any redundant joints
544  }
545  }
546 
551  std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
552  {
553  return supported_methods_;
554  }
555 
558  void setDefaultTimeout(double timeout)
559  {
560  default_timeout_ = timeout;
561  }
562 
565  double getDefaultTimeout() const
566  {
567  return default_timeout_;
568  }
569 
573  virtual ~KinematicsBase()
574  {
575  }
576 
578  : tip_frame_("DEPRECATED")
579  , // help users understand why this variable might not be set
580  // (if multiple tip frames provided, this variable will be unset)
581  search_discretization_(DEFAULT_SEARCH_DISCRETIZATION)
582  , default_timeout_(DEFAULT_TIMEOUT)
583  {
584  supported_methods_.push_back(DiscretizationMethods::NO_DISCRETIZATION);
585  }
586 
587 protected:
588  std::string robot_description_;
589  std::string group_name_;
590  std::string base_frame_;
591  std::vector<std::string> tip_frames_;
592  std::string tip_frame_; // DEPRECATED - this variable only still exists for backwards compatibility with
593  // previously generated custom ik solvers like IKFast
594 
595  double search_discretization_; // DEPRECATED - this variable only still exists for backwards compatibility
596  // with previous implementations. Discretization values for each joint are
597  // now stored in the redundant_joint_discretization_ member
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 
651 private:
652  std::string removeSlash(const std::string& str) const;
653 };
654 };
655 
656 #endif
std::vector< unsigned int > redundant_joint_indices_
double getDefaultTimeout() const
For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.
A set of options for the kinematics solver.
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
virtual const std::string & getBaseFrame() const
Return the name of the frame in which the solver is operating. This is usually a link name...
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()
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
std::vector< std::string > tip_frames_
static const double DEFAULT_TIMEOUT
std::vector< DiscretizationMethod > getSupportedDiscretizationMethods() const
Returns the set of supported kinematics discretization search types. This implementation only support...
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.
DiscretizationMethods::DiscretizationMethod DiscretizationMethod
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
Provides an interface for kinematics solvers.
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
MOVEIT_CLASS_FORWARD(RobotModel)
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...
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual ~KinematicsBase()
Virtual destructor for the interface.
DiscretizationMethod discretization_method
std::vector< DiscretizationMethod > supported_methods_
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...
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
The signature for a callback that can compute IK.
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...
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.
#define ROS_ERROR_NAMED(name,...)
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Initialization function for the kinematics, for use with non-chain IK solvers.
bool hasParam(const std::string &key) const
Main namespace for MoveIt!
KinematicErrors::KinematicError KinematicError


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05