Public Member Functions | Public Attributes | List of all members
cached_ik_kinematics_plugin::IKCache::Pose Struct Reference

class to represent end effector pose More...

#include <cached_ik_kinematics_plugin.h>

Public Member Functions

double distance (const Pose &pose) const
 
 Pose ()=default
 
 Pose (const geometry_msgs::Pose &pose)
 

Public Attributes

tf2::Quaternion orientation
 
tf2::Vector3 position
 

Detailed Description

class to represent end effector pose

tf2::Transform stores orientation as a matrix, so we define our own pose class that maps more directly to geometry_msgs::Pose and for which we can more easily define a distance metric.

Definition at line 74 of file cached_ik_kinematics_plugin.h.

Constructor & Destructor Documentation

cached_ik_kinematics_plugin::IKCache::Pose::Pose ( )
default
cached_ik_kinematics_plugin::IKCache::Pose::Pose ( const geometry_msgs::Pose &  pose)

Definition at line 274 of file ik_cache.cpp.

Member Function Documentation

double cached_ik_kinematics_plugin::IKCache::Pose::distance ( const Pose pose) const

compute the distance between this pose and another pose

Definition at line 282 of file ik_cache.cpp.

Member Data Documentation

tf2::Quaternion cached_ik_kinematics_plugin::IKCache::Pose::orientation

Definition at line 79 of file cached_ik_kinematics_plugin.h.

tf2::Vector3 cached_ik_kinematics_plugin::IKCache::Pose::position

Definition at line 78 of file cached_ik_kinematics_plugin.h.


The documentation for this struct 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