Skip to content

Commit 8d4ae5b

Browse files
authored
Option for stvl to not override StaticLayer's unknown parts (#1)
* Add updateWithMaxWithoutUnknownOverwrite to stvl * Fix small errors
1 parent 6ade4fe commit 8d4ae5b

File tree

2 files changed

+10
-4
lines changed

2 files changed

+10
-4
lines changed

include/spatio_temporal_voxel_layer/spatio_temporal_voxel_layer.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,8 @@ class SpatioTemporalVoxelLayer : public nav2_costmap_2d::CostmapLayer
182182
rclcpp::Time _last_map_save_time;
183183
std::string _global_frame;
184184
double _voxel_size, _voxel_decay;
185-
int _combination_method, _mark_threshold;
185+
int _mark_threshold;
186+
nav2_costmap_2d::CombinationMethod _combination_method;
186187
volume_grid::GlobalDecayModel _decay_model;
187188
bool _update_footprint_enabled, _enabled;
188189
std::vector<geometry_msgs::msg::Point> _transformed_footprint;

src/spatio_temporal_voxel_layer.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)