Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cached_ik_kinematics_plugin::IKCache Class Reference

A cache of inverse kinematic solutions. More...

#include <cached_ik_kinematics_plugin.h>

Classes

struct  Options
 
struct  Pose
 class to represent end effector pose More...
 

Public Types

using IKEntry = std::pair< std::vector< Pose >, std::vector< double > >
 

Public Member Functions

const IKEntrygetBestApproximateIKSolution (const Pose &pose) const
 
const IKEntrygetBestApproximateIKSolution (const std::vector< Pose > &poses) const
 
 IKCache ()
 
 IKCache (const IKCache &)=delete
 
void initializeCache (const std::string &robot_id, const std::string &group_name, const std::string &cache_name, const unsigned int num_joints, const Options &opts=Options())
 
void updateCache (const IKEntry &nearest, const Pose &pose, const std::vector< double > &config) const
 
void updateCache (const IKEntry &nearest, const std::vector< Pose > &poses, const std::vector< double > &config) const
 
void verifyCache (kdl_kinematics_plugin::KDLKinematicsPlugin &fk) const
 
 ~IKCache ()
 

Protected Member Functions

double configDistance2 (const std::vector< double > &config1, const std::vector< double > &config2) const
 
void saveCache () const
 

Protected Attributes

boost::filesystem::path cache_file_name_
 
std::vector< IKEntryik_cache_
 
NearestNeighborsGNAT< IKEntry * > ik_nn_
 
unsigned int last_saved_cache_size_ { 0 }
 
std::mutex lock_
 
unsigned int max_cache_size_
 
double min_config_distance2_
 
double min_pose_distance_
 
unsigned int num_joints_
 

Detailed Description

A cache of inverse kinematic solutions.

Definition at line 85 of file cached_ik_kinematics_plugin.h.

Member Typedef Documentation

◆ IKEntry

using cached_ik_kinematics_plugin::IKCache::IKEntry = std::pair<std::vector<Pose>, std::vector<double> >

the IK cache entries are simply a pair formed by a vector of poses (one for each end effector) and a configuration that achieves those poses

Definition at line 153 of file cached_ik_kinematics_plugin.h.

Constructor & Destructor Documentation

◆ IKCache() [1/2]

cached_ik_kinematics_plugin::IKCache::IKCache ( )

Definition at line 76 of file ik_cache.cpp.

◆ ~IKCache()

cached_ik_kinematics_plugin::IKCache::~IKCache ( )

Definition at line 87 of file ik_cache.cpp.

◆ IKCache() [2/2]

cached_ik_kinematics_plugin::IKCache::IKCache ( const IKCache )
delete

Member Function Documentation

◆ configDistance2()

double cached_ik_kinematics_plugin::IKCache::configDistance2 ( const std::vector< double > &  config1,
const std::vector< double > &  config2 
) const
protected

compute the distance between two joint configurations

Definition at line 170 of file ik_cache.cpp.

◆ getBestApproximateIKSolution() [1/2]

const IKCache::IKEntry & cached_ik_kinematics_plugin::IKCache::getBestApproximateIKSolution ( const Pose pose) const

get the entry from the IK cache that best matches a given pose

Definition at line 181 of file ik_cache.cpp.

◆ getBestApproximateIKSolution() [2/2]

const IKCache::IKEntry & cached_ik_kinematics_plugin::IKCache::getBestApproximateIKSolution ( const std::vector< Pose > &  poses) const

get the entry from the IK cache that best matches a given vector of poses

Definition at line 192 of file ik_cache.cpp.

◆ initializeCache()

void cached_ik_kinematics_plugin::IKCache::initializeCache ( const std::string &  robot_id,
const std::string &  group_name,
const std::string &  cache_name,
const unsigned int  num_joints,
const Options opts = Options() 
)

initialize cache, read from disk if found

Definition at line 93 of file ik_cache.cpp.

◆ saveCache()

void cached_ik_kinematics_plugin::IKCache::saveCache ( ) const
protected

save current state of cache to disk

Definition at line 246 of file ik_cache.cpp.

◆ updateCache() [1/2]

void cached_ik_kinematics_plugin::IKCache::updateCache ( const IKEntry nearest,
const Pose pose,
const std::vector< double > &  config 
) const

insert (pose,config) as an entry if it's different enough from the most similar cache entry

Definition at line 203 of file ik_cache.cpp.

◆ updateCache() [2/2]

void cached_ik_kinematics_plugin::IKCache::updateCache ( const IKEntry nearest,
const std::vector< Pose > &  poses,
const std::vector< double > &  config 
) const

insert (pose,config) as an entry if it's different enough from the most similar cache entry

Definition at line 216 of file ik_cache.cpp.

◆ verifyCache()

void cached_ik_kinematics_plugin::IKCache::verifyCache ( kdl_kinematics_plugin::KDLKinematicsPlugin fk) const

verify with forward kinematics that the cache entries are correct

Definition at line 282 of file ik_cache.cpp.

Member Data Documentation

◆ cache_file_name_

boost::filesystem::path cached_ik_kinematics_plugin::IKCache::cache_file_name_
protected

file name for loading / saving cache

Definition at line 195 of file cached_ik_kinematics_plugin.h.

◆ ik_cache_

std::vector<IKEntry> cached_ik_kinematics_plugin::IKCache::ik_cache_
mutableprotected

the IK methods are declared const in the base class, but the wrapped methods need to modify the cache, so the next four members are mutable cache of IK solutions

Definition at line 203 of file cached_ik_kinematics_plugin.h.

◆ ik_nn_

NearestNeighborsGNAT<IKEntry*> cached_ik_kinematics_plugin::IKCache::ik_nn_
mutableprotected

nearest neighbor data structure over IK cache entries

Definition at line 205 of file cached_ik_kinematics_plugin.h.

◆ last_saved_cache_size_

unsigned int cached_ik_kinematics_plugin::IKCache::last_saved_cache_size_ { 0 }
mutableprotected

size of the cache when it was last saved

Definition at line 207 of file cached_ik_kinematics_plugin.h.

◆ lock_

std::mutex cached_ik_kinematics_plugin::IKCache::lock_
mutableprotected

mutex for changing IK cache

Definition at line 209 of file cached_ik_kinematics_plugin.h.

◆ max_cache_size_

unsigned int cached_ik_kinematics_plugin::IKCache::max_cache_size_
protected

maximum size of the cache

Definition at line 193 of file cached_ik_kinematics_plugin.h.

◆ min_config_distance2_

double cached_ik_kinematics_plugin::IKCache::min_config_distance2_
protected

... or the configurations are at least minConfigDistance2_^.5 apart.

Definition at line 191 of file cached_ik_kinematics_plugin.h.

◆ min_pose_distance_

double cached_ik_kinematics_plugin::IKCache::min_pose_distance_
protected

for all cache entries, the poses are at least minPoseDistance_ apart ...

Definition at line 189 of file cached_ik_kinematics_plugin.h.

◆ num_joints_

unsigned int cached_ik_kinematics_plugin::IKCache::num_joints_
protected

number of joints in the system

Definition at line 186 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 Fri May 3 2024 02:29:33