moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | List of all members
cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin > Class Template Reference

#include <cached_ik_kinematics_plugin.h>

Inheritance diagram for cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >:
Inheritance graph
[legend]
Collaboration diagram for cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >:
Collaboration graph
[legend]

Public Types

using Pose = IKCache::Pose
 
using IKEntry = IKCache::IKEntry
 
using IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn
 
using KinematicsQueryOptions = kinematics::KinematicsQueryOptions
 
- Public Types inherited from cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >
using Pose = IKCache::Pose
 
using IKEntry = IKCache::IKEntry
 
using IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn
 
using KinematicsQueryOptions = kinematics::KinematicsQueryOptions
 

Public Member Functions

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 searchPositionIK (const std::vector< geometry_msgs::msg::Pose > &ik_poses, 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 moveit::core::RobotState *context_state=nullptr) const override
 
- Public Member Functions inherited from cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >
 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::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >

Caching wrapper for IK solvers that implement the multi-tip API.

Most solvers don't implement this, so the CachedIKKinematicsPlugin base class simply doesn't wrap the relevant methods and the implementation in the abstract base class will be called. Ideally, the two cache wrapper classes would be combined, but it's tricky to call a method in kinematics::KinematicsBase or KinematicsPlugin depending on whether KinematicsPlugin has overridden that method or not (although it can be done with some template meta-programming).

Definition at line 337 of file cached_ik_kinematics_plugin.h.

Member Typedef Documentation

◆ IKCallbackFn

Definition at line 342 of file cached_ik_kinematics_plugin.h.

◆ IKEntry

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

Definition at line 341 of file cached_ik_kinematics_plugin.h.

◆ KinematicsQueryOptions

Definition at line 343 of file cached_ik_kinematics_plugin.h.

◆ Pose

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

Definition at line 340 of file cached_ik_kinematics_plugin.h.

Member Function Documentation

◆ initialize()

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< 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 
)
override

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

Here is the call graph for this function:

◆ searchPositionIK()

template<class KinematicsPlugin >
bool cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >::searchPositionIK ( const std::vector< geometry_msgs::msg::Pose > &  ik_poses,
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 moveit::core::RobotState context_state = nullptr 
) const
override

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


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