Main Page
Related Pages
Namespaces
Namespace List
Namespace Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
Functions
a
b
c
d
e
f
g
h
i
l
m
n
o
p
r
s
t
u
v
w
x
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
p
q
r
s
t
u
v
w
x
y
Typedefs
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
Enumerations
Enumerator
a
c
d
e
f
i
l
m
n
o
r
t
u
w
Classes
Class List
Class Hierarchy
Class Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
~
Functions
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
z
~
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
_
a
b
c
d
e
f
i
l
m
n
o
p
q
r
s
t
v
Enumerations
Enumerator
a
b
c
d
e
f
h
i
k
l
m
n
o
p
r
s
t
u
v
w
Related Functions
Files
File List
File Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
r
s
t
u
v
w
x
y
Functions
_
a
b
c
d
e
f
g
h
i
j
l
m
n
o
p
r
s
t
u
v
w
y
Variables
_
b
c
d
e
f
g
h
i
l
m
n
o
p
r
s
t
u
v
Typedefs
b
c
f
h
i
l
p
r
s
t
u
Enumerations
Enumerator
c
d
e
i
o
p
r
s
t
w
Macros
_
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
r
s
t
u
v
w
x
roswrap
src
rossimu
melodic
include
tf2_ros
buffer_server.h
Go to the documentation of this file.
1
#include "
sick_scan/sick_scan_base.h
"
/* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2
/*********************************************************************
3
*
4
* Software License Agreement (BSD License)
5
*
6
* Copyright (c) 2009, Willow Garage, Inc.
7
* All rights reserved.
8
*
9
* Redistribution and use in source and binary forms, with or without
10
* modification, are permitted provided that the following conditions
11
* are met:
12
*
13
* * Redistributions of source code must retain the above copyright
14
* notice, this list of conditions and the following disclaimer.
15
* * Redistributions in binary form must reproduce the above
16
* copyright notice, this list of conditions and the following
17
* disclaimer in the documentation and/or other materials provided
18
* with the distribution.
19
* * Neither the name of Willow Garage, Inc. nor the names of its
20
* contributors may be used to endorse or promote products derived
21
* from this software without specific prior written permission.
22
*
23
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34
* POSSIBILITY OF SUCH DAMAGE.
35
*
36
* Author: Eitan Marder-Eppstein
37
*********************************************************************/
38
#ifndef TF2_ROS_BUFFER_SERVER_H_
39
#define TF2_ROS_BUFFER_SERVER_H_
40
41
#include <
actionlib/server/action_server.h
>
42
#include <tf2_msgs/LookupTransformAction.h>
43
#include <
geometry_msgs/TransformStamped.h
>
44
#include <tf2_ros/buffer.h>
45
46
namespace
tf2_ros
47
{
53
class
BufferServer
54
{
55
private
:
56
typedef
actionlib::ActionServer<tf2_msgs::LookupTransformAction>
LookupTransformServer
;
57
typedef
LookupTransformServer::GoalHandle
GoalHandle
;
58
59
struct
GoalInfo
60
{
61
GoalHandle
handle
;
62
ros::Time
end_time
;
63
};
64
65
public
:
72
BufferServer
(
const
Buffer& buffer,
const
std::string& ns,
73
bool
auto_start =
true
,
ros::Duration
check_period =
ros::Duration
(0.01));
74
77
void
start
();
78
79
private
:
80
void
goalCB
(
GoalHandle
gh);
81
void
cancelCB
(
GoalHandle
gh);
82
void
checkTransforms
(
const
ros::TimerEvent
& e);
83
bool
canTransform
(
GoalHandle
gh);
84
geometry_msgs::TransformStamped
lookupTransform
(
GoalHandle
gh);
85
86
const
Buffer&
buffer_
;
87
LookupTransformServer
server_
;
88
std::list<GoalInfo>
active_goals_
;
89
std::mutex
mutex_
;
90
ros::Timer
check_timer_
;
91
};
92
}
93
#endif
actionlib::ActionServer< tf2_msgs::LookupTransformAction >
tf2_ros::BufferServer::active_goals_
std::list< GoalInfo > active_goals_
Definition:
buffer_server.h:88
tf2_ros::BufferServer::server_
LookupTransformServer server_
Definition:
buffer_server.h:87
tf2_ros::BufferServer::goalCB
void goalCB(GoalHandle gh)
tf2_ros::BufferServer::BufferServer
BufferServer(const Buffer &buffer, const std::string &ns, bool auto_start=true, ros::Duration check_period=ros::Duration(0.01))
tf2_ros::BufferServer::GoalInfo::handle
GoalHandle handle
Definition:
buffer_server.h:61
tf2_ros
tf2_ros::BufferServer::mutex_
boost::mutex mutex_
tf2_ros::BufferServer::canTransform
bool canTransform(GoalHandle gh)
tf2_ros::BufferServer::cancelCB
void cancelCB(GoalHandle gh)
tf2_ros::BufferServer::checkTransforms
void checkTransforms(const ros::TimerEvent &e)
ros::TimerEvent
tf2_ros::BufferServer::start
void start()
action_server.h
tf2_ros::BufferServer::GoalHandle
LookupTransformServer::GoalHandle GoalHandle
actionlib::ActionServer< tf2_msgs::LookupTransformAction >::GoalHandle
ServerGoalHandle< ActionSpec > GoalHandle
tf2_ros::BufferServer::check_timer_
ros::Timer check_timer_
Definition:
buffer_server.h:90
tf2_ros::BufferServer::lookupTransform
geometry_msgs::TransformStamped lookupTransform(GoalHandle gh)
ros::Time
TransformStamped.h
tf2_ros::BufferServer::buffer_
const Buffer & buffer_
Definition:
buffer_server.h:86
sick_scan_base.h
ros::Duration
geometry_msgs::TransformStamped_
Definition:
TransformStamped.h:25
ros::Timer
tf2_ros::BufferServer::GoalInfo::end_time
ros::Time end_time
Definition:
buffer_server.h:62
tf2_ros::BufferServer::LookupTransformServer
actionlib::ActionServer< tf2_msgs::LookupTransformAction > LookupTransformServer
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof
, Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07