Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef OCTOMAP_TYPES_H
00035 #define OCTOMAP_TYPES_H
00036
00037 #include <stdio.h>
00038 #include <vector>
00039 #include <list>
00040
00041 #include <octomap/math/Vector3.h>
00042 #include <octomap/math/Pose6D.h>
00043 #include <octomap/octomap_deprecated.h>
00044
00045 namespace octomap {
00046
00048 typedef octomath::Vector3 point3d;
00050 typedef octomath::Pose6D pose6d;
00051
00052 typedef std::vector<octomath::Vector3> point3d_collection;
00053 typedef std::list<octomath::Vector3> point3d_list;
00054
00056 typedef std::pair<point3d, double> OcTreeVolume;
00057
00058 }
00059
00060
00061 #ifdef OCTOMAP_ROS
00062 #include <ros/ros.h>
00063
00064 #define OCTOMAP_DEBUG ROS_DEBUG
00065 #define OCTOMAP_DEBUG_STR ROS_DEBUG_STREAM
00066 #define OCTOMAP_WARNING ROS_WARN
00067 #define OCTOMAP_WARNING_STR ROS_WARN_STREAM
00068 #define OCTOMAP_ERROR ROS_ERROR
00069 #define OCTOMAP_ERROR_STR ROS_ERROR_STREAM
00070
00071 #else
00072
00073 #ifdef NDEBUG
00074 #ifndef OCTOMAP_NODEBUGOUT
00075 #define OCTOMAP_NODEBUGOUT
00076 #endif
00077 #endif
00078
00079 #ifdef OCTOMAP_NODEBUGOUT
00080 #define OCTOMAP_DEBUG(...) (void)0
00081 #define OCTOMAP_DEBUG_STR(...) (void)0
00082 #else
00083 #define OCTOMAP_DEBUG(...) fprintf(stderr, __VA_ARGS__), fflush(stderr)
00084 #define OCTOMAP_DEBUG_STR(args) std::cerr << args << std::endl
00085 #endif
00086
00087 #define OCTOMAP_WARNING(...) fprintf(stderr, "WARNING: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
00088 #define OCTOMAP_WARNING_STR(args) std::cerr << "WARNING: " << args << std::endl
00089 #define OCTOMAP_ERROR(...) fprintf(stderr, "ERROR: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
00090 #define OCTOMAP_ERROR_STR(args) std::cerr << "ERROR: " << args << std::endl
00091 #endif
00092
00093
00094 #endif