91inline bool solveCosineEqn(
double a,
double b,
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 <<
'\n';
103 double rhs_ratio = c / denom;
104 if (rhs_ratio < -1 || rhs_ratio > 1)
107 std::cout <<
"rhs_ratio: " << rhs_ratio <<
'\n';
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);
144 std::vector<std::vector<double> >& solution)
const;
152 std::vector<std::vector<double> >& solution)
const;
161 void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info);
171 void addJointToChainInfo(
const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info);
173 bool checkJointLimits(
const std::vector<double>& joint_values)
const;
175 bool checkJointLimits(
double joint_value,
int joint_num)
const;
177 Eigen::Isometry3f grhs_, gf_, home_inv_;
179 std::vector<double> angle_multipliers_;
181 std::vector<double> solution_;
183 double shoulder_upperarm_offset_, upperarm_elbow_offset_, elbow_wrist_offset_, shoulder_wrist_offset_,
184 shoulder_elbow_offset_, torso_shoulder_offset_x_, torso_shoulder_offset_y_, torso_shoulder_offset_z_;
186 std::vector<double> min_angles_;
188 std::vector<double> max_angles_;
190 std::vector<bool> continuous_joint_;
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.