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
00034 #include "ros/ros.h"
00035 #include "tf2_msgs/TFMessage.h"
00036 #include "tf2_ros/static_transform_broadcaster.h"
00037
00038 namespace tf2 {
00039
00040 StaticTransformBroadcaster::StaticTransformBroadcaster()
00041 {
00042 publisher_ = node_.advertise<tf2_msgs::TFMessage>("/tf_static", 100, true);
00043 };
00044
00045 void StaticTransformBroadcaster::sendTransform(const geometry_msgs::TransformStamped & msgtf)
00046 {
00047 std::vector<geometry_msgs::TransformStamped> v1;
00048 v1.push_back(msgtf);
00049 sendTransform(v1);
00050 }
00051
00052
00053 void StaticTransformBroadcaster::sendTransform(const std::vector<geometry_msgs::TransformStamped> & msgtf)
00054 {
00055 for (std::vector<geometry_msgs::TransformStamped>::const_iterator it_in = msgtf.begin(); it_in != msgtf.end(); ++it_in)
00056 {
00057 bool match_found = false;
00058 for (std::vector<geometry_msgs::TransformStamped>::iterator it_msg = net_message_.transforms.begin(); it_msg != net_message_.transforms.end(); ++it_msg)
00059 {
00060 if (it_in->header.frame_id == it_msg->header.frame_id)
00061 {
00062 *it_msg = *it_in;
00063 match_found = true;
00064 break;
00065 }
00066 }
00067 if (! match_found)
00068 net_message_.transforms.push_back(*it_in);
00069 }
00070
00071 publisher_.publish(net_message_);
00072 }
00073
00074
00075 }
00076
00077