Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions src/laser_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,13 @@ karto::LaserRangeFinder * LaserAssistant::makeLaser(const double & mountingYaw)
}
node_->get_parameter("max_laser_range", max_laser_range);

if (max_laser_range <= 0) {
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this a real issue you really ran into? This seems like its from a poorly formed laser scan message and it should be fixed by the publisher

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just consider it as a parameter a user can set, and it seems it is not related to scan message...

RCLCPP_WARN(node_->get_logger(),
"You've set maximum_laser_range to be negative,"
"this isn't allowed so it will be set to (%.1f).", scan_.range_max);
max_laser_range = scan_.range_max;
}

if (max_laser_range > scan_.range_max) {
RCLCPP_WARN(node_->get_logger(),
"maximum laser range setting (%.1f m) exceeds the capabilities "
Expand Down
36 changes: 36 additions & 0 deletions src/slam_mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,12 @@ void SMapper::configure(const rclcpp::Node::SharedPtr & node)
correlation_search_space_dimension);
}
node->get_parameter("correlation_search_space_dimension", correlation_search_space_dimension);
if (correlation_search_space_dimension <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set correlation_search_space_dimension to be negative,"
"this isn't allowed so it will be set to default value 0.5.");
correlation_search_space_dimension = 0.5;
}
mapper_->setParamCorrelationSearchSpaceDimension(correlation_search_space_dimension);

double correlation_search_space_resolution = 0.01;
Expand All @@ -216,6 +222,12 @@ void SMapper::configure(const rclcpp::Node::SharedPtr & node)
correlation_search_space_resolution);
}
node->get_parameter("correlation_search_space_resolution", correlation_search_space_resolution);
if (correlation_search_space_resolution <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set correlation_search_space_resolution to be negative,"
"this isn't allowed so it will be set to default value 0.01.");
correlation_search_space_resolution = 0.01;
}
mapper_->setParamCorrelationSearchSpaceResolution(correlation_search_space_resolution);

double correlation_search_space_smear_deviation = 0.1;
Expand All @@ -227,6 +239,12 @@ void SMapper::configure(const rclcpp::Node::SharedPtr & node)
node->get_parameter(
"correlation_search_space_smear_deviation",
correlation_search_space_smear_deviation);
if (correlation_search_space_smear_deviation <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set correlation_search_space_smear_deviation to be negative,"
"this isn't allowed so it will be set to default value 0.1.");
correlation_search_space_smear_deviation = 0.1;
}
mapper_->setParamCorrelationSearchSpaceSmearDeviation(correlation_search_space_smear_deviation);

// Setting Correlation Parameters, Loop Closure Parameters
Expand All @@ -235,20 +253,38 @@ void SMapper::configure(const rclcpp::Node::SharedPtr & node)
node->declare_parameter("loop_search_space_dimension", loop_search_space_dimension);
}
node->get_parameter("loop_search_space_dimension", loop_search_space_dimension);
if (loop_search_space_dimension <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set loop_search_space_dimension to be negative,"
"this isn't allowed so it will be set to default value 8.0.");
loop_search_space_dimension = 8.0;
}
mapper_->setParamLoopSearchSpaceDimension(loop_search_space_dimension);

double loop_search_space_resolution = 0.05;
if (!node->has_parameter("loop_search_space_resolution")) {
node->declare_parameter("loop_search_space_resolution", loop_search_space_resolution);
}
node->get_parameter("loop_search_space_resolution", loop_search_space_resolution);
if (loop_search_space_resolution <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set loop_search_space_resolution to be negative,"
"this isn't allowed so it will be set to default value 0.05.");
loop_search_space_resolution = 0.05;
}
mapper_->setParamLoopSearchSpaceResolution(loop_search_space_resolution);

double loop_search_space_smear_deviation = 0.03;
if (!node->has_parameter("loop_search_space_smear_deviation")) {
node->declare_parameter("loop_search_space_smear_deviation", loop_search_space_smear_deviation);
}
node->get_parameter("loop_search_space_smear_deviation", loop_search_space_smear_deviation);
if (loop_search_space_smear_deviation <= 0) {
RCLCPP_WARN(node->get_logger(),
"You've set loop_search_space_smear_deviation to be negative,"
"this isn't allowed so it will be set to default value 0.03.");
loop_search_space_smear_deviation = 0.03;
}
mapper_->setParamLoopSearchSpaceSmearDeviation(loop_search_space_smear_deviation);

// Setting Scan Matcher Parameters
Expand Down