Go to the documentation of this file.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 #include <ros/ros.h>
00031
00032 #include <geometry_msgs/TransformStamped.h>
00033 #include <sensor_msgs/JointState.h>
00034
00035 #include <tf/transform_broadcaster.h>
00036
00037 #include <signal.h>
00038 #include <sys/types.h>
00039 #include <sys/wait.h>
00040 #include <map>
00041 #include <string>
00042
00043 #include <compatibility.h>
00044
00045 class JointTfPublisherNode
00046 {
00047 private:
00048 ros::NodeHandle nh_;
00049 ros::NodeHandle pnh_;
00050 std::map<std::string, ros::Subscriber> subs_;
00051 tf::TransformBroadcaster tf_broadcaster_;
00052
00053 void cbJoint(const sensor_msgs::JointState::ConstPtr& msg)
00054 {
00055 for (size_t i = 0; i < msg->name.size(); i++)
00056 {
00057 geometry_msgs::TransformStamped trans;
00058 trans.header = msg->header;
00059 trans.header.frame_id = msg->name[i] + "_in";
00060 trans.child_frame_id = msg->name[i] + "_out";
00061 trans.transform.rotation = tf::createQuaternionMsgFromYaw(msg->position[i]);
00062 tf_broadcaster_.sendTransform(trans);
00063 }
00064 }
00065
00066 public:
00067 JointTfPublisherNode()
00068 : nh_()
00069 , pnh_("~")
00070 {
00071 subs_["joint"] = compat::subscribe(
00072 nh_, "joint_states",
00073 pnh_, "joint", 1, &JointTfPublisherNode::cbJoint, this);
00074 }
00075 };
00076
00077 int main(int argc, char* argv[])
00078 {
00079 ros::init(argc, argv, "joint_tf_publisher");
00080
00081 JointTfPublisherNode jp;
00082 ros::spin();
00083
00084 return 0;
00085 }