00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037
00038 #include <ros/ros.h>
00039 #include <kdl_parser/kdl_parser.hpp>
00040 #include <pr2_calibration_estimation/FkTest.h>
00041 #include <kdl/tree.hpp>
00042 #include <kdl/chainfksolverpos_recursive.hpp>
00043
00044 using namespace std;
00045 using namespace pr2_calibration_estimation;
00046
00047 bool fk(KDL::Tree* tree, FkTest::Request& req, FkTest::Response& resp)
00048 {
00049 KDL::Chain my_chain;
00050 bool success;
00051 success = tree->getChain(req.root, req.tip, my_chain);
00052
00053 if (!success)
00054 {
00055 ROS_ERROR("Error extracting chain from [%s] to [%s]\n", req.root.c_str(), req.tip.c_str());
00056 return false;
00057 }
00058
00059 KDL::ChainFkSolverPos_recursive solver(my_chain);
00060
00061 KDL::JntArray joints(my_chain.getNrOfJoints());
00062 for (unsigned int i=0; i<my_chain.getNrOfJoints(); i++)
00063 joints(i) = req.joint_positions[i];
00064
00065 KDL::Frame out_frame;
00066 if (solver.JntToCart(joints, out_frame))
00067 {
00068 ROS_ERROR("Error running KDL solver");
00069 return false;
00070 }
00071
00072 resp.pos.resize(3);
00073
00074
00075 resp.pos[0] = out_frame.p.data[0];
00076 resp.pos[1] = out_frame.p.data[1];
00077 resp.pos[2] = out_frame.p.data[2];
00078
00079
00080 resp.rot.resize(9);
00081 for (unsigned int i=0; i<9; i++)
00082 resp.rot[i] = out_frame.M.data[i];
00083
00084 return true;
00085 }
00086
00087 int main(int argc, char** argv)
00088 {
00089 ros::init(argc, argv, "fk_reference");
00090 ros::NodeHandle n;
00091 ros::NodeHandle pn("~");
00092
00093 KDL::Tree my_tree;
00094 string robot_desc_string;
00095 if (!n.getParam("robot_description", robot_desc_string))
00096 ROS_FATAL("Couldn't get a robot_description from the param server");
00097
00098 if (!kdl_parser::treeFromString(robot_desc_string, my_tree))
00099 {
00100 ROS_ERROR("Failed to construct kdl tree");
00101 return false;
00102 }
00103
00104 boost::function< bool(FkTest::Request&, FkTest::Response&) > func = boost::bind(fk, &my_tree, _1, _2) ;
00105 ros::ServiceServer fk_service = n.advertiseService("fk", func);
00106
00107 ros::spin();
00108
00109 return 0;
00110 }