161class IKCacheMap : 
public std::unordered_map<std::string, IKCache*>
 
  167  IKCacheMap(
const std::string& robot_description, 
const std::string& group_name, 
unsigned int num_joints);
 
  174                                              const std::vector<std::string>& active,
 
  175                                              const std::vector<Pose>& poses) 
const;
 
  181                   const std::vector<std::string>& active, 
const std::vector<Pose>& poses,
 
  182                   const std::vector<double>& config);
 
  185  std::string 
getKey(
const std::vector<std::string>& fixed, 
const std::vector<std::string>& active) 
const;
 
 
  200struct HasRobotModelApi<KinematicsPlugin, decltype(std::declval<KinematicsPlugin&>().initialize(
 
  201                                              std::declval<const rclcpp::Node::SharedPtr&>(),
 
  202                                              std::declval<const moveit::core::RobotModel&>(), std::string(),
 
  203                                              std::string(), std::vector<std::string>(), 0.0))> : std::true_type
 
 
  237                  const std::string& group_name, 
const std::string& base_frame,
 
  238                  const std::vector<std::string>& tip_frames, 
double search_discretization)
 override 
  242    std::string kinematics_param_prefix = 
"robot_description_kinematics." + group_name;
 
  243    param_listener_ = std::make_shared<cached_ik_kinematics::ParamListener>(node, kinematics_param_prefix);
 
  244    params_ = param_listener_->get_params();
 
  246    return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
 
 
  249  bool getPositionIK(
const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state,
 
  250                     std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  253  bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state,
 
  254                        double timeout, std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  257  bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state,
 
  258                        double timeout, 
const std::vector<double>& consistency_limits, std::vector<double>& solution,
 
  259                        moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  262  bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state,
 
  263                        double timeout, std::vector<double>& solution, 
const IKCallbackFn& solution_callback,
 
  264                        moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  267  bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, 
const std::vector<double>& ik_seed_state,
 
  268                        double timeout, 
const std::vector<double>& consistency_limits, std::vector<double>& solution,
 
  269                        const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  273  rclcpp::Node::SharedPtr node_;
 
  274  std::shared_ptr<cached_ik_kinematics::ParamListener> param_listener_;
 
  275  cached_ik_kinematics::Params params_;
 
  279  void initCache(
const std::string& robot_id, 
const std::string& group_name, 
const std::string& cache_name);
 
  284  template <
class T = KinematicsPlugin>
 
  285  typename std::enable_if<HasRobotModelApi<T>::value, 
bool>::type
 
  287                 const std::string& group_name, 
const std::string& base_frame,
 
  288                 const std::vector<std::string>& tip_frames, 
double search_discretization)
 
  290    if (tip_frames.size() != 1)
 
  293                   "This solver does not support multiple tip frames");
 
  298    if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
 
  300    initCache(robot_model.
getName(), group_name, base_frame + tip_frames[0]);
 
  304  template <
class T = KinematicsPlugin>
 
  305  typename std::enable_if<!HasRobotModelApi<T>::value, 
bool>::type
 
  307                 const std::string& , 
const std::string& ,
 
  308                 const std::vector<std::string>& , 
double )
 
  313  template <
class T = KinematicsPlugin>
 
  314  typename std::enable_if<HasRobotDescApi<T>::value, 
bool>::type
 
  315  initializeImpl(
const std::string& robot_description, 
const std::string& group_name, 
const std::string& base_frame,
 
  316                 const std::string& tip_frame, 
double search_discretization)
 
  319    if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
 
  321    initCache(robot_description, group_name, base_frame + tip_frame);
 
  325  template <
class T = KinematicsPlugin>
 
  326  typename std::enable_if<!HasRobotDescApi<T>::value, 
bool>::type
 
  327  initializeImpl(
const std::string& , 
const std::string& , 
const std::string& ,
 
  328                 const std::string& , 
double )
 
 
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