#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 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 |
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, 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 |
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, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override |
~CachedIKKinematicsPlugin () override | |
Private Member Functions | |
void | initCache (const std::string &robot_id, const std::string &group_name, const std::string &cache_name) |
template<class T = KinematicsPlugin> | |
std::enable_if<!HasRobotModelApi< T >::value, bool >::type | initializeImpl (const moveit::core::RobotModel &, const std::string &, const std::string &, const std::vector< std::string > &, double) |
template<class T = KinematicsPlugin> | |
std::enable_if< HasRobotModelApi< T >::value, bool >::type | initializeImpl (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) |
template<class T = KinematicsPlugin> | |
std::enable_if<!HasRobotDescApi< T >::value, bool >::type | initializeImpl (const std::string &, const std::string &, const std::string &, const std::string &, double) |
template<class T = KinematicsPlugin> | |
std::enable_if< HasRobotDescApi< T >::value, bool >::type | initializeImpl (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization) |
Private Attributes | |
IKCache | cache_ |
Caching wrapper for kinematics::KinematicsBase-derived IK solvers.
Definition at line 241 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn |
Definition at line 246 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKEntry = IKCache::IKEntry |
Definition at line 245 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::KinematicsQueryOptions = kinematics::KinematicsQueryOptions |
Definition at line 247 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::Pose = IKCache::Pose |
Definition at line 244 of file cached_ik_kinematics_plugin.h.
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::CachedIKKinematicsPlugin |
Definition at line 75 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 80 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 141 of file cached_ik_kinematics_plugin-inl.h.
|
private |
Definition at line 85 of file cached_ik_kinematics_plugin-inl.h.
|
inlineoverride |
Definition at line 255 of file cached_ik_kinematics_plugin.h.
|
inlineoverride |
Definition at line 262 of file cached_ik_kinematics_plugin.h.
|
inlineprivate |
Definition at line 320 of file cached_ik_kinematics_plugin.h.
|
inlineprivate |
Definition at line 301 of file cached_ik_kinematics_plugin.h.
|
inlineprivate |
Definition at line 340 of file cached_ik_kinematics_plugin.h.
|
inlineprivate |
Definition at line 328 of file cached_ik_kinematics_plugin.h.
|
override |
Definition at line 226 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 180 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 202 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 157 of file cached_ik_kinematics_plugin-inl.h.
|
private |
Definition at line 292 of file cached_ik_kinematics_plugin.h.