buffer_server_main.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Wim Meeussen
36 *********************************************************************/
37 #include <tf2_ros/buffer_server.h>
39 #include <ros/ros.h>
40 
41 
42 class MyClass
43 {
44 public:
45  MyClass() {}
46  MyClass(double d) {}
47 };
48 
50 {
51 public:
53 };
54 
55 int main(int argc, char** argv)
56 {
57  ros::init(argc, argv, "tf_buffer");
58  ros::NodeHandle nh;
59 
60  double buffer_size;
61  nh.param("buffer_size", buffer_size, 120.0);
62 
63  // WIM: this works fine:
64  tf2_ros::Buffer buffer_core(ros::Duration(buffer_size+0)); // WTF??
65  tf2_ros::TransformListener listener(buffer_core);
66  tf2_ros::BufferServer buffer_server(buffer_core, "tf2_buffer_server", false);
67  buffer_server.start();
68  // But you should probably read this instead:
69  // http://www.informit.com/guides/content.aspx?g=cplusplus&seqNum=439
70 
71  ros::spin();
72 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
MyClass(double d)
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:51
Action server for the actionlib-based implementation of tf2_ros::BufferInterface. ...
Definition: buffer_server.h:52
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int main(int argc, char **argv)
This class provides an easy way to request and receive coordinate frame transform information...
void start()
Start the action server.


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Jun 7 2019 21:45:43