src
OdomMsgToTFNode.cpp
Go to the documentation of this file.
1
/*
2
Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3
All rights reserved.
4
5
Redistribution and use in source and binary forms, with or without
6
modification, are permitted provided that the following conditions are met:
7
* Redistributions of source code must retain the above copyright
8
notice, this list of conditions and the following disclaimer.
9
* Redistributions in binary form must reproduce the above copyright
10
notice, this list of conditions and the following disclaimer in the
11
documentation and/or other materials provided with the distribution.
12
* Neither the name of the Universite de Sherbrooke nor the
13
names of its contributors may be used to endorse or promote products
14
derived from this software without specific prior written permission.
15
16
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
*/
27
28
#include <
ros/ros.h
>
29
#include <nav_msgs/Odometry.h>
30
#include <
tf2_ros/transform_broadcaster.h
>
31
#include <
rtabmap_conversions/MsgConversion.h
>
32
33
class
OdomMsgToTF
34
{
35
36
public
:
37
OdomMsgToTF
() :
38
frameId_
(
""
),
39
odomFrameId_
(
""
)
40
{
41
ros::NodeHandle
pnh(
"~"
);
42
pnh.
param
(
"frame_id"
,
frameId_
,
frameId_
);
43
pnh.
param
(
"odom_frame_id"
,
odomFrameId_
,
odomFrameId_
);
44
45
ros::NodeHandle
nh;
46
odomTopic_
= nh.
subscribe
(
"odom"
, 1, &
OdomMsgToTF::odomReceivedCallback
,
this
);
47
}
48
49
virtual
~OdomMsgToTF
(){}
50
51
void
odomReceivedCallback
(
const
nav_msgs::OdometryConstPtr &
msg
)
52
{
53
if
(
frameId_
.empty())
54
{
55
frameId_
=
msg
->child_frame_id;
56
}
57
if
(
odomFrameId_
.empty())
58
{
59
odomFrameId_
=
msg
->header.frame_id;
60
}
61
geometry_msgs::TransformStamped
t
;
62
rtabmap::Transform
pose =
rtabmap_conversions::transformFromPoseMsg
(
msg
->pose.pose);
63
if
(pose.
isNull
())
64
{
65
ROS_WARN
(
"Odometry received is null! Cannot send tf..."
);
66
}
67
else
68
{
69
t
.child_frame_id =
frameId_
;
70
t
.header.frame_id =
odomFrameId_
;
71
t
.header.stamp =
msg
->header.stamp;
72
rtabmap_conversions::transformToGeometryMsg
(pose,
t
.transform);
73
tfBroadcaster_
.
sendTransform
(
t
);
74
}
75
}
76
77
private
:
78
std::string
frameId_
;
79
std::string
odomFrameId_
;
80
81
ros::Subscriber
odomTopic_
;
82
tf2_ros::TransformBroadcaster
tfBroadcaster_
;
83
};
84
85
86
int
main
(
int
argc,
char
** argv)
87
{
88
ros::init
(argc,
argv
,
"odom_msg_to_tf"
);
89
OdomMsgToTF
odomToTf;
90
ros::spin
();
91
return
0;
92
}
OdomMsgToTF
Definition:
OdomMsgToTFNode.cpp:33
rtabmap_conversions::transformFromPoseMsg
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
OdomMsgToTF::frameId_
std::string frameId_
Definition:
OdomMsgToTFNode.cpp:78
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
transform_to_tf.TransformStamped
TransformStamped
Definition:
transform_to_tf.py:31
OdomMsgToTF::odomReceivedCallback
void odomReceivedCallback(const nav_msgs::OdometryConstPtr &msg)
Definition:
OdomMsgToTFNode.cpp:51
rtabmap::Transform::isNull
bool isNull() const
transform_broadcaster.h
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
OdomMsgToTF::tfBroadcaster_
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition:
OdomMsgToTFNode.cpp:82
argv
argv
OdomMsgToTF::~OdomMsgToTF
virtual ~OdomMsgToTF()
Definition:
OdomMsgToTFNode.cpp:49
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rtabmap::Transform
OdomMsgToTF::odomFrameId_
std::string odomFrameId_
Definition:
OdomMsgToTFNode.cpp:79
republish_tf_static.msg
msg
Definition:
republish_tf_static.py:5
rtabmap_conversions::transformToGeometryMsg
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
tf2_ros::TransformBroadcaster
ros::NodeHandle::param
T param(const std::string ¶m_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
t
Point2 t(10, 10)
OdomMsgToTF::odomTopic_
ros::Subscriber odomTopic_
Definition:
OdomMsgToTFNode.cpp:81
MsgConversion.h
main
int main(int argc, char **argv)
Definition:
OdomMsgToTFNode.cpp:86
OdomMsgToTF::OdomMsgToTF
OdomMsgToTF()
Definition:
OdomMsgToTFNode.cpp:37
ros::NodeHandle
ros::Subscriber
rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50