39 #include <urdf_model/model.h>
40 #if __has_include(<urdf/model.hpp>)
41 #include <urdf/model.hpp>
43 #include <urdf/model.h>
45 #include <Eigen/Geometry>
47 #include <kdl/chainiksolver.hpp>
48 #include <moveit_msgs/srv/get_position_fk.hpp>
49 #include <moveit_msgs/srv/get_position_ik.hpp>
50 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
51 #include <rclcpp/rclcpp.hpp>
55 static const int NUM_JOINTS_ARM7DOF = 7;
57 static const double IK_EPS = 1e-5;
59 inline double distance(
const urdf::Pose& transform)
61 return sqrt(transform.position.x * transform.position.x + transform.position.y * transform.position.y +
62 transform.position.z * transform.position.z);
65 inline bool solveQuadratic(
double a,
double b,
double c,
double* x1,
double* x2)
67 double discriminant = b * b - 4 * a * c;
75 if (discriminant >= 0)
77 *x1 = (-b + sqrt(discriminant)) / (2 * a);
78 *x2 = (-b - sqrt(discriminant)) / (2 * a);
81 else if (fabs(discriminant) < IK_EPS)
95 inline bool solveCosineEqn(
double a,
double b,
double c,
double& soln1,
double& soln2)
97 double theta1 = atan2(b, a);
98 double denom = sqrt(a * a + b * b);
100 if (fabs(denom) < IK_EPS)
103 std::cout <<
"denom: " << denom <<
'\n';
107 double rhs_ratio = c / denom;
108 if (rhs_ratio < -1 || rhs_ratio > 1)
111 std::cout <<
"rhs_ratio: " << rhs_ratio <<
'\n';
115 double acos_term = acos(rhs_ratio);
116 soln1 = theta1 + acos_term;
117 soln2 = theta1 - acos_term;
140 bool init(
const urdf::ModelInterface& robot_model,
const std::string& root_name,
const std::string& tip_name);
148 std::vector<std::vector<double> >& solution)
const;
156 std::vector<std::vector<double> >& solution)
const;
165 void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info);
175 void addJointToChainInfo(
const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info);
177 bool checkJointLimits(
const std::vector<double>& joint_values)
const;
179 bool checkJointLimits(
double joint_value,
int joint_num)
const;
181 Eigen::Isometry3f grhs_, gf_, home_inv_;
183 std::vector<double> angle_multipliers_;
185 std::vector<double> solution_;
187 double shoulder_upperarm_offset_, upperarm_elbow_offset_, elbow_wrist_offset_, shoulder_wrist_offset_,
188 shoulder_elbow_offset_, torso_shoulder_offset_x_, torso_shoulder_offset_y_, torso_shoulder_offset_z_;
190 std::vector<double> min_angles_;
192 std::vector<double> max_angles_;
194 std::vector<bool> continuous_joint_;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, double shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
compute IK based on an initial guess for the shoulder roll angle. h
bool init(const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name)
Initialize the solver by providing a urdf::Model and a root and tip name.
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, double shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
compute IK based on an initial guess for the shoulder pan angle.
moveit_msgs::msg::KinematicSolverInfo solver_info_
get chain information about the arm.
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
double distance(const urdf::Pose &transform)
bool solveQuadratic(double a, double b, double c, double *x1, double *x2)
bool solveCosineEqn(double a, double b, double c, double &soln1, double &soln2)