37 #include <geometry_msgs/PoseStamped.h> 51 bool PR2ArmIKSolver::getCount(
int& count,
const int& max_count,
const int& min_count)
55 if (-count >= min_count)
60 else if (count + 1 <= max_count)
72 if (1 - count <= max_count)
77 else if (count - 1 >= min_count)
87 PR2ArmIKSolver::PR2ArmIKSolver(
const urdf::ModelInterface&
robot_model,
const std::string& root_frame_name,
88 const std::string& tip_frame_name,
const double& search_discretization_angle,
89 const int& free_angle)
105 std::vector<std::vector<double> > solution_ik;
109 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"Solving with %f", q_init(0));
117 if (solution_ik.empty())
120 double min_distance = 1e6;
123 for (
int i = 0; i < (int)solution_ik.size(); i++)
127 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"Solution : %d", (
int)solution_ik.size());
129 for (
int j = 0; j < (int)solution_ik[i].size(); j++)
131 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"%d: %f", j, solution_ik[i][j]);
137 if (tmp_distance < min_distance)
139 min_distance = tmp_distance;
146 q_out.
resize((
int)solution_ik[min_index].size());
147 for (
int i = 0; i < (int)solution_ik[min_index].size(); i++)
149 q_out(i) = solution_ik[min_index][i];
158 const double& timeout)
165 double loop_time = 0;
168 int num_positive_increments =
170 int num_negative_increments =
173 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"%f %f %f %d %d \n\n", initial_guess,
176 num_negative_increments);
177 while (loop_time < timeout)
181 if (!
getCount(count, num_positive_increments, -num_negative_increments))
188 if (loop_time >= timeout)
190 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"IK Timed out in %f seconds", timeout);
195 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"No IK solution was found");
201 bool getKDLChain(
const urdf::ModelInterface& model,
const std::string& root_name,
const std::string& tip_name,
208 ROS_ERROR(
"Could not initialize tree object");
211 if (!tree.
getChain(root_name, tip_name, kdl_chain))
213 ROS_ERROR_STREAM(
"Could not initialize chain object for base " << root_name <<
" tip " << tip_name);
221 Eigen::Affine3f b = Eigen::Affine3f::Identity();
222 for (
int i = 0; i < 3; i++)
224 for (
int j = 0; j < 3; j++)
236 for (
int i = 0; i < (int)array_1.size(); i++)
238 distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
240 return sqrt(distance);
268 const std::string& base_name,
const std::string& tip_name,
269 double search_discretization)
271 setValues(robot_description, group_name, base_name, tip_name, search_discretization);
302 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"PR2Kinematics:: joint name: %s",
307 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"PR2Kinematics can solve IK for %s",
312 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"PR2Kinematics can solve FK for %s",
315 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"PR2KinematicsPlugin::active for %s", group_name.c_str());
323 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
330 const std::vector<double>& ik_seed_state,
double timeout,
331 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
337 error_code.val = error_code.PLANNING_FAILED;
351 jnt_pos_in(i) = ik_seed_state[i];
354 int ik_valid =
pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in, pose_desired, jnt_pos_out, timeout);
357 error_code.val = error_code.NO_IK_SOLUTION;
363 solution.resize(dimension_);
366 solution[i] = jnt_pos_out(i);
368 error_code.val = error_code.SUCCESS;
373 ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin",
"An IK solution could not be found");
374 error_code.val = error_code.NO_IK_SOLUTION;
380 const std::vector<double>& ik_seed_state,
double timeout,
381 const std::vector<double>& consistency_limit,
382 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
389 const std::vector<double>& ik_seed_state,
double timeout,
390 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
391 moveit_msgs::MoveItErrorCodes& error_code,
398 const std::vector<double>& ik_seed_state,
double timeout,
399 const std::vector<double>& consistency_limit,
400 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
401 moveit_msgs::MoveItErrorCodes& error_code,
408 const std::vector<double>& joint_angles,
409 std::vector<geometry_msgs::Pose>& poses)
const double search_discretization_angle_
A set of options for the kinematics solver.
Core components of MoveIt!
const Segment & getSegment(unsigned int nr) const
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
unsigned int getNrOfSegments() const
bool getCount(int &count, const int &max_count, const int &min_count)
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, search for the joint angles required to reach it...
moveit_msgs::KinematicSolverInfo fk_solver_info_
int CartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
std::string root_frame_name_
static const int NO_IK_SOLUTION
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
#define ROS_DEBUG_NAMED(name,...)
const std::string & getName() const
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
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, compute the joint angles to reach it.
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out)
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
urdf::ModelInterfaceSharedPtr robot_model_
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Set the parameters for the solver, for use with kinematic chain IK solvers.
def xml_string(rootXml, addHeader=True)
Eigen::Affine3f KDLToEigenMatrix(const KDL::Frame &p)
bool active_
Indicates whether the solver has been successfully initialized.
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
The signature for a callback that can compute IK.
moveit_msgs::KinematicSolverInfo ik_solver_info_
void resize(unsigned int newSize)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
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.
double search_discretization_
static const int TIMED_OUT
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.
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
Initialization function for the kinematics.
#define ROS_ERROR_STREAM(args)
void setRobotModel(urdf::ModelInterfaceSharedPtr &robot_model)
bool isActive()
Specifies if the node is active or not.
double distance(const urdf::Pose &transform)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)