39 using namespace Eigen;
42 PR2ArmIKSolver::PR2ArmIKSolver(
const urdf::Model& robot_model,
const std::string& root_frame_name,
43 const std::string& tip_frame_name,
const double& search_discretization_angle,
44 const int& free_angle)
48 search_discretization_angle_ = search_discretization_angle;
49 free_angle_ = free_angle;
50 root_frame_name_ = root_frame_name;
51 if (!pr2_arm_ik_->init(robot_model, root_frame_name, tip_frame_name))
57 void PR2ArmIKSolver::getSolverInfo(moveit_msgs::KinematicSolverInfo& response)
65 std::vector<std::vector<double> > solution_ik;
76 if (solution_ik.empty())
79 double min_distance = 1e6;
82 for (
int i = 0; i < (int)solution_ik.size(); ++i)
84 ROS_DEBUG(
"Solution : %d", (
int)solution_ik.size());
85 for (
int j = 0; j < (int)solution_ik[i].size(); j++)
87 ROS_DEBUG(
"Joint %d: %f", j, solution_ik[i][j]);
91 if (tmp_distance < min_distance)
93 min_distance = tmp_distance;
100 q_out.
resize((
int)solution_ik[min_index].size());
101 for (
int i = 0; i < (int)solution_ik[min_index].size(); ++i)
103 q_out(i) = solution_ik[min_index][i];
114 std::vector<std::vector<double> > solution_ik;
126 if (solution_ik.empty())
131 for (
int i = 0; i < (int)solution_ik.size(); ++i)
133 for (
int j = 0; j < 7; j++)
135 q(j) = solution_ik[i][j];
146 if (-count >= min_count)
151 else if (count + 1 <= max_count)
163 if (1 - count <= max_count)
168 else if (count - 1 >= min_count)
179 std::vector<KDL::JntArray>& q_out,
const double& timeout)
185 double loop_time = 0;
192 ROS_DEBUG(
"positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
193 while (loop_time < timeout)
197 if (!
getCount(count, num_positive_increments, -num_negative_increments))
203 if (loop_time >= timeout)
205 ROS_DEBUG(
"IK Timed out in %f seconds", timeout);
217 const double& timeout,
const double& consistency_limit)
219 moveit_msgs::MoveItErrorCodes error_code;
221 return CartToJntSearch(q_in, p_in, q_out, timeout,
true, consistency_limit, error_code, solution_callback);
225 const double& timeout, moveit_msgs::MoveItErrorCodes& error_code,
228 return CartToJntSearch(q_in, p_in, q_out, timeout,
false, 0.0, error_code, solution_callback);
232 const double& timeout,
const double& consistency_limit,
233 moveit_msgs::MoveItErrorCodes& error_code,
236 return CartToJntSearch(q_in, p_in, q_out, timeout,
true, consistency_limit, error_code, solution_callback);
240 const double& timeout,
bool use_consistency_limit,
const double& max_consistency,
241 moveit_msgs::MoveItErrorCodes& error_code,
248 double loop_time = 0;
251 double max_limit, min_limit;
252 if (use_consistency_limit)
266 if (use_consistency_limit)
268 ROS_DEBUG(
"Consistency[Joint: %d]: Initial guess %f, consistency %f",
free_angle_, initial_guess, max_consistency);
270 initial_guess + max_consistency);
272 initial_guess - max_consistency);
281 ROS_DEBUG(
"positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
283 unsigned int testnum = 0;
284 geometry_msgs::Pose ik_pose_msg;
289 while (loop_time < timeout)
294 if (solution_callback)
296 std::vector<double> ik_solution(7, 0.0);
297 for (
int i = 0; i < 7; ++i)
298 ik_solution[i] = q_out(i);
300 solution_callback(ik_pose_msg, ik_solution, error_code);
301 if (error_code.val == error_code.SUCCESS)
310 error_code.val = error_code.SUCCESS;
314 if (!
getCount(count, num_positive_increments, -num_negative_increments))
317 error_code.val = error_code.NO_IK_SOLUTION;
324 if (loop_time >= timeout)
326 ROS_DEBUG(
"IK Timed out in %f seconds", timeout);
327 error_code.val = error_code.TIMED_OUT;
331 error_code.val = error_code.NO_IK_SOLUTION;
336 std::string PR2ArmIKSolver::getFrameId()
double search_discretization_angle_
Namespace for the PR2ArmKinematics.
bool getCount(int &count, const int &max_count, const int &min_count)
std::string root_frame_name_
static const int NO_IK_SOLUTION
void updateInternalDataStructures()
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
void resize(unsigned int newSize)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
static const int TIMED_OUT
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)