Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use compatible structs for velodyne_pointcloud::PointXYZ* and autoware_point_types::PointXYZ* types #43

Open
VRichardJP opened this issue Jun 2, 2023 · 0 comments

Comments

@VRichardJP
Copy link

VRichardJP commented Jun 2, 2023

velodyne_pointcloud and autoware_point_types don't define the same point types:

struct PointXYZIR
{
PCL_ADD_POINT4D;
float intensity;
uint16_t ring;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
struct PointXYZIRADT
{
PCL_ADD_POINT4D;
float intensity;
uint16_t ring;
float azimuth;
float distance;
uint8_t return_type;
double time_stamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;

https://github.com/autowarefoundation/autoware.universe/blob/main/common/autoware_point_types/include/autoware_point_types/types.hpp

This has caused some issues in the past, but also it makes reading/writing PointCloud2 message data painful and slow.

I don't think there is any advantage to keep incompatible types. It would be better if velodyne_pointcloud was using the types defined by autoware_point_types.

If we are not willing to have velodyne_pointcloud depending on autoware_point_types package, at least the velodyne_pointcloud::PointXYZIR and velodyne_pointcloud::PointXYZIRADT types could be re-written to have "compatible layouts". For example:

struct PointXYZIR
{
  float x;
  float y;
  float z;
  float intensity;
  uint16_t ring;
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;

struct PointXYZIRADT
{
  float x;
  float y;
  float z;
  float intensity;
  uint16_t ring;
  float azimuth;
  float distance;
  uint8_t return_type;
  double time_stamp;
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;

Or the other way around: to have autoware_point_types types modified so that they would have the same layout than velodyne_pointcloud. Actually, it makes maybe more sense that way, because PCL operations rely a lot on the padding after xyz fields.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant