Skip to content

Commit

Permalink
Implement padding-free PointXYZI (#438)
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu authored Feb 19, 2025
1 parent 3e3e2d1 commit 80b37a0
Show file tree
Hide file tree
Showing 10 changed files with 69 additions and 3 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ Changelog
the topic can be turned on/off by including the token ``TLM`` in the flag ``proc_mask`` launch arg.
* Add a new launch file parameter ``min_scan_valid_columns_ratio`` to allow users to set the minimum
ratio of valid columns in a scan for it to be processed. Default value is ``0.0``.
* Add a padding-free point type of ``PointXYZI`` under ``ouster_ros`` namespace contrary to the pcl
version ``pcl::PointXYZI`` for bandwith sensitive applications.


ouster_ros v0.13.0
Expand Down
53 changes: 53 additions & 0 deletions include/ouster_ros/common_point_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,52 @@ namespace ouster_ros {
representation that we readily support.
*/

/*
* Same as Apollo point cloud type
* @remark XYZIT point type is not compatible with RNG15_RFL8_NIR8/LOW_DATA
* udp lidar profile.
*/
struct EIGEN_ALIGN16 _Ouster_PointXYZI {
union EIGEN_ALIGN16 {
float data[4];
struct {
float x;
float y;
float z;
float intensity;
};
};
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

struct PointXYZI : public _Ouster_PointXYZI {

inline PointXYZI(const _Ouster_PointXYZI& pt)
{
x = pt.x; y = pt.y; z = pt.z;
intensity = pt.intensity;
}

inline PointXYZI()
{
x = y = z = 0.0f; data[3] = 1.0f;
intensity = 0.0f;
}

inline const auto as_tuple() const {
return std::tie(x, y, z, intensity);
}

inline auto as_tuple() {
return std::tie(x, y, z, intensity);
}

template<size_t I>
inline auto& get() {
return std::get<I>(as_tuple());
}
};

/*
* Same as Velodyne point cloud type
* @remark XYZIR point type is not compatible with RNG15_RFL8_NIR8/LOW_DATA
Expand Down Expand Up @@ -60,6 +106,13 @@ struct PointXYZIR : public _PointXYZIR {

// clang-format off

POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::PointXYZI,
(float, x, x)
(float, y, y)
(float, z, z)
(float, intensity, intensity)
)

/* common point types */
POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::PointXYZIR,
(float, x, x)
Expand Down
3 changes: 2 additions & 1 deletion launch/common.launch
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@
native,
xyz,
xyzi,
xyzir
o_xyzi,
xyzir,
}"/>

<arg name="organized" doc="generate an organzied point cloud"/>
Expand Down
1 change: 1 addition & 0 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@
native,
xyz,
xyzi,
o_xyzi,
xyzir
}"/>

Expand Down
1 change: 1 addition & 0 deletions launch/record.launch
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@
native,
xyz,
xyzi,
o_xyzi,
xyzir
}"/>

Expand Down
1 change: 1 addition & 0 deletions launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@
native,
xyz,
xyzi,
o_xyzi,
xyzir
}"/>

Expand Down
1 change: 1 addition & 0 deletions launch/sensor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@
native,
xyz,
xyzi,
o_xyzi,
xyzir
}"/>

Expand Down
1 change: 1 addition & 0 deletions launch/sensor_mtp.launch
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@
native,
xyz,
xyzi,
o_xyzi,
xyzir
}"/>

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>ouster_ros</name>
<version>0.13.4</version>
<version>0.13.5</version>
<description>Ouster ROS driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
7 changes: 6 additions & 1 deletion src/point_cloud_processor_factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class PointCloudProcessorFactory {
public:
static bool point_type_requires_intensity(const std::string& point_type) {
return point_type == "xyzi" || point_type == "xyzir" ||
point_type == "original";
point_type == "original" || point_type == "o_xyzi";
}

static bool profile_has_intensity(UDPProfileLidar profile) {
Expand Down Expand Up @@ -189,6 +189,11 @@ class PointCloudProcessorFactory {
info, frame, apply_lidar_to_sensor_transform,
organized, destagger, min_range, max_range, rows_step,
post_processing_fn);
} else if (point_type == "o_xyzi") {
return make_point_cloud_processor<ouster_ros::PointXYZI>(
info, frame, apply_lidar_to_sensor_transform,
organized, destagger, min_range, max_range, rows_step,
post_processing_fn);
} else if (point_type == "xyzir") {
return make_point_cloud_processor<PointXYZIR>(
info, frame, apply_lidar_to_sensor_transform,
Expand Down

0 comments on commit 80b37a0

Please sign in to comment.