48 #ifndef OCTOMAP_TYPES_H
49 #define OCTOMAP_TYPES_H
79 #define OCTOMAP_DEBUG ROS_DEBUG
80 #define OCTOMAP_DEBUG_STR ROS_DEBUG_STREAM
81 #define OCTOMAP_WARNING ROS_WARN
82 #define OCTOMAP_WARNING_STR ROS_WARN_STREAM
83 #define OCTOMAP_ERROR ROS_ERROR
84 #define OCTOMAP_ERROR_STR ROS_ERROR_STREAM
89 #ifndef OCTOMAP_NODEBUGOUT
90 #define OCTOMAP_NODEBUGOUT
94 #ifdef OCTOMAP_NODEBUGOUT
95 #define OCTOMAP_DEBUG(...) (void)0
96 #define OCTOMAP_DEBUG_STR(...) (void)0
98 #define OCTOMAP_DEBUG(...) fprintf(stderr, __VA_ARGS__), fflush(stderr)
99 #define OCTOMAP_DEBUG_STR(args) std::cerr << args << std::endl
102 #define OCTOMAP_WARNING(...) fprintf(stderr, "WARNING: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
103 #define OCTOMAP_WARNING_STR(args) std::cerr << "WARNING: " << args << std::endl
104 #define OCTOMAP_ERROR(...) fprintf(stderr, "ERROR: "), fprintf(stderr, __VA_ARGS__), fflush(stderr)
105 #define OCTOMAP_ERROR_STR(args) std::cerr << "ERROR: " << args << std::endl
This class represents a tree-dimensional pose of an object.
OctoMap: A probabilistic, flexible, and compact 3D mapping library for robotic systems.
std::pair< point3d, double > OcTreeVolume
A voxel defined by its center point3d and its side length.
std::vector< octomath::Vector3 > point3d_collection
std::list< octomath::Vector3 > point3d_list
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
octomath::Pose6D pose6d
Use our Pose6D (float precision) as pose6d in octomap.
This class represents a three-dimensional vector.