Go to the documentation of this file.
   39 #include <urdf_model/model.h> 
   41 #include <Eigen/Geometry> 
   43 #include <kdl/chainiksolver.hpp> 
   44 #include <moveit_msgs/GetPositionFK.h> 
   45 #include <moveit_msgs/GetPositionIK.h> 
   46 #include <moveit_msgs/KinematicSolverInfo.h> 
   52 static const double IK_EPS = 1e-5;
 
   60 inline bool solveQuadratic(
const double& a, 
const double& b, 
const double& c, 
double* x1, 
double* x2)
 
   62   double discriminant = b * b - 4 * a * c;
 
   70   if (discriminant >= 0)
 
   72     *x1 = (-b + sqrt(discriminant)) / (2 * a);
 
   73     *x2 = (-b - sqrt(discriminant)) / (2 * a);
 
   76   else if (fabs(discriminant) < 
IK_EPS)
 
   90 inline bool solveCosineEqn(
const double& a, 
const double& b, 
const double& c, 
double& soln1, 
double& soln2)
 
   92   double theta1 = atan2(b, a);
 
   93   double denom = sqrt(a * a + b * b);
 
   98     std::cout << 
"denom: " << denom << std::endl;
 
  102   double rhs_ratio = c / denom;
 
  103   if (rhs_ratio < -1 || rhs_ratio > 1)
 
  106     std::cout << 
"rhs_ratio: " << rhs_ratio << std::endl;
 
  110   double acos_term = acos(rhs_ratio);
 
  111   soln1 = theta1 + acos_term;
 
  112   soln2 = theta1 - acos_term;
 
  134   bool init(
const urdf::ModelInterface& 
robot_model, 
const std::string& root_name, 
const std::string& tip_name);
 
  141   void computeIKShoulderPan(
const Eigen::Isometry3f& g_in, 
const double& shoulder_pan_initial_guess,
 
  142                             std::vector<std::vector<double> >& solution) 
const;
 
  150                              std::vector<std::vector<double> >& solution) 
const;
 
  164   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  167   void addJointToChainInfo(
const urdf::JointConstSharedPtr& joint, moveit_msgs::KinematicSolverInfo& info);
 
  171   bool checkJointLimits(
const double& joint_value, 
const int& joint_num) 
const;
 
  
double upperarm_elbow_offset_
Core components of MoveIt.
void addJointToChainInfo(const urdf::JointConstSharedPtr &joint, moveit_msgs::KinematicSolverInfo &info)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
std::vector< double > min_angles_
double torso_shoulder_offset_y_
double torso_shoulder_offset_x_
std::vector< double > angle_multipliers_
static const int NUM_JOINTS_ARM7DOF
Eigen::Isometry3f home_inv_
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
double shoulder_elbow_offset_
void computeIKShoulderRoll(const Eigen::Isometry3f &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.
std::vector< bool > continuous_joint_
std::vector< double > solution_
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 getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
void computeIKShoulderPan(const Eigen::Isometry3f &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.
double shoulder_wrist_offset_
PR2ArmIK()
Inverse kinematics for the PR2 arm.
double shoulder_upperarm_offset_
double torso_shoulder_offset_z_
bool checkJointLimits(const std::vector< double > &joint_values) const
double elbow_wrist_offset_
static const double IK_EPS
double distance(const urdf::Pose &transform)
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
std::vector< double > max_angles_
moveit_core
Author(s): Ioan Sucan 
, Sachin Chitta , Acorn Pooley 
autogenerated on Sat May 3 2025 02:25:32