|
| 1 | +#pragma once |
| 2 | + |
| 3 | +#include <pick_ik/robot.hpp> |
| 4 | + |
| 5 | +#include <moveit/kinematics_base/kinematics_base.h> |
| 6 | + |
| 7 | +namespace pick_ik { |
| 8 | + |
| 9 | +class ParamListener; |
| 10 | + |
| 11 | +class PickIKPlugin : public kinematics::KinematicsBase { |
| 12 | + rclcpp::Node::SharedPtr node_; |
| 13 | + std::shared_ptr<ParamListener> parameter_listener_; |
| 14 | + moveit::core::JointModelGroup const* jmg_; |
| 15 | + |
| 16 | + std::vector<std::string> joint_names_; |
| 17 | + std::vector<std::string> link_names_; |
| 18 | + std::vector<size_t> tip_link_indices_; |
| 19 | + Robot robot_; |
| 20 | + |
| 21 | + mutable std::mutex fk_mutex_; |
| 22 | + |
| 23 | + public: |
| 24 | + virtual bool initialize(rclcpp::Node::SharedPtr const& node, |
| 25 | + moveit::core::RobotModel const& robot_model, |
| 26 | + std::string const& group_name, |
| 27 | + std::string const& base_frame, |
| 28 | + std::vector<std::string> const& tip_frames, |
| 29 | + double search_discretization); |
| 30 | + |
| 31 | + virtual bool searchPositionIK( |
| 32 | + std::vector<geometry_msgs::msg::Pose> const& ik_poses, |
| 33 | + std::vector<double> const& ik_seed_state, |
| 34 | + double timeout, |
| 35 | + std::vector<double> const&, |
| 36 | + std::vector<double>& solution, |
| 37 | + IKCallbackFn const& solution_callback, |
| 38 | + IKCostFn const& cost_function, |
| 39 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 40 | + kinematics::KinematicsQueryOptions const& options = kinematics::KinematicsQueryOptions(), |
| 41 | + moveit::core::RobotState const* context_state = nullptr) const; |
| 42 | + |
| 43 | + virtual std::vector<std::string> const& getJointNames() const; |
| 44 | + |
| 45 | + virtual std::vector<std::string> const& getLinkNames() const; |
| 46 | + |
| 47 | + virtual bool getPositionFK(std::vector<std::string> const&, |
| 48 | + std::vector<double> const&, |
| 49 | + std::vector<geometry_msgs::msg::Pose>&) const; |
| 50 | + |
| 51 | + virtual bool getPositionIK(geometry_msgs::msg::Pose const&, |
| 52 | + std::vector<double> const&, |
| 53 | + std::vector<double>&, |
| 54 | + moveit_msgs::msg::MoveItErrorCodes&, |
| 55 | + kinematics::KinematicsQueryOptions const&) const; |
| 56 | + |
| 57 | + virtual bool searchPositionIK(geometry_msgs::msg::Pose const& ik_pose, |
| 58 | + std::vector<double> const& ik_seed_state, |
| 59 | + double timeout, |
| 60 | + std::vector<double>& solution, |
| 61 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 62 | + kinematics::KinematicsQueryOptions const& options = |
| 63 | + kinematics::KinematicsQueryOptions()) const; |
| 64 | + |
| 65 | + virtual bool searchPositionIK(geometry_msgs::msg::Pose const& ik_pose, |
| 66 | + std::vector<double> const& ik_seed_state, |
| 67 | + double timeout, |
| 68 | + std::vector<double> const& consistency_limits, |
| 69 | + std::vector<double>& solution, |
| 70 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 71 | + kinematics::KinematicsQueryOptions const& options = |
| 72 | + kinematics::KinematicsQueryOptions()) const; |
| 73 | + |
| 74 | + virtual bool searchPositionIK(geometry_msgs::msg::Pose const& ik_pose, |
| 75 | + std::vector<double> const& ik_seed_state, |
| 76 | + double timeout, |
| 77 | + std::vector<double>& solution, |
| 78 | + IKCallbackFn const& solution_callback, |
| 79 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 80 | + kinematics::KinematicsQueryOptions const& options = |
| 81 | + kinematics::KinematicsQueryOptions()) const; |
| 82 | + |
| 83 | + virtual bool searchPositionIK(geometry_msgs::msg::Pose const& ik_pose, |
| 84 | + std::vector<double> const& ik_seed_state, |
| 85 | + double timeout, |
| 86 | + std::vector<double> const& consistency_limits, |
| 87 | + std::vector<double>& solution, |
| 88 | + IKCallbackFn const& solution_callback, |
| 89 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 90 | + kinematics::KinematicsQueryOptions const& options = |
| 91 | + kinematics::KinematicsQueryOptions()) const; |
| 92 | + |
| 93 | + virtual bool searchPositionIK( |
| 94 | + std::vector<geometry_msgs::msg::Pose> const& ik_poses, |
| 95 | + std::vector<double> const& ik_seed_state, |
| 96 | + double timeout, |
| 97 | + std::vector<double> const& consistency_limits, |
| 98 | + std::vector<double>& solution, |
| 99 | + IKCallbackFn const& solution_callback, |
| 100 | + moveit_msgs::msg::MoveItErrorCodes& error_code, |
| 101 | + kinematics::KinematicsQueryOptions const& options = kinematics::KinematicsQueryOptions(), |
| 102 | + moveit::core::RobotState const* context_state = NULL) const; |
| 103 | +}; |
| 104 | + |
| 105 | +} // namespace pick_ik |
0 commit comments