40 #include <urdf_model/model.h> 42 #include <Eigen/Geometry> 44 #include <kdl/chainiksolver.hpp> 45 #include <moveit_msgs/GetPositionFK.h> 46 #include <moveit_msgs/GetPositionIK.h> 47 #include <moveit_msgs/KinematicSolverInfo.h> 55 inline double distance(
const urdf::Pose& transform)
57 return sqrt(transform.position.x * transform.position.x + transform.position.y * transform.position.y +
58 transform.position.z * transform.position.z);
61 inline bool solveQuadratic(
const double& a,
const double& b,
const double& c,
double* x1,
double* x2)
63 double discriminant = b * b - 4 * a * c;
71 if (discriminant >= 0)
73 *x1 = (-b +
sqrt(discriminant)) / (2 * a);
74 *x2 = (-b -
sqrt(discriminant)) / (2 * a);
77 else if (fabs(discriminant) <
IK_EPS)
91 inline bool solveCosineEqn(
const double& a,
const double& b,
const double& c,
double& soln1,
double& soln2)
93 double theta1 =
atan2(b, a);
94 double denom =
sqrt(a * a + b * b);
96 if (fabs(denom) < IK_EPS)
99 std::cout <<
"denom: " << denom << std::endl;
103 double rhs_ratio = c / denom;
104 if (rhs_ratio < -1 || rhs_ratio > 1)
107 std::cout <<
"rhs_ratio: " << rhs_ratio << std::endl;
111 double acos_term =
acos(rhs_ratio);
112 soln1 = theta1 + acos_term;
113 soln2 = theta1 - acos_term;
136 bool init(
const urdf::ModelInterface&
robot_model,
const std::string& root_name,
const std::string& tip_name);
143 void computeIKShoulderPan(
const Eigen::Affine3f& g_in,
const double& shoulder_pan_initial_guess,
144 std::vector<std::vector<double> >& solution)
const;
152 std::vector<std::vector<double> >& solution)
const;
171 void addJointToChainInfo(urdf::JointConstSharedPtr joint, moveit_msgs::KinematicSolverInfo& info);
175 bool checkJointLimits(
const double& joint_value,
const int& joint_num)
const;
193 #endif // PR2_ARM_IK_H std::vector< double > max_angles_
double torso_shoulder_offset_z_
Core components of MoveIt!
Eigen::Affine3f home_inv_
std::vector< bool > continuous_joint_
double elbow_wrist_offset_
double shoulder_elbow_offset_
static const int NUM_JOINTS_ARM7DOF
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
double upperarm_elbow_offset_
void computeIKShoulderRoll(const Eigen::Affine3f &g_in, const 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
double shoulder_upperarm_offset_
void addJointToChainInfo(urdf::JointConstSharedPtr joint, moveit_msgs::KinematicSolverInfo &info)
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
std::vector< double > min_angles_
double torso_shoulder_offset_y_
std::vector< double > solution_
double torso_shoulder_offset_x_
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
void computeIKShoulderPan(const Eigen::Affine3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
compute IK based on an initial guess for the shoulder pan angle.
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
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.
static const double IK_EPS
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
std::vector< double > angle_multipliers_
bool checkJointLimits(const std::vector< double > &joint_values) const
double distance(const urdf::Pose &transform)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
double shoulder_wrist_offset_