Skip to content

Commit cca2e89

Browse files
committed
{humble} laser-geometry: Refresh patch
Remove code block that was merged upstream. Signed-off-by: Rob Woolley <[email protected]>
1 parent a4c362a commit cca2e89

File tree

1 file changed

+12
-23
lines changed

1 file changed

+12
-23
lines changed

meta-ros2-humble/recipes-bbappends/laser-geometry/laser-geometry/switch-to-target_link_libraries.patch

Lines changed: 12 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,11 @@ Signed-off-by: Chris Lalancette <[email protected]>
1717
src/laser_geometry.cpp | 36 +++++++++++++++++-------------------
1818
2 files changed, 30 insertions(+), 26 deletions(-)
1919

20-
diff --git a/CMakeLists.txt b/CMakeLists.txt
21-
index b4de5c6d..7cfcd033 100644
22-
--- a/CMakeLists.txt
23-
+++ b/CMakeLists.txt
24-
@@ -24,10 +24,18 @@ target_include_directories(laser_geometry
20+
Index: laser-geometry-2.4.1-1/CMakeLists.txt
21+
===================================================================
22+
--- laser-geometry-2.4.1-1.orig/CMakeLists.txt
23+
+++ laser-geometry-2.4.1-1/CMakeLists.txt
24+
@@ -23,10 +23,18 @@ target_include_directories(laser_geometr
2525
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
2626
${Eigen3_INCLUDE_DIRS}
2727
)
@@ -44,7 +44,7 @@ index b4de5c6d..7cfcd033 100644
4444
)
4545

4646
# Causes the visibility macros to use dllexport rather than dllimport,
47-
@@ -42,9 +50,7 @@ ament_export_libraries(laser_geometry)
47+
@@ -41,9 +49,7 @@ ament_export_libraries(laser_geometry)
4848
ament_export_targets(laser_geometry)
4949

5050
ament_export_dependencies(
@@ -54,7 +54,7 @@ index b4de5c6d..7cfcd033 100644
5454
sensor_msgs
5555
tf2
5656
)
57-
@@ -80,7 +86,7 @@ if(BUILD_TESTING)
57+
@@ -79,7 +85,7 @@ if(BUILD_TESTING)
5858
test/projection_test.cpp
5959
TIMEOUT 240)
6060
if(TARGET projection_test)
@@ -63,10 +63,10 @@ index b4de5c6d..7cfcd033 100644
6363
endif()
6464

6565
# Python test
66-
diff --git a/src/laser_geometry.cpp b/src/laser_geometry.cpp
67-
index d07b7c55..1693a25c 100644
68-
--- a/src/laser_geometry.cpp
69-
+++ b/src/laser_geometry.cpp
66+
Index: laser-geometry-2.4.1-1/src/laser_geometry.cpp
67+
===================================================================
68+
--- laser-geometry-2.4.1-1.orig/src/laser_geometry.cpp
69+
+++ laser-geometry-2.4.1-1/src/laser_geometry.cpp
7070
@@ -30,16 +30,14 @@
7171

7272
#include "laser_geometry/laser_geometry.hpp"
@@ -166,7 +166,7 @@ index d07b7c55..1693a25c 100644
166166
cloud_out.fields[field_size + 2].offset = offset;
167167
cloud_out.fields[field_size + 2].count = 1;
168168
offset += 4;
169-
@@ -330,7 +328,7 @@ void LaserProjection::transformLaserScanToPointCloud_(
169+
@@ -330,7 +328,7 @@ void LaserProjection::transformLaserScan
170170
memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
171171

172172
// Assume constant motion during the laser-scan and use slerp to compute intermediate transforms
@@ -175,14 +175,3 @@ index d07b7c55..1693a25c 100644
175175

176176
// TODO(anon): Make a function that performs both the slerp and linear interpolation needed to
177177
// interpolate a Full Transform (Quaternion + Vector)
178-
@@ -423,8 +421,8 @@ void LaserProjection::transformLaserScanToPointCloud_(
179-
double range_cutoff,
180-
int channel_options)
181-
{
182-
- TIME start_time = scan_in.header.stamp;
183-
- TIME end_time = scan_in.header.stamp;
184-
+ rclcpp::Time start_time = scan_in.header.stamp;
185-
+ rclcpp::Time end_time = scan_in.header.stamp;
186-
// TODO(anonymous): reconcile all the different time constructs
187-
if (!scan_in.ranges.empty()) {
188-
end_time = start_time + rclcpp::Duration::from_seconds(

0 commit comments

Comments
 (0)