84 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
85 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
89 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
90 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
94 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
95 const std::vector<double>& consistency_limits, std::vector<double>& solution,
96 moveit_msgs::msg::MoveItErrorCodes& error_code,
100 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
101 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
102 moveit_msgs::msg::MoveItErrorCodes& error_code,
106 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
107 const std::vector<double>& consistency_limits, std::vector<double>& solution,
108 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
111 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
112 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
115 const std::string& group_name,
const std::string& base_frame,
116 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
121 const std::vector<std::string>&
getJointNames()
const override;
126 const std::vector<std::string>&
getLinkNames()
const override;
129 typedef Eigen::Matrix<double, 6, 1>
Twist;
134 KDL::JntArray& q_out,
const unsigned int max_iter,
const Eigen::VectorXd& joint_weights,
135 const Twist& cartesian_weights)
const;
138 void getJointWeights();
139 bool timedOut(
const rclcpp::Time& start_time,
double duration)
const;
147 bool checkConsistency(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
148 const Eigen::VectorXd& solution)
const;
150 void getRandomConfiguration(Eigen::VectorXd& jnt_array)
const;
157 void getRandomConfiguration(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
158 Eigen::VectorXd& jnt_array)
const;
161 void clipToJointLimits(
const KDL::JntArray& q, KDL::JntArray& q_delta, Eigen::ArrayXd& weighting)
const;
165 unsigned int dimension_;
166 moveit_msgs::msg::KinematicSolverInfo solver_info_;
169 moveit::core::RobotStatePtr state_;
170 KDL::Chain kdl_chain_;
171 std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
172 std::vector<JointMimic> mimic_joints_;
173 std::vector<double> joint_weights_;
174 Eigen::VectorXd joint_min_, joint_max_;
176 std::shared_ptr<kdl_kinematics::ParamListener> param_listener_;
177 kdl_kinematics::Params params_;
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 override
Given a desired pose of the end-effector, compute the joint angles to reach it.
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
Initialization function for the kinematics, for use with kinematic chain IK solvers.
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 override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
int CartToJnt(KDL::ChainIkSolverVelMimicSVD &ik_solver, const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const unsigned int max_iter, const Eigen::VectorXd &joint_weights, const Twist &cartesian_weights) const
Solve position IK given initial joint values.