octomap_types.h
Go to the documentation of this file.
1 /*
2  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
3  * http://octomap.github.com/
4  *
5  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
6  * All rights reserved.
7  * License: New BSD
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions 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 copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the University of Freiburg nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef OCTOMAP_TYPES_H
35 #define OCTOMAP_TYPES_H
36 
37 #include <stdio.h>
38 #include <vector>
39 #include <list>
40 
41 #include <octomap/math/Vector3.h>
42 #include <octomap/math/Pose6D.h>
44 
45 namespace octomap {
46 
51 
52  typedef std::vector<octomath::Vector3> point3d_collection;
53  typedef std::list<octomath::Vector3> point3d_list;
54 
56  typedef std::pair<point3d, double> OcTreeVolume;
57 
58 }
59 
60  //Macros for compiling with an without ROS (for output logging)
61  #ifdef OCTOMAP_ROS
62  #include <ros/ros.h>
63 
64  #define OCTOMAP_DEBUG ROS_DEBUG
65  #define OCTOMAP_DEBUG_STR ROS_DEBUG_STREAM
66  #define OCTOMAP_WARNING ROS_WARN
67  #define OCTOMAP_WARNING_STR ROS_WARN_STREAM
68  #define OCTOMAP_ERROR ROS_ERROR
69  #define OCTOMAP_ERROR_STR ROS_ERROR_STREAM
70 
71  #else
72  // no debug output if not in debug mode:
73  #ifdef NDEBUG
74  #ifndef OCTOMAP_NODEBUGOUT
75  #define OCTOMAP_NODEBUGOUT
76  #endif
77  #endif
78 
79  #ifdef OCTOMAP_NODEBUGOUT
80  #define OCTOMAP_DEBUG(...) (void)0
81  #define OCTOMAP_DEBUG_STR(...) (void)0
82  #else
83  #define OCTOMAP_DEBUG(...) fprintf(stderr, __VA_ARGS__), fflush(stderr)
84  #define OCTOMAP_DEBUG_STR(args) std::cerr << args << std::endl
85  #endif
86 
87  #define OCTOMAP_WARNING(...) fprintf(stderr, "WARNING: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
88  #define OCTOMAP_WARNING_STR(args) std::cerr << "WARNING: " << args << std::endl
89  #define OCTOMAP_ERROR(...) fprintf(stderr, "ERROR: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
90  #define OCTOMAP_ERROR_STR(args) std::cerr << "ERROR: " << args << std::endl
91  #endif
92 
93 
94 #endif
std::pair< point3d, double > OcTreeVolume
A voxel defined by its center point3d and its side length.
Definition: octomap_types.h:56
std::vector< octomath::Vector3 > point3d_collection
Definition: octomap_types.h:52
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
std::list< octomath::Vector3 > point3d_list
Definition: octomap_types.h:53
This class represents a three-dimensional vector.
Definition: Vector3.h:50
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:48
octomath::Pose6D pose6d
Use our Pose6D (float precision) as pose6d in octomap.
Definition: octomap_types.h:50


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Jun 10 2019 14:00:13