40 #include <rclcpp/rclcpp.hpp>
41 #include <random_numbers/random_numbers.h>
44 #include <geometry_msgs/msg/pose_stamped.hpp>
45 #include <moveit_msgs/srv/get_position_fk.hpp>
46 #include <moveit_msgs/srv/get_position_ik.hpp>
47 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
48 #include <moveit_msgs/msg/move_it_error_codes.hpp>
51 #include <kdl/config.h>
52 #include <kdl/chainfksolver.hpp>
53 #include <kdl/chainiksolver.hpp>
65 class ChainIkSolverVelMimicSVD;
83 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
84 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
88 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
89 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
93 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
94 const std::vector<double>& consistency_limits, std::vector<double>& solution,
95 moveit_msgs::msg::MoveItErrorCodes& error_code,
99 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
100 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
101 moveit_msgs::msg::MoveItErrorCodes& error_code,
105 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
106 const std::vector<double>& consistency_limits, std::vector<double>& solution,
107 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
110 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
111 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
114 const std::string& group_name,
const std::string& base_frame,
115 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
120 const std::vector<std::string>&
getJointNames()
const override;
125 const std::vector<std::string>&
getLinkNames()
const override;
128 typedef Eigen::Matrix<double, 6, 1>
Twist;
133 KDL::JntArray& q_out,
const unsigned int max_iter,
const Eigen::VectorXd& joint_weights,
134 const Twist& cartesian_weights)
const;
137 void getJointWeights();
138 bool timedOut(
const rclcpp::Time& start_time,
double duration)
const;
146 bool checkConsistency(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
147 const Eigen::VectorXd& solution)
const;
149 void getRandomConfiguration(Eigen::VectorXd& jnt_array)
const;
156 void getRandomConfiguration(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
157 Eigen::VectorXd& jnt_array)
const;
160 void clipToJointLimits(
const KDL::JntArray& q, KDL::JntArray& q_delta, Eigen::ArrayXd& weighting)
const;
162 static rclcpp::Clock steady_clock_;
166 unsigned int dimension_;
167 moveit_msgs::msg::KinematicSolverInfo solver_info_;
170 moveit::core::RobotStatePtr state_;
171 KDL::Chain kdl_chain_;
172 std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
173 std::vector<JointMimic> mimic_joints_;
174 std::vector<double> joint_weights_;
175 Eigen::VectorXd joint_min_, joint_max_;
177 int max_solver_iterations_;
184 double orientation_vs_position_weight_;
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
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....
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
KDLKinematicsPlugin()
Default constructor.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
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.
Eigen::Matrix< double, 6, 1 > Twist
Provides an interface for kinematics solvers.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
A set of options for the kinematics solver.