Skip to content

Commit

Permalink
fix code style for roslint
Browse files Browse the repository at this point in the history
  • Loading branch information
spuetz authored and JWhitleyWork committed Dec 4, 2022
1 parent 9e23c8c commit e81f532
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 25 deletions.
11 changes: 8 additions & 3 deletions velodyne_pointcloud/include/velodyne_pointcloud/convert.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#define VELODYNE_POINTCLOUD_CONVERT_H

#include <string>
#include <utility>
#include <map>

#include <ros/ros.h>
#include <diagnostic_updater/diagnostic_updater.h>
Expand Down Expand Up @@ -76,22 +78,25 @@ class Convert

bool container_configured_ = false;

enum Container{
enum Container
{
PointCloudXYZIR,
PointCloudXYZIRT,
OrganizedPointCloudXYZIR,
OrganizedPointCloudXYZIRT
};

std::map<std::string, Container> container_names_{
std::map<std::string, Container> container_names_
{
{"PointCloudXYZIR", Container::PointCloudXYZIR},
{"PointCloudXYZIRT", Container::PointCloudXYZIRT},
{"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR},
{"OrganizedPointCloudXYZIRT", Container::OrganizedPointCloudXYZIRT}
};

const std::pair<std::string, uint8_t> default_container_ = {"PointCloudXYZIR", PointCloudXYZIR};
const std::pair<std::string, uint8_t> default_organized_container_ = {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR};
const std::pair<std::string, uint8_t> default_organized_container_ =
{"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR};

boost::shared_ptr<velodyne_rawdata::DataContainerBase> getContainer(uint8_t container_id);

Expand Down
30 changes: 15 additions & 15 deletions velodyne_pointcloud/include/velodyne_pointcloud/point_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <pcl/point_types.h>

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,
Expand All @@ -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
20 changes: 13 additions & 7 deletions velodyne_pointcloud/include/velodyne_pointcloud/transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@
#define VELODYNE_POINTCLOUD_TRANSFORM_H

#include <string>
#include <utility>
#include <map>

#include <ros/ros.h>
#include "tf/message_filter.h"
#include "message_filters/subscriber.h"
Expand Down Expand Up @@ -85,22 +88,25 @@ class Transform

bool container_configured_ = false;

enum Container{
enum Container
{
PointCloudXYZIR,
PointCloudXYZIRT,
OrganizedPointCloudXYZIR,
OrganizedPointCloudXYZIRT
};

std::map<std::string, Container> container_names_{
{"PointCloudXYZIR", Container::PointCloudXYZIR},
{"PointCloudXYZIRT", Container::PointCloudXYZIRT},
{"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR},
{"OrganizedPointCloudXYZIRT", Container::OrganizedPointCloudXYZIRT}
std::map<std::string, Container> container_names_
{
{"PointCloudXYZIR", Container::PointCloudXYZIR},
{"PointCloudXYZIRT", Container::PointCloudXYZIRT},
{"OrganizedPointCloudXYZIR", Container::OrganizedPointCloudXYZIR},
{"OrganizedPointCloudXYZIRT", Container::OrganizedPointCloudXYZIRT}
};

const std::pair<std::string, uint8_t> default_container_ = {"PointCloudXYZIR", PointCloudXYZIR};
const std::pair<std::string, uint8_t> default_organized_container_ = {"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR};
const std::pair<std::string, uint8_t> default_organized_container_ =
{"OrganizedPointCloudXYZIR", OrganizedPointCloudXYZIR};

boost::shared_ptr<velodyne_rawdata::DataContainerBase> getContainer(uint8_t container_id);

Expand Down

0 comments on commit e81f532

Please sign in to comment.