39#include <kdl/config.h>
40#include <kdl/frames.hpp>
41#include <kdl/jntarray.hpp>
42#include <kdl/tree.hpp>
43#include <kdl_parser/kdl_parser.hpp>
46#include <moveit_msgs/srv/get_position_fk.hpp>
47#include <moveit_msgs/srv/get_position_ik.hpp>
48#include <moveit_msgs/msg/kinematic_solver_info.hpp>
49#include <moveit_msgs/msg/move_it_error_codes.hpp>
51#include <kdl/chainfksolverpos_recursive.hpp>
53#if __has_include(<urdf/model.hpp>)
54#include <urdf/model.hpp>
56#include <urdf/model.h>
67static const int NO_IK_SOLUTION = -1;
68static const int TIMED_OUT = -2;
86 PR2ArmIKSolver(
const urdf::ModelInterface& robot_model,
const std::string& root_frame_name,
87 const std::string& tip_frame_name,
double search_discretization_angle,
int free_angle);
103 int CartToJnt(
const KDL::JntArray& q_init,
const KDL::Frame& p_in, KDL::JntArray& q_out)
override;
105 int cartToJntSearch(
const KDL::JntArray& q_in,
const KDL::Frame& p_in, KDL::JntArray& q_out,
double timeout);
113 bool getCount(
int& count,
int max_count,
int min_count);
115 double search_discretization_angle_;
119 std::string root_frame_name_;
124void getKDLChainInfo(
const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info);
150 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
151 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
163 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
164 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
176 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
177 const std::vector<double>& consistency_limits, std::vector<double>& solution,
178 moveit_msgs::msg::MoveItErrorCodes& error_code,
190 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
191 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
192 moveit_msgs::msg::MoveItErrorCodes& error_code,
206 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
207 const std::vector<double>& consistency_limits, std::vector<double>& solution,
208 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
218 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
219 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
226 const std::string& group_name,
const std::string& base_frame,
227 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
232 const std::vector<std::string>&
getJointNames()
const override;
237 const std::vector<std::string>&
getLinkNames()
const override;
253 moveit_msgs::msg::MoveItErrorCodes& error_code)
const;
256 moveit_msgs::msg::MoveItErrorCodes& error_code)
const;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
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...
int cartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, double timeout)
~PR2ArmIKSolver() override
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &response)
void updateInternalDataStructures() override
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
bool active_
Indicates whether the solver has been successfully initialized.
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
IKCallbackFn desiredPoseCallback_
bool isActive()
Specifies if the node is active or not.
void desiredPoseCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::msg::MoveItErrorCodes &error_code) const
moveit_msgs::msg::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
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.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
moveit_msgs::msg::KinematicSolverInfo fk_solver_info_
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.
void jointSolutionCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::msg::MoveItErrorCodes &error_code) const
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.
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
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....
IKCallbackFn solutionCallback_
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::msg::KinematicSolverInfo &chain_info)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
Eigen::Isometry3f kdlToEigenMatrix(const KDL::Frame &p)
A set of options for the kinematics solver.