Skip to content

Commit

Permalink
Humble min laser range parameters (#713)
Browse files Browse the repository at this point in the history
* ignore vscode folder in gitignore

* add min_laser_range feature from parameters in laser_utils.cpp file

* add info related to min_laser_range in README.MD and add sample parameters to all .yaml file in config folder

* Update laser_utils.cpp, fix initial min_laser_range value from 25 to 0.0
  • Loading branch information
mich1342 authored Jun 28, 2024
1 parent 94cec98 commit 19a6690
Show file tree
Hide file tree
Showing 8 changed files with 30 additions and 1 deletion.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
snap_ws/*
.vscode/*
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,8 @@ The following settings and options are exposed to you. My default configuration

`resolution` - Resolution of the 2D occupancy map to generate

`min_laser_range` - Minimum laser range to use for 2D occupancy map rasterizing

`max_laser_range` - Maximum laser range to use for 2D occupancy map rasterizing

`minimum_time_interval` - The minimum duration of time between scans to be processed in synchronous mode
Expand Down
1 change: 1 addition & 0 deletions config/mapper_params_lifelong.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ slam_toolbox:
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
min_laser_range: 0.0 #for rastering images
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
Expand Down
1 change: 1 addition & 0 deletions config/mapper_params_localization.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ slam_toolbox:
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
min_laser_range: 0.0 #for rastering images
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
Expand Down
1 change: 1 addition & 0 deletions config/mapper_params_offline.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ slam_toolbox:
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 10.0
resolution: 0.05
min_laser_range: 0.0 #for rastering images
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
Expand Down
1 change: 1 addition & 0 deletions config/mapper_params_online_async.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ slam_toolbox:
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
min_laser_range: 0.0 #for rastering images
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
Expand Down
1 change: 1 addition & 0 deletions config/mapper_params_online_sync.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ slam_toolbox:
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
min_laser_range: 0.0 #for rastering images
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
Expand Down
23 changes: 22 additions & 1 deletion src/laser_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,28 @@ karto::LaserRangeFinder * LaserAssistant::makeLaser(const double & mountingYaw)
karto::LaserRangeFinder_Custom, karto::Name("Custom Described Lidar"));
laser->SetOffsetPose(karto::Pose2(laser_pose_.transform.translation.x,
laser_pose_.transform.translation.y, mountingYaw));
laser->SetMinimumRange(scan_.range_min);

double min_laser_range = 0.0;
if (!node_->has_parameter("min_laser_range")) {
node_->declare_parameter("min_laser_range", min_laser_range);
}
node_->get_parameter("min_laser_range", min_laser_range);

if (min_laser_range < 0) {
RCLCPP_WARN(node_->get_logger(),
"You've set minimum laser range to be negative,"
"this isn't allowed so it will be set to (%.1f).", scan_.range_min);
min_laser_range = scan_.range_min;
}

if (min_laser_range < scan_.range_min) {
RCLCPP_WARN(node_->get_logger(),
"minimum laser range setting (%.1f m) exceeds the capabilities "
"of the used Lidar (%.1f m)", min_laser_range, scan_.range_min);
min_laser_range = scan_.range_min;
}

laser->SetMinimumRange(min_laser_range);
laser->SetMaximumRange(scan_.range_max);
laser->SetMinimumAngle(scan_.angle_min);
laser->SetMaximumAngle(scan_.angle_max);
Expand Down

0 comments on commit 19a6690

Please sign in to comment.