moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <cached_ik_kinematics_plugin.hpp>
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 |
Caching wrapper for kinematics::KinematicsBase-derived IK solvers.
Definition at line 222 of file cached_ik_kinematics_plugin.hpp.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKCallbackFn = kinematics::KinematicsBase::IKCallbackFn |
Definition at line 227 of file cached_ik_kinematics_plugin.hpp.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::IKEntry = IKCache::IKEntry |
Definition at line 226 of file cached_ik_kinematics_plugin.hpp.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::KinematicsQueryOptions = kinematics::KinematicsQueryOptions |
Definition at line 228 of file cached_ik_kinematics_plugin.hpp.
using cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::Pose = IKCache::Pose |
Definition at line 225 of file cached_ik_kinematics_plugin.hpp.
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< KinematicsPlugin >::CachedIKKinematicsPlugin | ( | ) |
Definition at line 45 of file cached_ik_kinematics_plugin-inl.hpp.
|
override |
Definition at line 50 of file cached_ik_kinematics_plugin-inl.hpp.
|
override |
Definition at line 89 of file cached_ik_kinematics_plugin-inl.hpp.
|
inlineoverride |
Definition at line 236 of file cached_ik_kinematics_plugin.hpp.
|
override |
Definition at line 174 of file cached_ik_kinematics_plugin-inl.hpp.
|
override |
Definition at line 128 of file cached_ik_kinematics_plugin-inl.hpp.
|
override |
Definition at line 150 of file cached_ik_kinematics_plugin-inl.hpp.
|
override |
Definition at line 105 of file cached_ik_kinematics_plugin-inl.hpp.