tools
tf2_republisher.cpp
Go to the documentation of this file.
1
// Consolidate & republish static transforms from a bag file
2
// Author: Max Schwarz <max.schwarz@ais.uni-bonn.de>
3
4
#include <
ros/ros.h
>
5
6
#include <tf2_msgs/TFMessage.h>
7
8
#include <
tf2_ros/static_transform_broadcaster.h
>
9
10
int
main
(
int
argc,
char
** argv)
11
{
12
ros::init
(argc, argv,
"tf2_republisher"
);
13
14
ros::NodeHandle
nh{
"~"
};
15
16
tf2_ros::StaticTransformBroadcaster
pub_tf;
17
18
using
Msg
= tf2_msgs::TFMessage;
19
using
Event =
ros::MessageEvent<Msg>
;
20
21
ros::Subscriber
sub = nh.subscribe<
Msg
>(
"/tf_static"
, 100, boost::function<void(const Event&)>(
22
[&](
const
Event& event)
23
{
24
// Did we publish this message?
25
if
(event.getPublisherName() ==
ros::this_node::getName
())
26
return
;
27
28
pub_tf.
sendTransform
(event.getMessage()->transforms);
29
}
30
));
31
32
ros::spin
();
33
34
return
0;
35
}
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
Msg
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
tf2_ros::StaticTransformBroadcaster
main
int main(int argc, char **argv)
Definition:
tf2_republisher.cpp:10
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
static_transform_broadcaster.h
ros::spin
ROSCPP_DECL void spin()
ros::NodeHandle
ros::MessageEvent
ros::Subscriber
rosbag_fancy
Author(s):
autogenerated on Tue Feb 20 2024 03:20:59