#include <cached_ik_kinematics_plugin.h>
|
| IKCacheMap (const std::string &robot_description, const std::string &group_name, unsigned int num_joints) |
|
| ~IKCacheMap () |
|
const IKEntry & | getBestApproximateIKSolution (const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses) const |
|
void | updateCache (const IKEntry &nearest, const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses, const std::vector< double > &config) |
|
|
std::string | getKey (const std::vector< std::string > &fixed, const std::vector< std::string > &active) const |
|
a container of IK caches for cases where there is no fixed base frame
Definition at line 152 of file cached_ik_kinematics_plugin.h.
◆ IKEntry
◆ Pose
◆ IKCacheMap()
cached_ik_kinematics_plugin::IKCacheMap::IKCacheMap |
( |
const std::string & |
robot_description, |
|
|
const std::string & |
group_name, |
|
|
unsigned int |
num_joints |
|
) |
| |
◆ ~IKCacheMap()
cached_ik_kinematics_plugin::IKCacheMap::~IKCacheMap |
( |
| ) |
|
◆ getBestApproximateIKSolution()
const IKCache::IKEntry & cached_ik_kinematics_plugin::IKCacheMap::getBestApproximateIKSolution |
( |
const std::vector< std::string > & |
fixed, |
|
|
const std::vector< std::string > & |
active, |
|
|
const std::vector< Pose > & |
poses |
|
) |
| const |
get the entry from the IK cache that best matches a given vector of poses, with a specified set of fixed and active tip links
Definition at line 298 of file ik_cache.cpp.
◆ getKey()
std::string cached_ik_kinematics_plugin::IKCacheMap::getKey |
( |
const std::vector< std::string > & |
fixed, |
|
|
const std::vector< std::string > & |
active |
|
) |
| const |
|
protected |
◆ updateCache()
void cached_ik_kinematics_plugin::IKCacheMap::updateCache |
( |
const IKEntry & |
nearest, |
|
|
const std::vector< std::string > & |
fixed, |
|
|
const std::vector< std::string > & |
active, |
|
|
const std::vector< Pose > & |
poses, |
|
|
const std::vector< double > & |
config |
|
) |
| |
insert (pose,config) as an entry if it's different enough from the most similar cache entry
Definition at line 313 of file ik_cache.cpp.
◆ group_name_
std::string cached_ik_kinematics_plugin::IKCacheMap::group_name_ |
|
protected |
◆ num_joints_
unsigned int cached_ik_kinematics_plugin::IKCacheMap::num_joints_ |
|
protected |
◆ robot_description_
std::string cached_ik_kinematics_plugin::IKCacheMap::robot_description_ |
|
protected |
The documentation for this class was generated from the following files: