00001 00059 #include <ros/ros.h> 00060 #include <string> 00061 00062 //messages 00063 #include <std_msgs/Float64.h> 00064 #include <pr2_controllers_msgs/JointControllerState.h> 00065 00067 std::string parent_name = "ffj3"; 00069 std::string child_name = "mfj3"; 00071 std::string controller_type = "_position_controller"; 00072 00073 //a ros subscriber (will be instantiated later on) 00074 ros::Subscriber sub; 00075 //a ros publisher (will be instantiated later on) 00076 ros::Publisher pub; 00077 00084 void callback(const pr2_controllers_msgs::JointControllerStateConstPtr& msg) 00085 { 00086 //publish the message 00087 std_msgs::Float64 command; 00088 command.data = msg->set_point; 00089 pub.publish(command); 00090 00091 return; 00092 } 00093 00102 int main(int argc, char** argv) 00103 { 00104 //init the ros node 00105 ros::init(argc, argv, "link_joints_example"); 00106 ros::NodeHandle node; 00107 00113 sub = node.subscribe("sh_" + parent_name + controller_type + "/state", 2, callback); 00114 00119 pub = node.advertise<std_msgs::Float64>("sh_" + child_name + controller_type + "/command", 2); 00120 00121 //subscribe until interrupted. 00122 while( ros::ok() ) 00123 ros::spin(); 00124 00125 return 0; 00126 }