38 #include <geometry_msgs/PoseStamped.h> 57 PR2ArmKinematicsPlugin::PR2ArmKinematicsPlugin() : active_(false)
69 const std::string& base_frame,
const std::string& tip_frame,
70 double search_discretization)
72 setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
77 while (!
loadRobotModel(private_handle, robot_model, xml_string) && private_handle.ok())
79 ROS_ERROR(
"Could not load robot model. Are you sure the robot model is on the parameter server?");
91 private_handle.param<
int>(
"free_angle",
free_angle_, 2);
118 ROS_DEBUG(
"PR2KinematicsPlugin::active for %s", group_name.c_str());
126 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
132 error_code.val = error_code.NO_IK_SOLUTION;
145 jnt_pos_in(i) = ik_seed_state[i];
151 error_code.val = error_code.NO_IK_SOLUTION;
157 solution.resize(dimension_);
160 solution[i] = jnt_pos_out(i);
162 error_code.val = error_code.SUCCESS;
167 ROS_DEBUG(
"An IK solution could not be found");
168 error_code.val = error_code.NO_IK_SOLUTION;
174 const std::vector<double>& ik_seed_state,
double timeout,
175 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
179 static std::vector<double> consistency_limits;
180 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
184 const std::vector<double>& ik_seed_state,
double timeout,
185 const std::vector<double>& consistency_limits,
186 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
190 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
194 const std::vector<double>& ik_seed_state,
double timeout,
195 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
196 moveit_msgs::MoveItErrorCodes& error_code,
199 static std::vector<double> consistency_limits;
200 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
204 const std::vector<double>& ik_seed_state,
double timeout,
205 const std::vector<double>& consistency_limits,
206 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
207 moveit_msgs::MoveItErrorCodes& error_code,
213 error_code.val = error_code.FAILURE;
216 if (!consistency_limits.empty() && consistency_limits.size() !=
dimension_)
218 ROS_ERROR(
"Consistency limits should be of size: %d", dimension_);
219 error_code.val = error_code.FAILURE;
229 jnt_pos_in.
resize(dimension_);
232 jnt_pos_in(i) = ik_seed_state[i];
236 if (consistency_limits.empty())
238 ik_valid =
pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in, pose_desired, jnt_pos_out, timeout, error_code,
239 solution_callback ? boost::bind(solution_callback, _1, _2, _3) :
245 jnt_pos_in, pose_desired, jnt_pos_out, timeout, consistency_limits[free_angle_], error_code,
246 solution_callback ? boost::bind(solution_callback, _1, _2, _3) :
IKCallbackFn());
254 solution.resize(dimension_);
257 solution[i] = jnt_pos_out(i);
263 ROS_DEBUG(
"An IK solution could not be found");
269 const std::vector<double>& joint_angles,
270 std::vector<geometry_msgs::Pose>& poses)
const 280 geometry_msgs::PoseStamped pose;
283 jnt_pos_in.
resize(dimension_);
286 jnt_pos_in(i) = joint_angles[i];
290 poses.
resize(link_names.size());
293 for (
unsigned int i = 0; i < poses.size(); i++)
303 ROS_ERROR(
"Could not compute FK for %s", link_names[i].c_str());
Namespace for the PR2ArmKinematics.
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_
moveit_msgs::KinematicSolverInfo fk_solver_info_
static const int NO_IK_SOLUTION
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
PLUGINLIB_EXPORT_CLASS(pr2_arm_kinematics::PR2ArmKinematicsPlugin, kinematics::KinematicsBase)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
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 override
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
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 override
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)
def xml_string(rootXml, addHeader=True)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const override
void resize(unsigned int newSize)
bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
const std::vector< std::string > & getLinkNames() const override
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
double search_discretization_
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)