moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | 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]
Collaboration diagram for cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >:
Collaboration graph
[legend]

Public Types

using Pose = IKCache::Pose
 
using IKEntry = IKCache::IKEntry
 
using IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn
 
using KinematicsQueryOptions = kinematics::KinematicsQueryOptions
 

Public Member Functions

 CachedIKKinematicsPlugin ()
 
 ~CachedIKKinematicsPlugin () override
 
bool initialize (const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
 
bool getPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::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::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
 

Detailed Description

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

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

Definition at line 213 of file cached_ik_kinematics_plugin.h.

Member Typedef Documentation

◆ IKCallbackFn

Definition at line 218 of file cached_ik_kinematics_plugin.h.

◆ IKEntry

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

Definition at line 217 of file cached_ik_kinematics_plugin.h.

◆ KinematicsQueryOptions

Definition at line 219 of file cached_ik_kinematics_plugin.h.

◆ Pose

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

Definition at line 216 of file cached_ik_kinematics_plugin.h.

Constructor & Destructor Documentation

◆ CachedIKKinematicsPlugin()

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

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

◆ ~CachedIKKinematicsPlugin()

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

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

Member Function Documentation

◆ getPositionIK()

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::getPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const KinematicsQueryOptions options = KinematicsQueryOptions() 
) const
override

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

◆ initialize()

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::initialize ( const rclcpp::Node::SharedPtr &  node,
const moveit::core::RobotModel robot_model,
const std::string &  group_name,
const std::string &  base_frame,
const std::vector< std::string > &  tip_frames,
double  search_discretization 
)
inlineoverride

Definition at line 227 of file cached_ik_kinematics_plugin.h.

◆ searchPositionIK() [1/4]

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::searchPositionIK ( const geometry_msgs::msg::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::msg::MoveItErrorCodes &  error_code,
const KinematicsQueryOptions options = KinematicsQueryOptions() 
) const
override

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

◆ searchPositionIK() [2/4]

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const KinematicsQueryOptions options = KinematicsQueryOptions() 
) const
override

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

◆ searchPositionIK() [3/4]

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const KinematicsQueryOptions options = KinematicsQueryOptions() 
) const
override

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

◆ searchPositionIK() [4/4]

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const KinematicsQueryOptions options = KinematicsQueryOptions() 
) const
override

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


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