00001 #include <r2_controllers_ros/R2RosTreeFk.hpp> 00002 00003 R2RosTreeFk::R2RosTreeFk(std::string urdf) 00004 { 00005 treeFk.loadFromFile(urdf); 00006 } 00007 00008 void R2RosTreeFk::setup(std::string inputJointStatesName, std::string outputPoseStatesName) 00009 { 00011 poseStatesOut = nh.advertise<nasa_r2_common_msgs::PoseState>(outputPoseStatesName, 1); 00012 jointStatesIn = nh.subscribe(inputJointStatesName, 1, &R2RosTreeFk::jointStatesCallback, this); 00013 } 00014 00015 void R2RosTreeFk::jointStatesCallback(const sensor_msgs::JointState &msg) 00016 { 00017 treeFk.getPoseState(msg, poseStatesOutMsg); 00018 poseStatesOut.publish(poseStatesOutMsg); 00019 }