From 79dc1f848f274b0b09357f8ccebaa306aa7ba427 Mon Sep 17 00:00:00 2001 From: Wolfgang Hess Date: Thu, 4 May 2017 15:38:41 +0200 Subject: [PATCH] Remove 'laser' references from parameter names. (#259) Related to #250. --- .../io/outlier_removing_points_processor.cc | 4 +-- cartographer/kalman_filter/pose_tracker.h | 2 +- cartographer/mapping/trajectory_node.h | 6 ++-- .../mapping_2d/local_trajectory_builder.cc | 34 ++++++++----------- cartographer/mapping_2d/map_limits.h | 4 +-- .../local_trajectory_builder_options.proto | 17 +++++----- .../kalman_local_trajectory_builder.cc | 16 ++++----- .../kalman_local_trajectory_builder_test.cc | 21 ++++++------ .../local_trajectory_builder_options.cc | 10 +++--- .../optimizing_local_trajectory_builder.cc | 8 ++--- .../local_trajectory_builder_options.proto | 11 +++--- .../fast_correlative_scan_matcher.cc | 2 +- .../scan_matching/rotational_scan_matcher.cc | 13 ++++--- cartographer/sensor/collator_test.cc | 2 +- cartographer/sensor/compressed_point_cloud.cc | 6 ++-- configuration_files/trajectory_builder_2d.lua | 12 +++---- configuration_files/trajectory_builder_3d.lua | 10 +++--- docs/source/configuration.rst | 17 +++++----- 18 files changed, 93 insertions(+), 102 deletions(-) diff --git a/cartographer/io/outlier_removing_points_processor.cc b/cartographer/io/outlier_removing_points_processor.cc index 72481c2..0cec8d2 100644 --- a/cartographer/io/outlier_removing_points_processor.cc +++ b/cartographer/io/outlier_removing_points_processor.cc @@ -88,8 +88,8 @@ void OutlierRemovingPointsProcessor::ProcessInPhaseOne( void OutlierRemovingPointsProcessor::ProcessInPhaseTwo( const PointsBatch& batch) { // TODO(whess): This samples every 'voxel_size' distance and could be improved - // by better ray casting, and also by marking the hits of the current laser - // fan to be excluded. + // by better ray casting, and also by marking the hits of the current range + // data to be excluded. for (size_t i = 0; i < batch.points.size(); ++i) { const Eigen::Vector3f delta = batch.points[i] - batch.origin; const float length = delta.norm(); diff --git a/cartographer/kalman_filter/pose_tracker.h b/cartographer/kalman_filter/pose_tracker.h index 96cef6a..73b30e0 100644 --- a/cartographer/kalman_filter/pose_tracker.h +++ b/cartographer/kalman_filter/pose_tracker.h @@ -65,7 +65,7 @@ proto::PoseTrackerOptions CreatePoseTrackerOptions( common::LuaParameterDictionary* parameter_dictionary); // A Kalman filter for a 3D state of position and orientation. -// Includes functions to update from IMU and laser scan matches. +// Includes functions to update from IMU and range data matches. class PoseTracker { public: enum { diff --git a/cartographer/mapping/trajectory_node.h b/cartographer/mapping/trajectory_node.h index b5c51e9..5c78efd 100644 --- a/cartographer/mapping/trajectory_node.h +++ b/cartographer/mapping/trajectory_node.h @@ -45,9 +45,9 @@ struct TrajectoryNode { // doesn't seem like a good name for a Submaps*. Sort this out. const Submaps* trajectory; - // Transform from the 3D 'tracking' frame to the 'pose' frame of the - // laser, which contains roll, pitch and height for 2D. In 3D this is - // always identity. + // Transform from the 3D 'tracking' frame to the 'pose' frame of the range + // data, which contains roll, pitch and height for 2D. In 3D this is always + // identity. transform::Rigid3d tracking_to_pose; }; diff --git a/cartographer/mapping_2d/local_trajectory_builder.cc b/cartographer/mapping_2d/local_trajectory_builder.cc index b72710d..0831f24 100644 --- a/cartographer/mapping_2d/local_trajectory_builder.cc +++ b/cartographer/mapping_2d/local_trajectory_builder.cc @@ -27,16 +27,14 @@ namespace mapping_2d { proto::LocalTrajectoryBuilderOptions CreateLocalTrajectoryBuilderOptions( common::LuaParameterDictionary* const parameter_dictionary) { proto::LocalTrajectoryBuilderOptions options; - options.set_laser_min_range( - parameter_dictionary->GetDouble("laser_min_range")); - options.set_laser_max_range( - parameter_dictionary->GetDouble("laser_max_range")); - options.set_laser_min_z(parameter_dictionary->GetDouble("laser_min_z")); - options.set_laser_max_z(parameter_dictionary->GetDouble("laser_max_z")); - options.set_laser_missing_echo_ray_length( - parameter_dictionary->GetDouble("laser_missing_echo_ray_length")); - options.set_laser_voxel_filter_size( - parameter_dictionary->GetDouble("laser_voxel_filter_size")); + options.set_min_range(parameter_dictionary->GetDouble("min_range")); + options.set_max_range(parameter_dictionary->GetDouble("max_range")); + options.set_min_z(parameter_dictionary->GetDouble("min_z")); + options.set_max_z(parameter_dictionary->GetDouble("max_z")); + options.set_missing_data_ray_length( + parameter_dictionary->GetDouble("missing_data_ray_length")); + options.set_voxel_filter_size( + parameter_dictionary->GetDouble("voxel_filter_size")); options.set_use_online_correlative_scan_matching( parameter_dictionary->GetBool("use_online_correlative_scan_matching")); *options.mutable_adaptive_voxel_filter_options() = @@ -86,25 +84,23 @@ sensor::RangeData LocalTrajectoryBuilder::TransformAndFilterRangeData( sensor::RangeData returns_and_misses{range_data.origin, {}, {}}; for (const Eigen::Vector3f& hit : range_data.returns) { const float range = (hit - range_data.origin).norm(); - if (range >= options_.laser_min_range()) { - if (range <= options_.laser_max_range()) { + if (range >= options_.min_range()) { + if (range <= options_.max_range()) { returns_and_misses.returns.push_back(hit); } else { returns_and_misses.misses.push_back( - range_data.origin + options_.laser_missing_echo_ray_length() * + range_data.origin + options_.missing_data_ray_length() * (hit - range_data.origin).normalized()); } } } const sensor::RangeData cropped = sensor::CropRangeData( sensor::TransformRangeData(returns_and_misses, tracking_to_tracking_2d), - options_.laser_min_z(), options_.laser_max_z()); + options_.min_z(), options_.max_z()); return sensor::RangeData{ cropped.origin, - sensor::VoxelFiltered(cropped.returns, - options_.laser_voxel_filter_size()), - sensor::VoxelFiltered(cropped.misses, - options_.laser_voxel_filter_size())}; + sensor::VoxelFiltered(cropped.returns, options_.voxel_filter_size()), + sensor::VoxelFiltered(cropped.misses, options_.voxel_filter_size())}; } void LocalTrajectoryBuilder::ScanMatch( @@ -158,7 +154,7 @@ LocalTrajectoryBuilder::AddHorizontalRangeData( if (imu_tracker_ == nullptr) { // Until we've initialized the IMU tracker with our first IMU message, we - // cannot compute the orientation of the laser scanner. + // cannot compute the orientation of the rangefinder. LOG(INFO) << "ImuTracker not yet initialized."; return nullptr; } diff --git a/cartographer/mapping_2d/map_limits.h b/cartographer/mapping_2d/map_limits.h index 4fda7fa..fa751ba 100644 --- a/cartographer/mapping_2d/map_limits.h +++ b/cartographer/mapping_2d/map_limits.h @@ -84,8 +84,8 @@ class MapLimits { .all(); } - // Computes MapLimits that contain the origin, and all laser rays (both - // returns and misses) in the 'trajectory'. + // Computes MapLimits that contain the origin, and all rays (both returns and + // misses) in the 'trajectory'. static MapLimits ComputeMapLimits( const double resolution, const std::vector& trajectory_nodes) { diff --git a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto index 3435469..f16504a 100644 --- a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto @@ -23,19 +23,18 @@ import "cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.p import "cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.proto"; message LocalTrajectoryBuilderOptions { - // Laser returns outside these ranges will be dropped. - optional float laser_min_range = 14; - optional float laser_max_range = 15; - optional float laser_min_z = 1; - optional float laser_max_z = 2; + // Rangefinder points outside these ranges will be dropped. + optional float min_range = 14; + optional float max_range = 15; + optional float min_z = 1; + optional float max_z = 2; - // Laser returns beyond 'laser_max_range' will be inserted with this length as - // empty space. - optional float laser_missing_echo_ray_length = 16; + // Points beyond 'max_range' will be inserted with this length as empty space. + optional float missing_data_ray_length = 16; // Voxel filter that gets applied to the range data immediately after // cropping. - optional float laser_voxel_filter_size = 3; + optional float voxel_filter_size = 3; // Whether to solve the online scan matching first using the correlative scan // matcher to generate a good starting point for Ceres. diff --git a/cartographer/mapping_3d/kalman_local_trajectory_builder.cc b/cartographer/mapping_3d/kalman_local_trajectory_builder.cc index ff4b678..df6b7c9 100644 --- a/cartographer/mapping_3d/kalman_local_trajectory_builder.cc +++ b/cartographer/mapping_3d/kalman_local_trajectory_builder.cc @@ -96,16 +96,16 @@ KalmanLocalTrajectoryBuilder::AddRangefinderData( for (const Eigen::Vector3f& hit : range_data_in_first_tracking.returns) { const Eigen::Vector3f delta = hit - range_data_in_first_tracking.origin; const float range = delta.norm(); - if (range >= options_.laser_min_range()) { - if (range <= options_.laser_max_range()) { + if (range >= options_.min_range()) { + if (range <= options_.max_range()) { accumulated_range_data_.returns.push_back(hit); } else { - // We insert a ray cropped to 'laser_max_range' as a miss for hits - // beyond the maximum range. This way the free space up to the maximum - // range will be updated. + // We insert a ray cropped to 'max_range' as a miss for hits beyond the + // maximum range. This way the free space up to the maximum range will + // be updated. accumulated_range_data_.misses.push_back( range_data_in_first_tracking.origin + - options_.laser_max_range() / range * delta); + options_.max_range() / range * delta); } } } @@ -129,9 +129,9 @@ KalmanLocalTrajectoryBuilder::AddAccumulatedRangeData( const sensor::RangeData filtered_range_data = { range_data_in_tracking.origin, sensor::VoxelFiltered(range_data_in_tracking.returns, - options_.laser_voxel_filter_size()), + options_.voxel_filter_size()), sensor::VoxelFiltered(range_data_in_tracking.misses, - options_.laser_voxel_filter_size())}; + options_.voxel_filter_size())}; if (filtered_range_data.returns.empty()) { LOG(WARNING) << "Dropped empty range data."; diff --git a/cartographer/mapping_3d/kalman_local_trajectory_builder_test.cc b/cartographer/mapping_3d/kalman_local_trajectory_builder_test.cc index 452d1a9..2c37eb4 100644 --- a/cartographer/mapping_3d/kalman_local_trajectory_builder_test.cc +++ b/cartographer/mapping_3d/kalman_local_trajectory_builder_test.cc @@ -47,10 +47,10 @@ class KalmanLocalTrajectoryBuilderTest : public ::testing::Test { proto::LocalTrajectoryBuilderOptions CreateTrajectoryBuilderOptions() { auto parameter_dictionary = common::MakeDictionary(R"text( return { - laser_min_range = 0.5, - laser_max_range = 50., + min_range = 0.5, + max_range = 50., scans_per_accumulation = 1, - laser_voxel_filter_size = 0.05, + voxel_filter_size = 0.05, high_resolution_adaptive_voxel_filter = { max_length = 0.7, @@ -191,15 +191,15 @@ class KalmanLocalTrajectoryBuilderTest : public ::testing::Test { sensor::RangeData GenerateRangeData(const transform::Rigid3d& pose) { // 360 degree rays at 16 angles. - sensor::PointCloud directions_in_laser_frame; + sensor::PointCloud directions_in_rangefinder_frame; for (int r = -8; r != 8; ++r) { for (int s = -250; s != 250; ++s) { - directions_in_laser_frame.push_back( + directions_in_rangefinder_frame.push_back( Eigen::AngleAxisf(M_PI * s / 250., Eigen::Vector3f::UnitZ()) * Eigen::AngleAxisf(M_PI / 12. * r / 8., Eigen::Vector3f::UnitY()) * Eigen::Vector3f::UnitX()); - // Second orthogonal laser. - directions_in_laser_frame.push_back( + // Second orthogonal rangefinder. + directions_in_rangefinder_frame.push_back( Eigen::AngleAxisf(M_PI / 2., Eigen::Vector3f::UnitX()) * Eigen::AngleAxisf(M_PI * s / 250., Eigen::Vector3f::UnitZ()) * Eigen::AngleAxisf(M_PI / 12. * r / 8., Eigen::Vector3f::UnitY()) * @@ -210,13 +210,12 @@ class KalmanLocalTrajectoryBuilderTest : public ::testing::Test { // 50 cm radius spheres. sensor::PointCloud returns_in_world_frame; for (const Eigen::Vector3f& direction_in_world_frame : - sensor::TransformPointCloud(directions_in_laser_frame, + sensor::TransformPointCloud(directions_in_rangefinder_frame, pose.cast())) { - const Eigen::Vector3f laser_origin = + const Eigen::Vector3f origin = pose.cast() * Eigen::Vector3f::Zero(); returns_in_world_frame.push_back(CollideWithBubbles( - laser_origin, - CollideWithBox(laser_origin, direction_in_world_frame))); + origin, CollideWithBox(origin, direction_in_world_frame))); } return {Eigen::Vector3f::Zero(), sensor::TransformPointCloud(returns_in_world_frame, diff --git a/cartographer/mapping_3d/local_trajectory_builder_options.cc b/cartographer/mapping_3d/local_trajectory_builder_options.cc index 40fd0a8..ac7bdb4 100644 --- a/cartographer/mapping_3d/local_trajectory_builder_options.cc +++ b/cartographer/mapping_3d/local_trajectory_builder_options.cc @@ -30,14 +30,12 @@ namespace mapping_3d { proto::LocalTrajectoryBuilderOptions CreateLocalTrajectoryBuilderOptions( common::LuaParameterDictionary* const parameter_dictionary) { proto::LocalTrajectoryBuilderOptions options; - options.set_laser_min_range( - parameter_dictionary->GetDouble("laser_min_range")); - options.set_laser_max_range( - parameter_dictionary->GetDouble("laser_max_range")); + options.set_min_range(parameter_dictionary->GetDouble("min_range")); + options.set_max_range(parameter_dictionary->GetDouble("max_range")); options.set_scans_per_accumulation( parameter_dictionary->GetInt("scans_per_accumulation")); - options.set_laser_voxel_filter_size( - parameter_dictionary->GetDouble("laser_voxel_filter_size")); + options.set_voxel_filter_size( + parameter_dictionary->GetDouble("voxel_filter_size")); *options.mutable_high_resolution_adaptive_voxel_filter_options() = sensor::CreateAdaptiveVoxelFilterOptions( parameter_dictionary diff --git a/cartographer/mapping_3d/optimizing_local_trajectory_builder.cc b/cartographer/mapping_3d/optimizing_local_trajectory_builder.cc index d44ef85..b2b48e2 100644 --- a/cartographer/mapping_3d/optimizing_local_trajectory_builder.cc +++ b/cartographer/mapping_3d/optimizing_local_trajectory_builder.cc @@ -144,8 +144,8 @@ OptimizingLocalTrajectoryBuilder::AddRangefinderData( for (const Eigen::Vector3f& hit : ranges) { const Eigen::Vector3f delta = hit - origin; const float range = delta.norm(); - if (range >= options_.laser_min_range()) { - if (range <= options_.laser_max_range()) { + if (range >= options_.min_range()) { + if (range <= options_.max_range()) { point_cloud.push_back(hit); } } @@ -361,9 +361,9 @@ OptimizingLocalTrajectoryBuilder::AddAccumulatedRangeData( const sensor::RangeData filtered_range_data = { range_data_in_tracking.origin, sensor::VoxelFiltered(range_data_in_tracking.returns, - options_.laser_voxel_filter_size()), + options_.voxel_filter_size()), sensor::VoxelFiltered(range_data_in_tracking.misses, - options_.laser_voxel_filter_size())}; + options_.voxel_filter_size())}; if (filtered_range_data.returns.empty()) { LOG(WARNING) << "Dropped empty range data."; diff --git a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto index da02469..32638a1 100644 --- a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto @@ -29,16 +29,17 @@ message LocalTrajectoryBuilderOptions { OPTIMIZING = 1; } - // Laser limits. - optional float laser_min_range = 1; - optional float laser_max_range = 2; + // Rangefinder points outside these ranges will be dropped. + optional float min_range = 1; + optional float max_range = 2; // Number of scans to accumulate into one unwarped, combined scan to use for // scan matching. optional int32 scans_per_accumulation = 3; - // Voxel filter that gets applied to the laser before doing anything with it. - optional float laser_voxel_filter_size = 4; + // Voxel filter that gets applied to the range data immediately after + // cropping. + optional float voxel_filter_size = 4; // Voxel filter used to compute a sparser point cloud for matching. optional sensor.proto.AdaptiveVoxelFilterOptions diff --git a/cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc b/cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc index c050851..598f4ea 100644 --- a/cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc +++ b/cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc @@ -247,7 +247,7 @@ std::vector FastCorrelativeScanMatcher::GenerateDiscreteScans( const Eigen::Vector3f angle_axis(0.f, 0.f, angles[i]); // It's important to apply the 'angle_axis' rotation between the translation // and rotation of the 'initial_pose', so that the rotation is around the - // origin of the laser scanner, and yaw is in map frame. + // origin of the range data, and yaw is in map frame. const transform::Rigid3f pose( Eigen::Translation3f(initial_pose.translation()) * transform::AngleAxisVectorToRotationQuaternion(angle_axis) * diff --git a/cartographer/mapping_3d/scan_matching/rotational_scan_matcher.cc b/cartographer/mapping_3d/scan_matching/rotational_scan_matcher.cc index 3149f3c..c35d667 100644 --- a/cartographer/mapping_3d/scan_matching/rotational_scan_matcher.cc +++ b/cartographer/mapping_3d/scan_matching/rotational_scan_matcher.cc @@ -68,11 +68,10 @@ void AddPointCloudSliceToValueVector( if (slice.empty()) { return; } - // We compute the angle of the ray from the centroid to a laser return. - // If it is orthogonal to the angle we compute between laser returns, we will - // add the angle between laser returns to the histogram with the maximum - // weight. This is to reject, e.g., the angles observed on the ceiling and - // floor. + // We compute the angle of the ray from a point to the centroid of the whole + // point cloud. If it is orthogonal to the angle we compute between points, we + // will add the angle between points to the histogram with the maximum weight. + // This is to reject, e.g., the angles observed on the ceiling and floor. const Eigen::Vector3f centroid = ComputeCentroid(slice); Eigen::Vector3f last_point = slice.front(); for (const Eigen::Vector3f& point : slice) { @@ -94,8 +93,8 @@ void AddPointCloudSliceToValueVector( } // A function to sort the points in each slice by angle around the centroid. -// This is because the returns from different lasers are interleaved in the -// data. +// This is because the returns from different rangefinders are interleaved in +// the data. sensor::PointCloud SortSlice(const sensor::PointCloud& slice) { struct SortableAnglePointPair { bool operator<(const SortableAnglePointPair& rhs) const { diff --git a/cartographer/sensor/collator_test.cc b/cartographer/sensor/collator_test.cc index 5ebb55a..4597539 100644 --- a/cartographer/sensor/collator_test.cc +++ b/cartographer/sensor/collator_test.cc @@ -31,7 +31,7 @@ namespace { TEST(Collator, Ordering) { const std::array kSensorId = { - {"horizontal_laser", "vertical_laser", "imu", "odometry"}}; + {"horizontal_rangefinder", "vertical_rangefinder", "imu", "odometry"}}; Data zero(common::FromUniversal(0), Data::Rangefinder{}); Data first(common::FromUniversal(100), Data::Rangefinder{}); Data second(common::FromUniversal(200), Data::Rangefinder{}); diff --git a/cartographer/sensor/compressed_point_cloud.cc b/cartographer/sensor/compressed_point_cloud.cc index b2b90e9..01b24fa 100644 --- a/cartographer/sensor/compressed_point_cloud.cc +++ b/cartographer/sensor/compressed_point_cloud.cc @@ -137,9 +137,9 @@ CompressedPointCloud::CompressedPointCloud(const PointCloud& point_cloud) point_data_.push_back(block_coordinate.z()); for (const RasterPoint& raster_point : raster_points) { point_data_.push_back((((raster_point.point.z() << kBitsPerCoordinate) + - raster_point.point.y()) - << kBitsPerCoordinate) + - raster_point.point.x()); + raster_point.point.y()) + << kBitsPerCoordinate) + + raster_point.point.x()); } } CHECK_EQ(num_blocks, 0); diff --git a/configuration_files/trajectory_builder_2d.lua b/configuration_files/trajectory_builder_2d.lua index f0127d9..a650c77 100644 --- a/configuration_files/trajectory_builder_2d.lua +++ b/configuration_files/trajectory_builder_2d.lua @@ -14,12 +14,12 @@ TRAJECTORY_BUILDER_2D = { use_imu_data = true, - laser_min_range = 0., - laser_max_range = 30., - laser_min_z = -0.8, - laser_max_z = 2., - laser_missing_echo_ray_length = 5., - laser_voxel_filter_size = 0.025, + min_range = 0., + max_range = 30., + min_z = -0.8, + max_z = 2., + missing_data_ray_length = 5., + voxel_filter_size = 0.025, use_online_correlative_scan_matching = false, adaptive_voxel_filter = { diff --git a/configuration_files/trajectory_builder_3d.lua b/configuration_files/trajectory_builder_3d.lua index fb74794..bf9915c 100644 --- a/configuration_files/trajectory_builder_3d.lua +++ b/configuration_files/trajectory_builder_3d.lua @@ -12,13 +12,13 @@ -- See the License for the specific language governing permissions and -- limitations under the License. -MAX_3D_LASER_RANGE = 60. +MAX_3D_RANGE = 60. TRAJECTORY_BUILDER_3D = { - laser_min_range = 1., - laser_max_range = MAX_3D_LASER_RANGE, + min_range = 1., + max_range = MAX_3D_RANGE, scans_per_accumulation = 1, - laser_voxel_filter_size = 0.15, + voxel_filter_size = 0.15, high_resolution_adaptive_voxel_filter = { max_length = 2., @@ -29,7 +29,7 @@ TRAJECTORY_BUILDER_3D = { low_resolution_adaptive_voxel_filter = { max_length = 4., min_num_points = 200, - max_range = MAX_3D_LASER_RANGE, + max_range = MAX_3D_RANGE, }, ceres_scan_matcher = { diff --git a/docs/source/configuration.rst b/docs/source/configuration.rst index 4e22ea9..dff8e91 100644 --- a/docs/source/configuration.rst +++ b/docs/source/configuration.rst @@ -167,23 +167,22 @@ cartographer.common.proto.CeresSolverOptions ceres_solver_options cartographer.mapping_2d.proto.LocalTrajectoryBuilderOptions =========================================================== -float laser_min_range - Laser returns outside these ranges will be dropped. +float min_range + Rangefinder points outside these ranges will be dropped. -float laser_max_range +float max_range Not yet documented. -float laser_min_z +float min_z Not yet documented. -float laser_max_z +float max_z Not yet documented. -float laser_missing_echo_ray_length - Laser returns beyond 'laser_max_range' will be inserted with this length as - empty space. +float missing_data_ray_length + Points beyond 'max_range' will be inserted with this length as empty space. -float laser_voxel_filter_size +float voxel_filter_size Voxel filter that gets applied to the range data immediately after cropping.