| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
class to represent end effector pose More...
#include <cached_ik_kinematics_plugin.h>
Public Member Functions | |
| Pose ()=default | |
| Pose (const geometry_msgs::msg::Pose &pose) | |
| double | distance (const Pose &pose) const | 
Public Attributes | |
| tf2::Vector3 | position | 
| tf2::Quaternion | orientation | 
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::msg::Pose and for which we can more easily define a distance metric.
Definition at line 86 of file cached_ik_kinematics_plugin.h.
      
  | 
  default | 
| cached_ik_kinematics_plugin::IKCache::Pose::Pose | ( | const geometry_msgs::msg::Pose & | pose | ) | 
Definition at line 274 of file ik_cache.cpp.
| 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.
| tf2::Quaternion cached_ik_kinematics_plugin::IKCache::Pose::orientation | 
Definition at line 91 of file cached_ik_kinematics_plugin.h.
| tf2::Vector3 cached_ik_kinematics_plugin::IKCache::Pose::position | 
Definition at line 90 of file cached_ik_kinematics_plugin.h.