@@ -100,8 +100,10 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
100100 declareParameter (" voxel_size" , rclcpp::ParameterValue (0.05 ));
101101 node->get_parameter (name_ + " .voxel_size" , _voxel_size);
102102 // 1=takes highest in layers, 0=takes current layer
103+ int combination_method_param{};
103104 declareParameter (" combination_method" , rclcpp::ParameterValue (1 ));
104- node->get_parameter (name_ + " .combination_method" , _combination_method);
105+ node->get_parameter (name_ + " .combination_method" , combination_method_param);
106+ _combination_method = combination_method_from_int (combination_method_param);
105107 // number of voxels per vertical needed to have obstacle
106108 declareParameter (" mark_threshold" , rclcpp::ParameterValue (0 ));
107109 node->get_parameter (name_ + " .mark_threshold" , _mark_threshold);
@@ -684,12 +686,15 @@ void SpatioTemporalVoxelLayer::updateCosts(
684686 }
685687
686688 switch (_combination_method) {
687- case 0 :
689+ case nav2_costmap_2d::CombinationMethod::Overwrite :
688690 updateWithOverwrite (master_grid, min_i, min_j, max_i, max_j);
689691 break ;
690- case 1 :
692+ case nav2_costmap_2d::CombinationMethod::Max :
691693 updateWithMax (master_grid, min_i, min_j, max_i, max_j);
692694 break ;
695+ case nav2_costmap_2d::CombinationMethod::MaxWithoutUnknownOverwrite:
696+ updateWithMaxWithoutUnknownOverwrite (master_grid, min_i, min_j, max_i, max_j);
697+ break ;
693698 default :
694699 break ;
695700 }
0 commit comments