diff --git a/CHANGELOG.rst b/CHANGELOG.rst index c2cf516d..0296597a 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -12,7 +12,8 @@ Changelog * [BUGFIX]: LaserScan is not properly aligned with generated point cloud * address an issue where LaserScan appeared different on FW prior to 2.4 * [BUGFIX]: LaserScan does not work when using dual mode -* [BUGFIX]: Implement lock free ring buffer with throttling +* [BUGFIX]: Implement lock free ring buffer with throttling to avoid generating partial frames +* add support for FUSA udp profile ``Point_FUSA_RNG15_RFL8_NIR8_DUAL`` ouster_ros v0.10.0 diff --git a/launch/driver.launch b/launch/driver.launch index 0cc23f05..0f6f1002 100644 --- a/launch/driver.launch +++ b/launch/driver.launch @@ -7,9 +7,10 @@ ouster_ros - 0.12.2 + 0.12.3 Ouster ROS driver ouster developers BSD diff --git a/src/os_driver_nodelet.cpp b/src/os_driver_nodelet.cpp index bfe84927..8f71217b 100644 --- a/src/os_driver_nodelet.cpp +++ b/src/os_driver_nodelet.cpp @@ -89,9 +89,11 @@ class OusterDriver : public OusterSensor { // warn about profile incompatibility if (PointCloudProcessorFactory::point_type_requires_intensity(point_type) && - info.format.udp_profile_lidar == UDPProfileLidar::PROFILE_RNG15_RFL8_NIR8) { + !PointCloudProcessorFactory::profile_has_intensity(info.format.udp_profile_lidar)) { NODELET_WARN_STREAM( - "selected point type '" << point_type << "' is not compatible with the current udp profile: RNG15_RFL8_NIR8"); + "selected point type '" << point_type + << "' is not compatible with the udp profile: " + << to_string(info.format.udp_profile_lidar)); } }