44template <
class KinematicsPlugin>
 
   49template <
class KinematicsPlugin>
 
   54template <
class KinematicsPlugin>
 
   56                                                           const std::string& cache_name)
 
   64  cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
 
   72template <
class KinematicsPlugin>
 
   75    const std::string& base_frame, 
const std::vector<std::string>& tip_frames, 
double search_discretization)
 
   78  if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
 
   81  std::string cache_name = base_frame;
 
   82  std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
 
   84                                                                     KinematicsPlugin::getJointNames().size());
 
 
   88template <
class KinematicsPlugin>
 
   90                                                               const std::vector<double>& ik_seed_state,
 
   91                                                               std::vector<double>& solution,
 
   92                                                               moveit_msgs::msg::MoveItErrorCodes& error_code,
 
   96  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
 
   97  bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
 
   98                        KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
 
  100    cache_.updateCache(nearest, pose, solution);
 
  101  return solution_found;
 
 
  104template <
class KinematicsPlugin>
 
  106                                                                  const std::vector<double>& ik_seed_state,
 
  107                                                                  double timeout, std::vector<double>& solution,
 
  108                                                                  moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  111  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
 
  113  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
 
  114  bool solution_found =
 
  115      KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
 
  118    std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
 
  120        KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code, options);
 
  123    cache_.updateCache(nearest, pose, solution);
 
  124  return solution_found;
 
 
  127template <
class KinematicsPlugin>
 
  129    const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state, 
double timeout,
 
  130    const std::vector<double>& consistency_limits, std::vector<double>& solution,
 
  133  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
 
  135  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
 
  136  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
 
  137                                                           solution, error_code, options);
 
  140    std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
 
  141    solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
 
  142                                                        solution, error_code, options);
 
  145    cache_.updateCache(nearest, pose, solution);
 
  146  return solution_found;
 
 
  149template <
class KinematicsPlugin>
 
  151                                                                  const std::vector<double>& ik_seed_state,
 
  152                                                                  double timeout, std::vector<double>& solution,
 
  154                                                                  moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  157  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
 
  159  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
 
  160  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
 
  161                                                           solution_callback, error_code, options);
 
  164    std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
 
  165    solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
 
  166                                                        solution_callback, error_code, options);
 
  169    cache_.updateCache(nearest, pose, solution);
 
  170  return solution_found;
 
 
  173template <
class KinematicsPlugin>
 
  175    const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state, 
double timeout,
 
  176    const std::vector<double>& consistency_limits, std::vector<double>& solution, 
const IKCallbackFn& solution_callback,
 
  179  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
 
  181  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
 
  182  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
 
  183                                                           solution, solution_callback, error_code, options);
 
  186    std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
 
  187    solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
 
  188                                                        solution, solution_callback, error_code, options);
 
  191    cache_.updateCache(nearest, pose, solution);
 
  192  return solution_found;
 
 
  195template <
class KinematicsPlugin>
 
  197    const std::vector<geometry_msgs::msg::Pose>& ik_poses, 
const std::vector<double>& ik_seed_state, 
double timeout,
 
  198    const std::vector<double>& consistency_limits, std::vector<double>& solution, 
const IKCallbackFn& solution_callback,
 
  202  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
 
  203  std::vector<Pose> poses(ik_poses.size());
 
  204  for (
unsigned int i = 0; i < poses.size(); ++i)
 
  205    poses[i] = 
Pose(ik_poses[i]);
 
  207  bool solution_found =
 
  208      KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
 
  209                                         solution_callback, error_code, options, context_state);
 
  212    std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
 
  214        KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
 
  215                                           solution_callback, error_code, options, context_state);
 
  220  return solution_found;
 
 
 
~CachedIKKinematicsPlugin() override
 
CachedIKKinematicsPlugin()
 
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
kinematics::KinematicsBase::IKCallbackFn IKCallbackFn
 
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
bool searchPositionIK(const std::vector< geometry_msgs::msg::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::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const override
 
bool initialize(const rclcpp::Node::SharedPtr &node, 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) override
 
kinematics::KinematicsBase::IKCallbackFn IKCallbackFn
 
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
 
const std::string & getName() const
Get the model name.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
double min_joint_config_distance
 
std::string cached_ik_path
 
unsigned int max_cache_size
 
class to represent end effector pose
 
A set of options for the kinematics solver.