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 #include <moveit/moveit_kinematics_base_export.h>
48 
49 namespace moveit
50 {
51 namespace core
52 {
53 MOVEIT_CLASS_FORWARD(JointModelGroup);
54 MOVEIT_CLASS_FORWARD(RobotState);
55 MOVEIT_CLASS_FORWARD(RobotModel);
56 } // namespace core
57 } // namespace moveit
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 } // namespace DiscretizationMethods
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 } // namespace KinematicErrors
104 
110 {
112  : lock_redundant_joints(false)
114  , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
115  {
116  }
117 
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 {
138 };
139 
140 MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, WeakPtr... etc
141 
146 {
147 public:
148  static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */
149  static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_TIMEOUT; /* = 1.0 */
150 
152  using IKCallbackFn =
153  boost::function<void(const geometry_msgs::Pose&, const std::vector<double>&, moveit_msgs::MoveItErrorCodes&)>;
154 
167  virtual bool
168  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
169  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
171 
193  virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
194  std::vector<std::vector<double> >& solutions, KinematicsResult& result,
195  const kinematics::KinematicsQueryOptions& options) const;
196 
209  virtual bool
210  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
211  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
213 
228  virtual bool
229  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
230  const std::vector<double>& consistency_limits, std::vector<double>& solution,
231  moveit_msgs::MoveItErrorCodes& error_code,
233 
247  virtual bool
248  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
249  std::vector<double>& solution, const IKCallbackFn& solution_callback,
250  moveit_msgs::MoveItErrorCodes& error_code,
252 
268  virtual bool
269  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
270  const std::vector<double>& consistency_limits, std::vector<double>& solution,
271  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
273 
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 = nullptr) const
301  {
302  (void)context_state;
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 = nullptr) const;
512 
516  void setSearchDiscretization(double sd)
517  {
519  for (unsigned int index : redundant_joint_indices_)
521  }
522 
530  void setSearchDiscretization(const std::map<int, double>& discretization)
531  {
533  redundant_joint_indices_.clear();
534  for (const auto& pair : discretization)
535  {
536  redundant_joint_discretization_.insert(pair);
537  redundant_joint_indices_.push_back(pair.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 } // 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:83
node_handle.h
kinematics::DiscretizationMethods::SOME_DISCRETIZED
@ SOME_DISCRETIZED
Definition: kinematics_base.h:73
kinematics::KinematicsQueryOptions::return_approximate_solution
bool return_approximate_solution
Definition: kinematics_base.h:119
kinematics::KinematicsBase::supported_methods_
std::vector< DiscretizationMethod > supported_methods_
Definition: kinematics_base.h:602
kinematics::DiscretizationMethods::SOME_RANDOM_SAMPLED
@ SOME_RANDOM_SAMPLED
Definition: kinematics_base.h:77
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:618
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:574
kinematics::KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION
Definition: kinematics_base.h:148
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:530
kinematics::KinematicsQueryOptions::KinematicsQueryOptions
KinematicsQueryOptions()
Definition: kinematics_base.h:111
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:560
kinematics::KinematicsResult::solution_percentage
double solution_percentage
Definition: kinematics_base.h:136
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:143
kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED
@ MULTIPLE_TIPS_NOT_SUPPORTED
Definition: kinematics_base.h:95
kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED
@ ALL_RANDOM_SAMPLED
Definition: kinematics_base.h:76
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:420
kinematics::KinematicsBase::redundant_joint_discretization_
std::map< int, double > redundant_joint_discretization_
Definition: kinematics_base.h:601
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:89
kinematics::KinematicsBase::search_discretization_
double search_discretization_
Definition: kinematics_base.h:597
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:153
kinematics::KinematicsBase::group_name_
std::string group_name_
Definition: kinematics_base.h:589
kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
Definition: kinematics_base.h:92
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:93
kinematics::KinematicsBase::robot_description_
std::string robot_description_
Definition: kinematics_base.h:588
kinematics::KinematicErrors::OK
@ OK
Definition: kinematics_base.h:91
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:600
kinematics::DiscretizationMethods::DiscretizationMethod
DiscretizationMethod
Definition: kinematics_base.h:69
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:454
kinematics::KinematicsBase
Provides an interface for kinematics solvers.
Definition: kinematics_base.h:145
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:60
kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS
@ IK_SEED_OUTSIDE_LIMITS
Definition: kinematics_base.h:97
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:133
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:567
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:587
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:120
kinematics::KinematicsBase::setSearchDiscretization
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
Definition: kinematics_base.h:516
kinematics::KinematicErrors::EMPTY_TIP_POSES
@ EMPTY_TIP_POSES
Definition: kinematics_base.h:96
kinematics::KinematicsQueryOptions::lock_redundant_joints
bool lock_redundant_joints
Definition: kinematics_base.h:118
kinematics::KinematicsBase::default_timeout_
double default_timeout_
Definition: kinematics_base.h:599
kinematics::KinematicsBase::getSearchDiscretization
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
Definition: kinematics_base.h:544
kinematics::KinematicsBase::tip_frames_
std::vector< std::string > tip_frames_
Definition: kinematics_base.h:591
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:440
kinematics::DiscretizationMethods::NO_DISCRETIZATION
@ NO_DISCRETIZATION
Definition: kinematics_base.h:71
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
kinematics::KinematicsQueryOptions
A set of options for the kinematics solver.
Definition: kinematics_base.h:109
moveit::core::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(JointModelGroup)
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:99
kinematics::KinematicsBase::DEFAULT_TIMEOUT
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_TIMEOUT
Definition: kinematics_base.h:149
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:430
kinematics::KinematicsResult::kinematic_error
KinematicError kinematic_error
Definition: kinematics_base.h:135
kinematics::KinematicsBase::getRedundantJoints
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
Definition: kinematics_base.h:480
kinematics::KinematicsBase::base_frame_
std::string base_frame_
Definition: kinematics_base.h:590
ros::NodeHandle
kinematics::KinematicErrors::SOLVER_NOT_ACTIVE
@ SOLVER_NOT_ACTIVE
Definition: kinematics_base.h:98
kinematics::DiscretizationMethods::ALL_DISCRETIZED
@ ALL_DISCRETIZED
Definition: kinematics_base.h:72
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:296
kinematics::KinematicsBase::tip_frame_
std::string tip_frame_
Definition: kinematics_base.h:596


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:35