Skip to content

Commit 020369b

Browse files
Use fixed thresholds for Trinary yaml (#5278) (#5284)
(cherry picked from commit 829e683) Signed-off-by: Adi Vardi <[email protected]> Co-authored-by: Adi Vardi <[email protected]>
1 parent fd3e8e2 commit 020369b

File tree

1 file changed

+12
-2
lines changed

1 file changed

+12
-2
lines changed

nav2_map_server/src/map_io.cpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -602,8 +602,18 @@ void tryWriteMapToFile(
602602
e << YAML::Key << "origin" << YAML::Flow << YAML::BeginSeq << map.info.origin.position.x <<
603603
map.info.origin.position.y << yaw << YAML::EndSeq;
604604
e << YAML::Key << "negate" << YAML::Value << 0;
605-
e << YAML::Key << "occupied_thresh" << YAML::Value << save_parameters.occupied_thresh;
606-
e << YAML::Key << "free_thresh" << YAML::Value << save_parameters.free_thresh;
605+
606+
if (save_parameters.mode == MapMode::Trinary) {
607+
// For Trinary mode, the thresholds depend on the pixel values in the saved map,
608+
// not on the thresholds used to threshold the map.
609+
// As these values are fixed above, the thresholds must also be fixed to separate the
610+
// pixel values into occupied, free and unknown.
611+
e << YAML::Key << "occupied_thresh" << YAML::Value << 0.65;
612+
e << YAML::Key << "free_thresh" << YAML::Value << 0.196;
613+
} else {
614+
e << YAML::Key << "occupied_thresh" << YAML::Value << save_parameters.occupied_thresh;
615+
e << YAML::Key << "free_thresh" << YAML::Value << save_parameters.free_thresh;
616+
}
607617

608618
if (!e.good()) {
609619
RCLCPP_ERROR_STREAM(

0 commit comments

Comments
 (0)