moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <cached_ik_kinematics_plugin.h>
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 |
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.
using cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >::IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn |
Definition at line 342 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >::IKEntry = IKCache::IKEntry |
Definition at line 341 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >::KinematicsQueryOptions = kinematics::KinematicsQueryOptions |
Definition at line 343 of file cached_ik_kinematics_plugin.h.
using cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin< KinematicsPlugin >::Pose = IKCache::Pose |
Definition at line 340 of file cached_ik_kinematics_plugin.h.
|
override |
Definition at line 71 of file cached_ik_kinematics_plugin-inl.h.
|
override |
Definition at line 194 of file cached_ik_kinematics_plugin-inl.h.