Public Types | Public Member Functions | Protected Attributes | List of all members
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin > Class Template Reference

#include <cached_ik_kinematics_plugin.h>

Inheritance diagram for cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >:
Inheritance graph
[legend]

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_
 

Detailed Description

template<class KinematicsPlugin>
class cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >

Caching wrapper for kinematics::KinematicsBase-derived IK solvers.

Definition at line 181 of file cached_ik_kinematics_plugin.h.

Member Typedef Documentation

Definition at line 186 of file cached_ik_kinematics_plugin.h.

template<class KinematicsPlugin >
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKEntry = IKCache::IKEntry

Definition at line 185 of file cached_ik_kinematics_plugin.h.

Definition at line 187 of file cached_ik_kinematics_plugin.h.

template<class KinematicsPlugin >
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::Pose = IKCache::Pose

Definition at line 184 of file cached_ik_kinematics_plugin.h.

Constructor & Destructor Documentation

template<class KinematicsPlugin >
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::CachedIKKinematicsPlugin ( )

Definition at line 43 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::~CachedIKKinematicsPlugin ( )

Definition at line 48 of file cached_ik_kinematics_plugin-inl.h.

Member Function Documentation

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 106 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 53 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 122 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 145 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 167 of file cached_ik_kinematics_plugin-inl.h.

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::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

Definition at line 191 of file cached_ik_kinematics_plugin-inl.h.

Member Data Documentation

template<class KinematicsPlugin >
IKCache cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::cache_
protected

Definition at line 222 of file cached_ik_kinematics_plugin.h.


The documentation for this class was generated from the following files:


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:53