diff --git a/CMakeLists.txt b/CMakeLists.txt
index 25d0dd8..17dbf6a 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,7 +7,6 @@ if(NOT CMAKE_CXX_STANDARD)
endif()
find_package(ament_cmake REQUIRED)
-find_package(ament_cmake_pytest REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
@@ -71,7 +70,6 @@ if(BUILD_TESTING)
ament_uncrustify()
find_package(ament_cmake_gtest REQUIRED)
- find_package(ament_cmake_gmock REQUIRED)
ament_add_gtest(projection_test
test/projection_test.cpp
@@ -80,10 +78,24 @@ if(BUILD_TESTING)
target_link_libraries(projection_test laser_geometry)
endif()
+ # Python test
+ # Provides PYTHON_EXECUTABLE_DEBUG
+ find_package(python_cmake_module REQUIRED)
+ find_package(PythonExtra REQUIRED)
+
+ set(_PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}")
+ if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug")
+ set(PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}")
+ endif()
+
+ find_package(ament_cmake_pytest REQUIRED)
+
ament_add_pytest_test(projection test/projection_test.py
TIMEOUT 120
- WERROR ON
+ PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}"
)
+
+ set(PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}")
endif()
ament_package()
diff --git a/package.xml b/package.xml
index 2b4a48d..7e93dca 100644
--- a/package.xml
+++ b/package.xml
@@ -24,7 +24,6 @@
http://ros.org/wiki/laser_geometry
ament_cmake
- ament_cmake_pytest
eigen3_cmake_module
eigen3_cmake_module
@@ -36,20 +35,20 @@
eigen
+ python3-numpy
rclcpp
+ rclpy
sensor_msgs
+ sensor_msgs_py
tf2
- ament_cmake
-
ament_cmake_cppcheck
ament_cmake_cpplint
ament_cmake_gtest
- ament_cmake_gmock
ament_cmake_lint_cmake
+ ament_cmake_pytest
ament_cmake_uncrustify
- rclpy
- sensor_msgs_py
+ python_cmake_module
ament_cmake
diff --git a/pytest.ini b/pytest.ini
new file mode 100644
index 0000000..eded8a3
--- /dev/null
+++ b/pytest.ini
@@ -0,0 +1,3 @@
+; Needed to suppress warnings from pytest about the default junit_family
+[pytest]
+junit_family=xunit2
diff --git a/src/laser_geometry/laser_geometry.py b/src/laser_geometry/laser_geometry.py
index 227e1ff..7c9cb07 100644
--- a/src/laser_geometry/laser_geometry.py
+++ b/src/laser_geometry/laser_geometry.py
@@ -38,11 +38,11 @@ class LaserProjection:
"""
A class to Project Laser Scan
- This calls will project laser scans into point clouds. It caches
+ This class will project laser scans into point clouds. It caches
unit vectors between runs (provided the angular resolution of
your scanner is not changing) to avoid excess computation.
- By default all range values less thatn the scanner min_range,
+ By default all range values less than the scanner min_range or
greater than the scanner max_range are removed from the generated
point cloud, as these are assumed to be invalid.
diff --git a/test/projection_test.py b/test/projection_test.py
index 0b16d39..21ac4e1 100755
--- a/test/projection_test.py
+++ b/test/projection_test.py
@@ -44,10 +44,10 @@ def test_project_laser():
tolerance = 6 # decimal places
projector = LaserProjection()
- ranges = [-1.0, 1.0, 2.0, 3.0, 4.0, 5.0, 100.0]
- intensities = np.arange(1.0, 6.0).tolist()
+ ranges = [-1.0, 1.0, 5.0, 100.0]
+ intensities = np.arange(1.0, 4.0).tolist()
- min_angles = -np.pi / np.array([1.0, 1.5, 2.0, 4.0, 8.0])
+ min_angles = -np.pi / np.array([1.0, 1.5, 8.0])
max_angles = -min_angles
angle_increments = np.pi / np.array([180., 360., 720.])
@@ -65,32 +65,6 @@ def test_project_laser():
except BuildScanException:
assert (angle_max - angle_min)/angle_increment <= 0
- cloud_out = projector.projectLaser(scan, -1.0,
- LaserProjection.ChannelOption.INDEX)
- assert len(cloud_out.fields) == 4, \
- "PointCloud2 with channel INDEX: fields size != 4"
-
- cloud_out = projector.projectLaser(scan, -1.0,
- LaserProjection.ChannelOption.INTENSITY)
- assert len(cloud_out.fields) == 4, \
- "PointCloud2 with channel INDEX: fields size != 4"
-
- cloud_out = projector.projectLaser(scan, -1.0)
- assert len(cloud_out.fields) == 5, \
- "PointCloud2 with channel INDEX: fields size != 5"
- cloud_out = projector.projectLaser(scan, -1.0,
- LaserProjection.ChannelOption.INTENSITY |
- LaserProjection.ChannelOption.INDEX)
- assert len(cloud_out.fields) == 5, \
- "PointCloud2 with channel INDEX: fields size != 5"
-
- cloud_out = projector.projectLaser(scan, -1.0,
- LaserProjection.ChannelOption.INTENSITY |
- LaserProjection.ChannelOption.INDEX |
- LaserProjection.ChannelOption.DISTANCE)
- assert len(cloud_out.fields) == 6, \
- "PointCloud2 with channel INDEX: fields size != 6"
-
cloud_out = projector.projectLaser(scan, -1.0,
LaserProjection.ChannelOption.INTENSITY |
LaserProjection.ChannelOption.INDEX |
@@ -153,4 +127,3 @@ def test_project_laser():
if __name__ == '__main__':
pytest.main()
-