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 #pragma once
38 
39 #include <geometry_msgs/Pose.h>
40 #include <moveit_msgs/MoveItErrorCodes.h>
42 #include <ros/node_handle.h>
43 
44 #include <boost/function.hpp>
45 #include <string>
46 
47 namespace moveit
48 {
49 namespace core
50 {
51 MOVEIT_CLASS_FORWARD(JointModelGroup)
52 MOVEIT_CLASS_FORWARD(RobotState)
53 MOVEIT_CLASS_FORWARD(RobotModel)
54 } // namespace core
55 } // namespace moveit
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 } // namespace DiscretizationMethods
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 } // namespace KinematicErrors
102 
108 {
110  : lock_redundant_joints(false)
112  , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
113  {
114  }
115 
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 ratio of solutions found over solutions searched.
129  *
130  */
132 {
136 };
137 
138 MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, WeakPtr... etc
139 
145 {
146 public:
147  static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */
148  static const double DEFAULT_TIMEOUT; /* = 1.0 */
149 
151  using IKCallbackFn =
152  boost::function<void(const geometry_msgs::Pose&, const std::vector<double>&, moveit_msgs::MoveItErrorCodes&)>;
153 
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 
192  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
193  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
194  const kinematics::KinematicsQueryOptions& options) const;
195 
208  virtual bool
209  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
210  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
212 
227  virtual bool
228  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
229  const std::vector<double>& consistency_limits, std::vector<double>& solution,
230  moveit_msgs::MoveItErrorCodes& error_code,
232 
246  virtual bool
247  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
248  std::vector<double>& solution, const IKCallbackFn& solution_callback,
249  moveit_msgs::MoveItErrorCodes& error_code,
251 
267  virtual bool
268  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
269  const std::vector<double>& consistency_limits, std::vector<double>& solution,
270  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
272 
294  virtual bool
295  searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
296  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
297  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
299  const moveit::core::RobotState* context_state = nullptr) const
300  {
301  (void)context_state;
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  /* Replace by tip_frames-based method! */
343  [[deprecated]] virtual void setValues(const std::string& robot_description, const std::string& group_name,
344  const std::string& base_frame, const std::string& tip_frame,
345  double search_discretization);
346 
357  virtual void setValues(const std::string& robot_description, const std::string& group_name,
358  const std::string& base_frame, const std::vector<std::string>& tip_frames,
359  double search_discretization);
360 
375  [[deprecated]] virtual bool initialize(const std::string& robot_description, const std::string& group_name,
376  const std::string& base_frame, const std::string& tip_frame,
377  double search_discretization);
378 
393  virtual bool initialize(const std::string& robot_description, const std::string& group_name,
394  const std::string& base_frame, const std::vector<std::string>& tip_frames,
395  double search_discretization);
396 
411  virtual bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
412  const std::string& base_frame, const std::vector<std::string>& tip_frames,
413  double search_discretization);
414 
419  virtual const std::string& getGroupName() const
420  {
421  return group_name_;
422  }
423 
429  virtual const std::string& getBaseFrame() const
430  {
431  return base_frame_;
432  }
433 
439  virtual const std::string& getTipFrame() const
440  {
441  if (tip_frames_.size() > 1)
442  ROS_ERROR_NAMED("kinematics_base", "This kinematic solver has more than one tip frame, "
443  "do not call getTipFrame()");
444 
445  return tip_frames_[0];
446  }
447 
453  virtual const std::vector<std::string>& getTipFrames() const
454  {
455  return tip_frames_;
456  }
457 
466  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
467 
474  bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
475 
479  virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
480  {
481  redundant_joint_indices = redundant_joint_indices_;
482  }
483 
487  virtual const std::vector<std::string>& getJointNames() const = 0;
488 
492  virtual const std::vector<std::string>& getLinkNames() const = 0;
493 
510  virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = nullptr) const;
511 
515  void setSearchDiscretization(double sd)
516  {
518  for (unsigned int index : redundant_joint_indices_)
520  }
521 
529  void setSearchDiscretization(const std::map<int, double>& discretization)
530  {
532  redundant_joint_indices_.clear();
533  for (const auto& pair : discretization)
534  {
535  redundant_joint_discretization_.insert(pair);
536  redundant_joint_indices_.push_back(pair.first);
537  }
538  }
539 
543  double getSearchDiscretization(int joint_index = 0) const
544  {
545  if (redundant_joint_discretization_.count(joint_index) > 0)
546  {
547  return redundant_joint_discretization_.at(joint_index);
548  }
549  else
550  {
551  return 0.0; // returned when there aren't any redundant joints
552  }
553  }
554 
559  std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
560  {
561  return supported_methods_;
562  }
563 
566  void setDefaultTimeout(double timeout)
567  {
568  default_timeout_ = timeout;
569  }
570 
573  double getDefaultTimeout() const
574  {
575  return default_timeout_;
576  }
577 
581  virtual ~KinematicsBase();
582 
583  KinematicsBase();
584 
585 protected:
586  moveit::core::RobotModelConstPtr robot_model_;
587  std::string robot_description_;
588  std::string group_name_;
589  std::string base_frame_;
590  std::vector<std::string> tip_frames_;
591 
592  // The next two variables still exists for backwards compatibility
593  // with previously generated custom ik solvers like IKFast
594  // Replace tip_frame_ -> tip_frames_[0], search_discretization_ -> redundant_joint_discretization_
595  [[deprecated]] std::string tip_frame_;
596  [[deprecated]] double search_discretization_;
597 
599  std::vector<unsigned int> redundant_joint_indices_;
600  std::map<int, double> redundant_joint_discretization_;
601  std::vector<DiscretizationMethod> supported_methods_;
602 
616  template <typename T>
617  inline bool lookupParam(const std::string& param, T& val, const T& default_val) const
618  {
619  ros::NodeHandle pnh("~");
620  if (pnh.hasParam(group_name_ + "/" + param))
621  {
622  val = pnh.param(group_name_ + "/" + param, default_val);
623  return true;
624  }
625 
626  if (pnh.hasParam(param))
627  {
628  val = pnh.param(param, default_val);
629  return true;
630  }
631 
632  ros::NodeHandle nh;
633  if (nh.hasParam("robot_description_kinematics/" + group_name_ + "/" + param))
634  {
635  val = nh.param("robot_description_kinematics/" + group_name_ + "/" + param, default_val);
636  return true;
637  }
638 
639  if (nh.hasParam("robot_description_kinematics/" + param))
640  {
641  val = nh.param("robot_description_kinematics/" + param, default_val);
642  return true;
643  }
644 
645  val = default_val;
646 
647  return false;
648  }
649 
658  void storeValues(const moveit::core::RobotModel& robot_model, const std::string& group_name,
659  const std::string& base_frame, const std::vector<std::string>& tip_frames,
660  double search_discretization);
661 
662 private:
663  std::string removeSlash(const std::string& str) const;
664 };
665 } // namespace kinematics
kinematics::KinematicsBase::setRedundantJoints
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
Definition: kinematics_base.cpp:130
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:81
node_handle.h
kinematics::DiscretizationMethods::SOME_DISCRETIZED
@ SOME_DISCRETIZED
Definition: kinematics_base.h:71
kinematics::KinematicsQueryOptions::return_approximate_solution
bool return_approximate_solution
Definition: kinematics_base.h:117
kinematics::KinematicsBase::supported_methods_
std::vector< DiscretizationMethod > supported_methods_
Definition: kinematics_base.h:601
kinematics::DiscretizationMethods::SOME_RANDOM_SAMPLED
@ SOME_RANDOM_SAMPLED
Definition: kinematics_base.h:75
kinematics::KinematicsBase::lookupParam
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...
Definition: kinematics_base.h:617
kinematics::KinematicsBase::storeValues
void storeValues(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Definition: kinematics_base.cpp:51
kinematics::KinematicsBase::getDefaultTimeout
double getDefaultTimeout() const
For functions that require a timeout specified but one is not specified using arguments,...
Definition: kinematics_base.h:573
kinematics::KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION
static const double DEFAULT_SEARCH_DISCRETIZATION
Definition: kinematics_base.h:147
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
kinematics::KinematicsBase::setSearchDiscretization
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets individual discretization values for each redundant joint.
Definition: kinematics_base.h:529
kinematics::KinematicsQueryOptions::KinematicsQueryOptions
KinematicsQueryOptions()
Definition: kinematics_base.h:109
kinematics::KinematicsBase::getPositionFK
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const =0
Given a set of joint angles and a set of links, compute their pose.
kinematics::KinematicsBase::getSupportedDiscretizationMethods
std::vector< DiscretizationMethod > getSupportedDiscretizationMethods() const
Returns the set of supported kinematics discretization search types. This implementation only support...
Definition: kinematics_base.h:559
moveit::core::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(RobotModel)
kinematics::KinematicsResult::solution_percentage
double solution_percentage
Definition: kinematics_base.h:134
kinematics::KinematicsBase::setValues
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)
Set the parameters for the solver, for use with kinematic chain IK solvers.
Definition: kinematics_base.cpp:91
moveit::core::RobotModel
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:132
kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED
@ MULTIPLE_TIPS_NOT_SUPPORTED
Definition: kinematics_base.h:93
kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED
@ ALL_RANDOM_SAMPLED
Definition: kinematics_base.h:74
kinematics::KinematicsBase::getGroupName
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
Definition: kinematics_base.h:419
kinematics::KinematicsBase::redundant_joint_discretization_
std::map< int, double > redundant_joint_discretization_
Definition: kinematics_base.h:600
class_forward.h
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
kinematics::KinematicErrors::KinematicError
KinematicError
Definition: kinematics_base.h:87
kinematics::KinematicsBase::search_discretization_
double search_discretization_
Definition: kinematics_base.h:596
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
Definition: kinematics_base.h:152
kinematics::KinematicsBase::group_name_
std::string group_name_
Definition: kinematics_base.h:588
kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
Definition: kinematics_base.h:90
kinematics::KinematicsBase::getLinkNames
virtual const std::vector< std::string > & getLinkNames() const =0
Return all the link names in the order they are represented internally.
kinematics::KinematicsBase::searchPositionIK
virtual 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 =0
Given a desired pose of the end-effector, search for the joint angles required to reach it....
kinematics::KinematicErrors::DISCRETIZATION_NOT_INITIALIZED
@ DISCRETIZATION_NOT_INITIALIZED
Definition: kinematics_base.h:91
kinematics::KinematicsBase::robot_description_
std::string robot_description_
Definition: kinematics_base.h:587
kinematics::KinematicErrors::OK
@ OK
Definition: kinematics_base.h:89
kinematics::KinematicsBase::~KinematicsBase
virtual ~KinematicsBase()
Virtual destructor for the interface.
kinematics::KinematicsBase::redundant_joint_indices_
std::vector< unsigned int > redundant_joint_indices_
Definition: kinematics_base.h:599
kinematics::DiscretizationMethods::DiscretizationMethod
DiscretizationMethod
Definition: kinematics_base.h:67
kinematics::KinematicsBase::KinematicsBase
KinematicsBase()
Definition: kinematics_base.cpp:180
kinematics::KinematicsBase::getTipFrames
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....
Definition: kinematics_base.h:453
kinematics::KinematicsBase
Provides an interface for kinematics solvers.
Definition: kinematics_base.h:144
kinematics::KinematicsBase::initialize
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Initialization function for the kinematics, for use with kinematic chain IK solvers.
Definition: kinematics_base.cpp:98
kinematics::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(KinematicsBase)
kinematics
API for forward and inverse kinematics.
Definition: kinematics_base.h:58
kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS
@ IK_SEED_OUTSIDE_LIMITS
Definition: kinematics_base.h:95
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
kinematics::KinematicsBase::removeSlash
std::string removeSlash(const std::string &str) const
Definition: kinematics_base.cpp:160
kinematics::KinematicsResult
Definition: kinematics_base.h:131
kinematics::KinematicsBase::setDefaultTimeout
void setDefaultTimeout(double timeout)
For functions that require a timeout specified but one is not specified using arguments,...
Definition: kinematics_base.h:566
kinematics::KinematicsBase::getJointNames
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
kinematics::KinematicsBase::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: kinematics_base.h:586
kinematics::KinematicsBase::supportsGroup
virtual bool supportsGroup(const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
Check if this solver supports a given JointModelGroup.
Definition: kinematics_base.cpp:165
kinematics::KinematicsQueryOptions::discretization_method
DiscretizationMethod discretization_method
Definition: kinematics_base.h:118
kinematics::KinematicsBase::setSearchDiscretization
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
Definition: kinematics_base.h:515
kinematics::KinematicErrors::EMPTY_TIP_POSES
@ EMPTY_TIP_POSES
Definition: kinematics_base.h:94
kinematics::KinematicsQueryOptions::lock_redundant_joints
bool lock_redundant_joints
Definition: kinematics_base.h:116
kinematics::KinematicsBase::default_timeout_
double default_timeout_
Definition: kinematics_base.h:598
kinematics::KinematicsBase::getSearchDiscretization
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
Definition: kinematics_base.h:543
kinematics::KinematicsBase::tip_frames_
std::vector< std::string > tip_frames_
Definition: kinematics_base.h:590
kinematics::KinematicsBase::getTipFrame
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...
Definition: kinematics_base.h:439
kinematics::DiscretizationMethods::NO_DISCRETIZATION
@ NO_DISCRETIZATION
Definition: kinematics_base.h:69
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
kinematics::KinematicsQueryOptions
A set of options for the kinematics solver.
Definition: kinematics_base.h:107
index
unsigned int index
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
param
T param(const std::string &param_name, const T &default_val)
kinematics::KinematicErrors::NO_SOLUTION
@ NO_SOLUTION
Definition: kinematics_base.h:97
kinematics::KinematicsBase::DEFAULT_TIMEOUT
static const double DEFAULT_TIMEOUT
Definition: kinematics_base.h:148
kinematics::KinematicsBase::getPositionIK
virtual 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 =0
Given a desired pose of the end-effector, compute the joint angles to reach it.
kinematics::KinematicsBase::getBaseFrame
virtual const std::string & getBaseFrame() const
Return the name of the frame in which the solver is operating. This is usually a link name....
Definition: kinematics_base.h:429
kinematics::KinematicsResult::kinematic_error
KinematicError kinematic_error
Definition: kinematics_base.h:133
kinematics::KinematicsBase::getRedundantJoints
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
Definition: kinematics_base.h:479
kinematics::KinematicsBase::base_frame_
std::string base_frame_
Definition: kinematics_base.h:589
ros::NodeHandle
kinematics::KinematicErrors::SOLVER_NOT_ACTIVE
@ SOLVER_NOT_ACTIVE
Definition: kinematics_base.h:96
kinematics::DiscretizationMethods::ALL_DISCRETIZED
@ ALL_DISCRETIZED
Definition: kinematics_base.h:70
kinematics::KinematicsBase::searchPositionIK
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=nullptr) const
Given a set of desired poses for a planning group with multiple end-effectors, search for the joint a...
Definition: kinematics_base.h:295
kinematics::KinematicsBase::tip_frame_
std::string tip_frame_
Definition: kinematics_base.h:595


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Oct 21 2020 03:28:04