Skip to content

Commit

Permalink
Fixed build error related to #714 PR (#718)
Browse files Browse the repository at this point in the history
  • Loading branch information
CihatAltiparmak authored Jul 4, 2024
1 parent 5fb7fa5 commit a108d26
Showing 1 changed file with 9 additions and 5 deletions.
14 changes: 9 additions & 5 deletions src/laser_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,20 +102,24 @@ karto::LaserRangeFinder * LaserAssistant::makeLaser(const double & mountingYaw)
laser_pose_.transform.translation.y, mountingYaw));

double min_laser_range = 0.0;
if (!node_->has_parameter("min_laser_range")) {
node_->declare_parameter("min_laser_range", min_laser_range);
if (!parameters_interface_->has_parameter("min_laser_range")) {
parameters_interface_->declare_parameter(
"min_laser_range",
rclcpp::ParameterValue(min_laser_range));
}
node_->get_parameter("min_laser_range", min_laser_range);
min_laser_range = parameters_interface_->get_parameter("min_laser_range").as_double();

if (min_laser_range < 0) {
RCLCPP_WARN(node_->get_logger(),
RCLCPP_WARN(
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(),
RCLCPP_WARN(
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;
Expand Down

0 comments on commit a108d26

Please sign in to comment.