#include <cached_ik_kinematics_plugin.h>
Public Types | |
using | IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn |
using | IKEntry = IKCache::IKEntry |
using | KinematicsQueryOptions = kinematics::KinematicsQueryOptions |
using | Pose = IKCache::Pose |
Public Member Functions | |
CachedIKKinematicsPlugin () | |
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 KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
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) override |
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 KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, 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 KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
~CachedIKKinematicsPlugin () | |
Protected Attributes | |
IKCache | cache_ |
Caching wrapper for kinematics::KinematicsBase-derived IK solvers.
Definition at line 181 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn |
Definition at line 186 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKEntry = IKCache::IKEntry |
Definition at line 185 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::KinematicsQueryOptions = kinematics::KinematicsQueryOptions |
Definition at line 187 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::Pose = IKCache::Pose |
Definition at line 184 of file cached_ik_kinematics_plugin.h.
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::CachedIKKinematicsPlugin | ( | ) |
Definition at line 43 of file cached_ik_kinematics_plugin-inl.h.
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::~CachedIKKinematicsPlugin | ( | ) |
Definition at line 48 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 106 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 53 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 122 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 145 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 167 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 191 of file cached_ik_kinematics_plugin-inl.h.
|
protected |
Definition at line 222 of file cached_ik_kinematics_plugin.h.