41 #include <pr2_calibration_launch/FkTest.h> 42 #include <kdl/tree.hpp> 43 #include <kdl/chainfksolverpos_recursive.hpp> 48 bool fk(
KDL::Tree* tree, FkTest::Request& req, FkTest::Response& resp)
52 success = tree->
getChain(req.root, req.tip, my_chain);
56 ROS_ERROR(
"Error extracting chain from [%s] to [%s]\n", req.root.c_str(), req.tip.c_str());
64 joints(
i) = req.joint_positions[
i];
76 resp.pos[0] = out_frame.
p.
data[0];
77 resp.pos[1] = out_frame.
p.
data[1];
78 resp.pos[2] = out_frame.
p.
data[2];
82 for (
unsigned int i=0;
i<9;
i++)
83 resp.rot[
i] = out_frame.
M.
data[
i];
88 int main(
int argc,
char** argv)
95 string robot_desc_string;
96 if (!n.
getParam(
"robot_description", robot_desc_string))
97 ROS_FATAL(
"Couldn't get a robot_description from the param server");
101 ROS_ERROR(
"Failed to construct kdl tree");
105 boost::function< bool(FkTest::Request&, FkTest::Response&) > func = boost::bind(
fk, &my_tree, _1, _2) ;
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ROSCPP_DECL void spin(Spinner &spinner)
unsigned int getNrOfJoints() const
KDL_PARSER_PUBLIC bool treeFromString(const std::string &xml, KDL::Tree &tree)
bool fk(KDL::Tree *tree, FkTest::Request &req, FkTest::Response &resp)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)