Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion velodyne_pointcloud/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,9 @@

#ifndef VELODYNE_POINTCLOUD__TRANSFORM_HPP_
#define VELODYNE_POINTCLOUD__TRANSFORM_HPP_

#ifdef ROS2_IRON
#include <message_filters/subscriber.h>
#endif
#include <tf2_ros/buffer.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_listener.h>
Expand All @@ -43,6 +44,9 @@

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#ifndef ROS2_IRON
#include <message_filters/subscriber.hpp>
#endif
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>
Expand Down
1 change: 1 addition & 0 deletions velodyne_pointcloud/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<author>Andreas Klintberg</author>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_cmake</build_depend>

<depend>angles</depend>
<depend>diagnostic_updater</depend>
Expand Down
6 changes: 6 additions & 0 deletions velodyne_pointcloud/src/lib/rawdata.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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 =
Expand Down Expand Up @@ -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(
Expand Down