Class CRXKinematicsPlugin
Defined in File crx_kinematics_plugin.hpp
Inheritance Relationships
Base Type
public kinematics::KinematicsBase
Class Documentation
-
class CRXKinematicsPlugin : public kinematics::KinematicsBase
Public Functions
-
bool DoIK(const geometry_msgs::msg::Pose &ik_pose, std::vector<double> &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const std::vector<double> &reference_joint_values, const IKCallbackFn &solution_callback = IKCallbackFn()) const
-
virtual 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 kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual 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 kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual 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 kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual 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 kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual 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 kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual bool getPositionFK(const std::vector<std::string> &link_names, const std::vector<double> &joint_angles, std::vector<geometry_msgs::msg::Pose> &poses) const final override
-
virtual bool getPositionIK(const std::vector<geometry_msgs::msg::Pose> &ik_poses, const std::vector<double> &ik_seed_state, std::vector<std::vector<double>> &solutions, kinematics::KinematicsResult &result, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const final override
-
virtual const std::vector<std::string> &getJointNames() const final override
-
virtual const std::vector<std::string> &getLinkNames() const final override
-
bool DoIK(const geometry_msgs::msg::Pose &ik_pose, std::vector<double> &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const std::vector<double> &reference_joint_values, const IKCallbackFn &solution_callback = IKCallbackFn()) const