src
simple_server_node.cpp
Go to the documentation of this file.
1
/*
2
* Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3
*
4
* Redistribution and use in source and binary forms, with or without
5
* modification, are permitted provided that the following conditions
6
* are met:
7
*
8
* 1. Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
*
11
* 2. Redistributions in binary form must reproduce the above
12
* copyright notice, this list of conditions and the following
13
* disclaimer in the documentation and/or other materials provided
14
* with the distribution.
15
*
16
* 3. Neither the name of the copyright holder nor the names of its
17
* contributors may be used to endorse or promote products derived
18
* from this software without specific prior written permission.
19
*
20
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31
* POSSIBILITY OF SUCH DAMAGE.
32
*
33
* simple_server_node.cpp
34
*
35
* authors:
36
* Sebastian Pütz <spuetz@uni-osnabrueck.de>
37
* Jorge Santos Simón <santos@magazino.eu>
38
*
39
*/
40
41
#include "
mbf_simple_nav/simple_navigation_server.h
"
42
#include <
mbf_utility/types.h
>
43
#include <
tf2_ros/transform_listener.h
>
44
45
int
main
(
int
argc,
char
**argv)
46
{
47
ros::init
(argc, argv,
"mbf_simple_server"
);
48
49
typedef
boost::shared_ptr<mbf_simple_nav::SimpleNavigationServer>
SimpleNavigationServerPtr;
50
51
ros::NodeHandle
nh;
52
ros::NodeHandle
private_nh(
"~"
);
53
54
double
cache_time;
55
private_nh.
param
(
"tf_cache_time"
, cache_time, 10.0);
56
57
#ifdef USE_OLD_TF
58
TFPtr
tf_listener_ptr(
new
TF
(nh,
ros::Duration
(cache_time),
true
));
59
#else
60
TFPtr
tf_listener_ptr(
new
TF
(
ros::Duration
(cache_time)));
61
tf2_ros::TransformListener
tf_listener(*tf_listener_ptr);
62
#endif
63
64
SimpleNavigationServerPtr controller_ptr(
65
new
mbf_simple_nav::SimpleNavigationServer
(tf_listener_ptr));
66
67
ros::spin
();
68
return
EXIT_SUCCESS;
69
}
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tf2_ros::TransformListener
simple_navigation_server.h
mbf_simple_nav::SimpleNavigationServer
The SimpleNavigationServer provides a simple navigation server, which does not bind a map representat...
Definition:
simple_navigation_server.h:63
transform_listener.h
tf::TransformListener
ros::NodeHandle::param
T param(const std::string ¶m_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
types.h
main
int main(int argc, char **argv)
Definition:
simple_server_node.cpp:45
ros::Duration
ros::NodeHandle
mbf_simple_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:58