#include <moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.hpp>
#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.hpp>
#include <moveit/kinematics_base/kinematics_base.hpp>
#include <moveit/robot_model/robot_model.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>
#include <mutex>
#include <unordered_map>
#include <utility>
#include <filesystem>
#include <moveit/utils/logger.hpp>
#include <moveit_kinematics/cached_ik_kinematics_parameters.hpp>
#include "cached_ik_kinematics_plugin-inl.hpp"
 
Go to the source code of this file.
 | 
| class   | cached_ik_kinematics_plugin::IKCache | 
|   | A cache of inverse kinematic solutions.  More...
  | 
|   | 
| struct   | cached_ik_kinematics_plugin::IKCache::Options | 
|   | 
| struct   | cached_ik_kinematics_plugin::IKCache::Pose | 
|   | class to represent end effector pose  More...
  | 
|   | 
| class   | cached_ik_kinematics_plugin::IKCacheMap | 
|   | 
| struct   | cached_ik_kinematics_plugin::HasRobotModelApi< KinematicsPlugin, typename > | 
|   | 
| struct   | cached_ik_kinematics_plugin::HasRobotModelApi< KinematicsPlugin, decltype(std::declval< KinematicsPlugin & >().initialize(std::declval< const rclcpp::Node::SharedPtr & >(), std::declval< const moveit::core::RobotModel & >(), std::string(), std::string(), std::vector< std::string >(), 0.0))> | 
|   | 
| struct   | cached_ik_kinematics_plugin::HasRobotDescApi< KinematicsPlugin, typename > | 
|   | 
| struct   | cached_ik_kinematics_plugin::HasRobotDescApi< KinematicsPlugin, decltype(std::declval< KinematicsPlugin & >().KinematicsPlugin::initialize(std::string(), std::string(), std::string(), std::vector< std::string >(), 0.0))> | 
|   | 
| class   | cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin > | 
|   | 
| class   | cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin > | 
|   |