diff --git a/velodyne_pointcloud/CMakeLists.txt b/velodyne_pointcloud/CMakeLists.txt index 2a6757f74..6d38d4894 100644 --- a/velodyne_pointcloud/CMakeLists.txt +++ b/velodyne_pointcloud/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(message_filters REQUIRED) find_package(PCL REQUIRED COMPONENTS common) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) +find_package(rosidl_cmake REQUIRED) find_package(sensor_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) @@ -73,9 +74,11 @@ target_link_libraries(velodyne_cloud_types PUBLIC tf2_ros::tf2_ros ${velodyne_msgs_TARGETS} ) - add_library(transform SHARED src/conversions/transform.cpp) +if(${rosidl_cmake_VERSION} VERSION_EQUAL 4.0.1) + target_compile_definitions(transform PUBLIC ROS2_IRON) +endif() target_include_directories(transform PUBLIC "$" "$") diff --git a/velodyne_pointcloud/include/velodyne_pointcloud/transform.hpp b/velodyne_pointcloud/include/velodyne_pointcloud/transform.hpp index 1f7ef7b04..4ce55b804 100644 --- a/velodyne_pointcloud/include/velodyne_pointcloud/transform.hpp +++ b/velodyne_pointcloud/include/velodyne_pointcloud/transform.hpp @@ -32,8 +32,9 @@ #ifndef VELODYNE_POINTCLOUD__TRANSFORM_HPP_ #define VELODYNE_POINTCLOUD__TRANSFORM_HPP_ - +#ifdef ROS2_IRON #include +#endif #include #include #include @@ -43,6 +44,9 @@ #include #include +#ifndef ROS2_IRON +#include +#endif #include #include #include diff --git a/velodyne_pointcloud/package.xml b/velodyne_pointcloud/package.xml index 6c705b7db..49a0d539d 100644 --- a/velodyne_pointcloud/package.xml +++ b/velodyne_pointcloud/package.xml @@ -16,6 +16,7 @@ Andreas Klintberg ament_cmake + rosidl_cmake angles diagnostic_updater diff --git a/velodyne_pointcloud/src/lib/rawdata.cpp b/velodyne_pointcloud/src/lib/rawdata.cpp index 15f116bba..c60332f88 100644 --- a/velodyne_pointcloud/src/lib/rawdata.cpp +++ b/velodyne_pointcloud/src/lib/rawdata.cpp @@ -328,6 +328,8 @@ void RawData::unpack( float time = 0; if (timing_offsets_.size()) { time = timing_offsets_[i][j] + time_diff_start_to_this_packet; + } else { + time = time_diff_start_to_this_packet; } if (tmp.uint == 0) { // no valid laser beam return @@ -546,6 +548,8 @@ void RawData::unpack_vls128( if (timing_offsets_.size()) { time = timing_offsets_[block / 4][firing_order + laser_number / 64] + time_diff_start_to_this_packet; + } else { + time = time_diff_start_to_this_packet; } velodyne_pointcloud::LaserCorrection & corrections = @@ -811,6 +815,8 @@ void RawData::unpack_vlp16( float time = 0; if (timing_offsets_.size()) { time = timing_offsets_[block][firing * 16 + dsr] + time_diff_start_to_this_packet; + } else { + time = time_diff_start_to_this_packet; } data.addPoint(