38 #include <geometry_msgs/PoseStamped.h> 58 PR2ArmKinematics::PR2ArmKinematics(
bool create_tf_listener): node_handle_(
"~"),dimension_(7)
65 ROS_ERROR(
"Could not load robot model. Are you sure the robot model is on the parameter server?");
70 ROS_FATAL(
"PR2IK: No root name found on parameter server");
74 ROS_FATAL(
"PR2IK: No tip name found on parameter server");
84 if(create_tf_listener) {
143 moveit_msgs::GetPositionIK::Response &response)
154 geometry_msgs::PoseStamped pose_msg_in = request.ik_request.pose_stamped;
155 geometry_msgs::PoseStamped pose_msg_out;
159 response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
164 response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
167 request.ik_request.pose_stamped = pose_msg_out;
173 moveit_msgs::GetPositionIK::Response &response)
187 jnt_pos_in(tmp_index) = request.ik_request.robot_state.joint_state.position[i];
191 ROS_ERROR(
"i: %d, No joint index for %s",i,request.ik_request.robot_state.joint_state.name[i].c_str());
195 std::vector<KDL::JntArray> jnt_array;
196 jnt_array.push_back(jnt_pos_out);
200 (
const double)(request.ik_request.timeout.toSec()));
202 response.error_code.val = response.error_code.TIMED_OUT;
204 response.error_code.val = response.error_code.NO_IK_SOLUTION;
206 response.solution.joint_state.header = request.ik_request.pose_stamped.header;
211 response.solution.joint_state.position.resize(dimension_);
214 response.solution.joint_state.position[i] = jnt_array[0](i);
215 ROS_DEBUG(
"IK Solution: %s %d: %f",response.solution.joint_state.name[i].c_str(),i,jnt_array[0](i));
217 response.error_code.val = response.error_code.SUCCESS;
222 ROS_DEBUG(
"An IK solution could not be found");
228 moveit_msgs::GetPositionFK::Response &response)
241 geometry_msgs::PoseStamped pose;
245 for(
int i=0; i < (int) request.robot_state.joint_state.position.size(); i++)
249 jnt_pos_in(tmp_index) = request.robot_state.joint_state.position[i];
252 response.pose_stamped.
resize(request.fk_link_names.size());
253 response.fk_link_names.resize(request.fk_link_names.size());
255 for(
unsigned int i=0; i < request.fk_link_names.size(); i++)
265 if(!
transformPose(request.header.frame_id, pose, response.pose_stamped[i])) {
266 response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
269 response.fk_link_names[i] = request.fk_link_names[i];
270 response.error_code.val = response.error_code.SUCCESS;
274 ROS_ERROR(
"Could not compute FK for %s",request.fk_link_names[i].c_str());
275 response.error_code.val = response.error_code.NO_IK_SOLUTION;
282 const geometry_msgs::PoseStamped& pose_in,
283 geometry_msgs::PoseStamped& pose_out)
290 ROS_ERROR(
"Could not transform FK pose to frame: %s",des_frame.c_str());
294 ROS_WARN_STREAM(
"No tf listener, can't transform to frame " << des_frame);
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
tf::TransformListener * tf_
bool getPositionIKHelper(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
ros::ServiceServer fk_service_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
Namespace for the PR2ArmKinematics.
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
unsigned int getNrOfSegments() const
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
ros::NodeHandle node_handle_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual ~PR2ArmKinematics()
static const int NO_IK_SOLUTION
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool getPositionFK(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response)
This is the basic forward kinematics service that will return information about the kinematics node...
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
virtual bool getPositionIK(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
This is the basic IK service method that will compute and return an IK solution.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
ros::ServiceServer ik_service_
def xml_string(rootXml, addHeader=True)
moveit_msgs::KinematicSolverInfo fk_solver_info_
#define ROS_WARN_STREAM(args)
double search_discretization_
static const std::string IK_SERVICE
static const std::string FK_INFO_SERVICE
void resize(unsigned int newSize)
static const std::string IK_INFO_SERVICE
virtual bool transformPose(const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)
bool getParam(const std::string &key, std::string &s) const
static const int TIMED_OUT
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool isActive()
Specifies if the node is active or not.
static const std::string FK_SERVICE
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
moveit_msgs::KinematicSolverInfo ik_solver_info_
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)