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 #include <console_bridge/console.h>
45 
46 #include <boost/function.hpp>
47 #include <string>
48 
49 namespace moveit
50 {
51 namespace core
52 {
53 class JointModelGroup;
54 class RobotState;
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 ration 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 
166  virtual bool
167  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
168  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
170 
186  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
187  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
188  const kinematics::KinematicsQueryOptions& options) const;
189 
203  virtual bool
204  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
205  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
207 
223  virtual bool
224  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
225  const std::vector<double>& consistency_limits, std::vector<double>& solution,
226  moveit_msgs::MoveItErrorCodes& error_code,
228 
243  virtual bool searchPositionIK(
244  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
245  std::vector<double>& solution, const IKCallbackFn& solution_callback, 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  CONSOLE_BRIDGE_logError("moveit.kinematics_base: This kinematic solver "
319  "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  virtual void setValues(const std::string& robot_description, const std::string& group_name,
344  const std::string& base_frame, const std::string& tip_frame, double search_discretization);
345 
356  virtual void setValues(const std::string& robot_description, const std::string& group_name,
357  const std::string& base_frame, const std::vector<std::string>& tip_frames,
358  double search_discretization);
359 
371  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) = 0;
374 
386  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
387  const std::string& base_frame, const std::vector<std::string>& tip_frames,
388  double search_discretization)
389  {
390  // For IK solvers that do not support multiple tip frames, fall back to single pose call
391  if (tip_frames.size() == 1)
392  {
393  return initialize(robot_description, group_name, base_frame, tip_frames[0], search_discretization);
394  }
395 
396  CONSOLE_BRIDGE_logError("moveit.kinematics_base: This kinematic solver "
397  "does not support initialization with more than one tip frames");
398  return false;
399  }
400 
405  virtual const std::string& getGroupName() const
406  {
407  return group_name_;
408  }
409 
415  virtual const std::string& getBaseFrame() const
416  {
417  return base_frame_;
418  }
419 
427  virtual const std::string& getTipFrame() const
428  {
429  if (tip_frames_.size() > 1)
430  CONSOLE_BRIDGE_logError("moveit.kinematics_base: This kinematic solver has more than one tip frame, "
431  "do not call getTipFrame()");
432 
433  return tip_frame_; // for backwards-compatibility. should actually use tip_frames_[0]
434  }
435 
441  virtual const std::vector<std::string>& getTipFrames() const
442  {
443  return tip_frames_;
444  }
445 
455  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
456 
464  bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
465 
469  virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
470  {
471  redundant_joint_indices = redundant_joint_indices_;
472  }
473 
477  virtual const std::vector<std::string>& getJointNames() const = 0;
478 
482  virtual const std::vector<std::string>& getLinkNames() const = 0;
483 
500  virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = NULL) const;
501 
505  void setSearchDiscretization(double sd)
506  {
507  redundant_joint_discretization_.clear();
508  for (std::vector<unsigned int>::iterator i = redundant_joint_indices_.begin(); i != redundant_joint_indices_.end();
509  i++)
510  {
511  redundant_joint_discretization_[*i] = sd;
512  }
513  }
514 
522  void setSearchDiscretization(const std::map<int, double>& discretization)
523  {
524  redundant_joint_discretization_.clear();
525  redundant_joint_indices_.clear();
526  for (std::map<int, double>::const_iterator i = discretization.begin(); i != discretization.end(); i++)
527  {
528  redundant_joint_discretization_.insert(*i);
529  redundant_joint_indices_.push_back(i->first);
530  }
531  }
532 
536  double getSearchDiscretization(int joint_index = 0) const
537  {
538  if (redundant_joint_discretization_.count(joint_index) > 0)
539  {
540  return redundant_joint_discretization_.at(joint_index);
541  }
542  else
543  {
544  return 0.0; // returned when there aren't any redundant joints
545  }
546  }
547 
552  std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
553  {
554  return supported_methods_;
555  }
556 
559  void setDefaultTimeout(double timeout)
560  {
561  default_timeout_ = timeout;
562  }
563 
566  double getDefaultTimeout() const
567  {
568  return default_timeout_;
569  }
570 
574  virtual ~KinematicsBase()
575  {
576  }
577 
579  : tip_frame_("DEPRECATED")
580  , // help users understand why this variable might not be set
581  // (if multiple tip frames provided, this variable will be unset)
582  search_discretization_(DEFAULT_SEARCH_DISCRETIZATION)
583  , default_timeout_(DEFAULT_TIMEOUT)
584  {
585  supported_methods_.push_back(DiscretizationMethods::NO_DISCRETIZATION);
586  }
587 
588 protected:
589  std::string robot_description_;
590  std::string group_name_;
591  std::string base_frame_;
592  std::vector<std::string> tip_frames_;
593  std::string tip_frame_; // DEPRECATED - this variable only still exists for backwards compatibility with
594  // previously generated custom ik solvers like IKFast
595 
596  double search_discretization_; // DEPRECATED - this variable only still exists for backwards compatibility
597  // with previous implementations. Discretization values for each joint are
598  // now stored in the redundant_joint_discretization_ member
599 
601  std::vector<unsigned int> redundant_joint_indices_;
602  std::map<int, double> redundant_joint_discretization_;
603  std::vector<DiscretizationMethod> supported_methods_;
604 
618  template <typename T>
619  inline bool lookupParam(const std::string& param, T& val, const T& default_val) const
620  {
621  ros::NodeHandle pnh("~");
622  if (pnh.hasParam(group_name_ + "/" + param))
623  {
624  val = pnh.param(group_name_ + "/" + param, default_val);
625  return true;
626  }
627 
628  if (pnh.hasParam(param))
629  {
630  val = pnh.param(param, default_val);
631  return true;
632  }
633 
634  ros::NodeHandle nh;
635  if (nh.hasParam("robot_description_kinematics/" + group_name_ + "/" + param))
636  {
637  val = nh.param("robot_description_kinematics/" + group_name_ + "/" + param, default_val);
638  return true;
639  }
640 
641  if (nh.hasParam("robot_description_kinematics/" + param))
642  {
643  val = nh.param("robot_description_kinematics/" + param, default_val);
644  return true;
645  }
646 
647  val = default_val;
648 
649  return false;
650  }
651 
652 private:
653  std::string removeSlash(const std::string& str) const;
654 };
655 };
656 
657 #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
#define CONSOLE_BRIDGE_logError(fmt,...)
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets individual discretization values for each redundant joint.
API for forward and inverse kinematics.
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:110
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 Sat Apr 21 2018 02:54:51