include
tf2_ros
transform_listener.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, Willow Garage, Inc.
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
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
32
#ifndef TF2_ROS_TRANSFORMLISTENER_H
33
#define TF2_ROS_TRANSFORMLISTENER_H
34
35
#include "std_msgs/Empty.h"
36
#include "tf2_msgs/TFMessage.h"
37
#include "
ros/ros.h
"
38
#include "
ros/callback_queue.h
"
39
40
#include "
tf2_ros/buffer.h
"
41
42
#include "boost/thread.hpp"
43
44
namespace
tf2_ros
{
45
48
class
TransformListener
49
{
50
51
public
:
53
TransformListener
(
tf2::BufferCore
& buffer,
bool
spin_thread =
true
);
54
TransformListener
(
tf2::BufferCore
& buffer,
const
ros::NodeHandle
& nh,
bool
spin_thread =
true
);
55
56
~TransformListener
();
57
58
private
:
59
61
void
init
();
62
void
initWithThread
();
63
65
void
subscription_callback
(
const
ros::MessageEvent<tf2_msgs::TFMessage const>
& msg_evt);
66
void
static_subscription_callback
(
const
ros::MessageEvent<tf2_msgs::TFMessage const>
& msg_evt);
67
void
subscription_callback_impl
(
const
ros::MessageEvent<tf2_msgs::TFMessage const>
& msg_evt,
bool
is_static);
68
69
ros::CallbackQueue
tf_message_callback_queue_
;
70
boost::thread*
dedicated_listener_thread_
;
71
ros::NodeHandle
node_
;
72
ros::Subscriber
message_subscriber_tf_
;
73
ros::Subscriber
message_subscriber_tf_static_
;
74
tf2::BufferCore
&
buffer_
;
75
bool
using_dedicated_thread_
;
76
ros::Time
last_update_
;
77
78
void
dedicatedListenerThread
()
79
{
80
while
(using_dedicated_thread_)
81
{
82
tf_message_callback_queue_.
callAvailable
(
ros::WallDuration
(0.01));
83
}
84
};
85
86
};
87
}
88
89
#endif //TF_TRANSFORMLISTENER_H
tf2_ros::TransformListener::TransformListener
TransformListener(tf2::BufferCore &buffer, bool spin_thread=true)
Constructor for transform listener.
Definition:
transform_listener.cpp:38
tf2::BufferCore
tf2_ros::TransformListener::dedicated_listener_thread_
boost::thread * dedicated_listener_thread_
Definition:
transform_listener.h:70
tf2_ros::TransformListener::message_subscriber_tf_static_
ros::Subscriber message_subscriber_tf_static_
Definition:
transform_listener.h:73
ros::NodeHandle
tf2_ros::TransformListener::tf_message_callback_queue_
ros::CallbackQueue tf_message_callback_queue_
Definition:
transform_listener.h:69
tf2_ros::TransformListener::subscription_callback_impl
void subscription_callback_impl(const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt, bool is_static)
Definition:
transform_listener.cpp:102
ros::Time
tf2_ros::TransformListener::~TransformListener
~TransformListener()
Definition:
transform_listener.cpp:60
ros::WallDuration
tf2_ros::TransformListener::buffer_
tf2::BufferCore & buffer_
Definition:
transform_listener.h:74
ros::CallbackQueue
tf2_ros::TransformListener::last_update_
ros::Time last_update_
Definition:
transform_listener.h:76
tf2_ros::TransformListener::node_
ros::NodeHandle node_
Definition:
transform_listener.h:71
ros::CallbackQueue::callAvailable
void callAvailable()
ros::Subscriber
tf2_ros::TransformListener::message_subscriber_tf_
ros::Subscriber message_subscriber_tf_
Definition:
transform_listener.h:72
ros::MessageEvent
tf2_ros::TransformListener::dedicatedListenerThread
void dedicatedListenerThread()
Definition:
transform_listener.h:78
tf2_ros::TransformListener::init
void init()
Initialize this transform listener, subscribing, advertising services, etc.
Definition:
transform_listener.cpp:70
ros.h
tf2_ros::TransformListener
This class provides an easy way to request and receive coordinate frame transform information...
Definition:
transform_listener.h:48
buffer.h
tf2_ros::TransformListener::initWithThread
void initWithThread()
Definition:
transform_listener.cpp:76
tf2_ros
Definition:
buffer.h:42
callback_queue.h
tf2_ros::TransformListener::subscription_callback
void subscription_callback(const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt)
Callback function for ros message subscription.
Definition:
transform_listener.cpp:93
tf2_ros::TransformListener::static_subscription_callback
void static_subscription_callback(const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt)
Definition:
transform_listener.cpp:97
tf2_ros::TransformListener::using_dedicated_thread_
bool using_dedicated_thread_
Definition:
transform_listener.h:75
tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 27 2022 02:43:12