diff --git a/velodyne_pointcloud/include/velodyne_pointcloud/convert.h b/velodyne_pointcloud/include/velodyne_pointcloud/convert.h index dccf323b6..a6a8d1e97 100644 --- a/velodyne_pointcloud/include/velodyne_pointcloud/convert.h +++ b/velodyne_pointcloud/include/velodyne_pointcloud/convert.h @@ -40,6 +40,8 @@ #define VELODYNE_POINTCLOUD_CONVERT_H #include +#include +#include #include #include @@ -76,14 +78,16 @@ class Convert bool container_configured_ = false; - enum Container{ + enum Container + { PointCloudXYZIR, PointCloudXYZIRT, OrganizedPointCloudXYZIR, OrganizedPointCloudXYZIRT }; - std::map container_names_{ + std::map container_names_ + { {"PointCloudXYZIR", Container::PointCloudXYZIR}, {"PointCloudXYZIRT", Container::PointCloudXYZIRT}, {"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR}, @@ -91,7 +95,8 @@ class Convert }; const std::pair default_container_ = {"PointCloudXYZIR", PointCloudXYZIR}; - const std::pair default_organized_container_ = {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR}; + const std::pair default_organized_container_ = + {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR}; boost::shared_ptr getContainer(uint8_t container_id); diff --git a/velodyne_pointcloud/include/velodyne_pointcloud/point_types.h b/velodyne_pointcloud/include/velodyne_pointcloud/point_types.h index 62a8fee61..613be32fd 100644 --- a/velodyne_pointcloud/include/velodyne_pointcloud/point_types.h +++ b/velodyne_pointcloud/include/velodyne_pointcloud/point_types.h @@ -16,25 +16,26 @@ * @author Piyush Khandelwal */ -#ifndef __VELODYNE_POINTCLOUD_POINT_TYPES_H -#define __VELODYNE_POINTCLOUD_POINT_TYPES_H +#ifndef VELODYNE_POINTCLOUD_POINT_TYPES_H +#define VELODYNE_POINTCLOUD_POINT_TYPES_H #include namespace velodyne_pointcloud { - /** Euclidean Velodyne coordinate, including intensity and ring number. */ - struct PointXYZIR - { - float x; ///< x coord - float y; ///< y coord - float z; ///< z coord - float intensity; ///< laser intensity reading - uint16_t ring; ///< laser ring number - EIGEN_MAKE_ALIGNED_OPERATOR_NEW // ensure proper alignment - } EIGEN_ALIGN16; +/** Euclidean Velodyne coordinate, including intensity and ring number. */ +struct PointXYZIR +{ + float x; ///< x coord + float y; ///< y coord + float z; ///< z coord + float intensity; ///< laser intensity reading + uint16_t ring; ///< laser ring number + EIGEN_MAKE_ALIGNED_OPERATOR_NEW // ensure proper alignment +} +EIGEN_ALIGN16; -}; // namespace velodyne_pointcloud +}; // namespace velodyne_pointcloud POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_pointcloud::PointXYZIR, @@ -44,5 +45,4 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_pointcloud::PointXYZIR, (float, intensity, intensity) (uint16_t, ring, ring)) -#endif // __VELODYNE_POINTCLOUD_POINT_TYPES_H - +#endif // VELODYNE_POINTCLOUD_POINT_TYPES_H diff --git a/velodyne_pointcloud/include/velodyne_pointcloud/transform.h b/velodyne_pointcloud/include/velodyne_pointcloud/transform.h index 92c17ea3a..5a7ec4a59 100644 --- a/velodyne_pointcloud/include/velodyne_pointcloud/transform.h +++ b/velodyne_pointcloud/include/velodyne_pointcloud/transform.h @@ -41,6 +41,9 @@ #define VELODYNE_POINTCLOUD_TRANSFORM_H #include +#include +#include + #include #include "tf/message_filter.h" #include "message_filters/subscriber.h" @@ -85,22 +88,25 @@ class Transform bool container_configured_ = false; - enum Container{ + enum Container + { PointCloudXYZIR, PointCloudXYZIRT, OrganizedPointCloudXYZIR, OrganizedPointCloudXYZIRT }; - std::map container_names_{ - {"PointCloudXYZIR", Container::PointCloudXYZIR}, - {"PointCloudXYZIRT", Container::PointCloudXYZIRT}, - {"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR}, - {"OrganizedPointCloudXYZIRT", Container::OrganizedPointCloudXYZIRT} + std::map container_names_ + { + {"PointCloudXYZIR", Container::PointCloudXYZIR}, + {"PointCloudXYZIRT", Container::PointCloudXYZIRT}, + {"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR}, + {"OrganizedPointCloudXYZIRT", Container::OrganizedPointCloudXYZIRT} }; const std::pair default_container_ = {"PointCloudXYZIR", PointCloudXYZIR}; - const std::pair default_organized_container_ = {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR}; + const std::pair default_organized_container_ = + {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR}; boost::shared_ptr getContainer(uint8_t container_id);