Class PickIKPlugin
Defined in File pick_ik_plugin.hpp
Inheritance Relationships
Base Type
public kinematics::KinematicsBase
Class Documentation
-
class PickIKPlugin : public kinematics::KinematicsBase
Public Functions
-
virtual bool searchPositionIK(std::vector<geometry_msgs::msg::Pose> const &ik_poses, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> const&, std::vector<double> &solution, IKCallbackFn const &solution_callback, IKCostFn const &cost_function, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions(), moveit::core::RobotState const *context_state = nullptr) const
-
virtual std::vector<std::string> const &getJointNames() const
-
virtual std::vector<std::string> const &getLinkNames() const
-
virtual bool getPositionFK(std::vector<std::string> const&, std::vector<double> const&, std::vector<geometry_msgs::msg::Pose>&) const
-
virtual bool getPositionIK(geometry_msgs::msg::Pose const&, std::vector<double> const&, std::vector<double>&, moveit_msgs::msg::MoveItErrorCodes&, kinematics::KinematicsQueryOptions const&) const
-
virtual bool searchPositionIK(geometry_msgs::msg::Pose const &ik_pose, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions()) const
-
virtual bool searchPositionIK(geometry_msgs::msg::Pose const &ik_pose, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> const &consistency_limits, std::vector<double> &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions()) const
-
virtual bool searchPositionIK(geometry_msgs::msg::Pose const &ik_pose, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> &solution, IKCallbackFn const &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions()) const
-
virtual bool searchPositionIK(geometry_msgs::msg::Pose const &ik_pose, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> const &consistency_limits, std::vector<double> &solution, IKCallbackFn const &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions()) const
-
virtual bool searchPositionIK(std::vector<geometry_msgs::msg::Pose> const &ik_poses, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> const &consistency_limits, std::vector<double> &solution, IKCallbackFn const &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions(), moveit::core::RobotState const *context_state = NULL) const
-
virtual bool searchPositionIK(std::vector<geometry_msgs::msg::Pose> const &ik_poses, std::vector<double> const &ik_seed_state, double timeout, std::vector<double> const&, std::vector<double> &solution, IKCallbackFn const &solution_callback, IKCostFn const &cost_function, moveit_msgs::msg::MoveItErrorCodes &error_code, kinematics::KinematicsQueryOptions const &options = kinematics::KinematicsQueryOptions(), moveit::core::RobotState const *context_state = nullptr) const