Skip to content

Commit 2692f15

Browse files
author
Guillaume
committed
french spelling
1 parent a5033cf commit 2692f15

File tree

5 files changed

+13
-13
lines changed

5 files changed

+13
-13
lines changed

cfg/SpatioTemporalVoxelLayer.cfg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ gen.add("mark_threshold", double_t, 0, "Over this threshold, the measurement wil
2222
gen.add("update_footprint_enabled", bool_t, 0, "Cleans where the robot's footprint is", True)
2323
gen.add("track_unknown_space", bool_t, 1, "If true, marks will be UNKNOWN (255) otherwise, FREE (0)", True)
2424
gen.add("decay_model", int_t, 1, "Decay models", 0, edit_method=decay_model_enum)
25-
gen.add("min_age_outside_frustrum", double_t, 1, "the minimum age that a voxel should have to be allow to live outside frustrums", 0.0, 0.0, 100.0)
25+
gen.add("min_age_outside_frustum", double_t, 1, "the minimum age that a voxel should have to be allow to live outside frustrums", 0.0, 0.0, 100.0)
2626
gen.add("voxel_decay", double_t, 1, "Seconds if linear, e^n if exponential", 10.0, -1, 200.0)
2727
gen.add("mapping_mode", bool_t, 0, "Mapping mode", False)
2828
gen.add("map_save_duration", double_t, 0, "f mapping, how often to save a map for safety", 60.0, 1.0, 2000.0)

include/spatio_temporal_voxel_layer/spatio_temporal_voxel_grid.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ class SpatioTemporalVoxelGrid
124124
typedef openvdb::math::Ray<openvdb::Real>::Vec3T Vec3Type;
125125

126126
SpatioTemporalVoxelGrid(const float& voxel_size, const double& background_value,
127-
const int& decay_model, const double& min_age_outside_frustrum, const double& voxel_decay,
127+
const int& decay_model, const double& min_age_outside_frustum, const double& voxel_decay,
128128
const bool& pub_voxels);
129129
~SpatioTemporalVoxelGrid(void);
130130

@@ -169,7 +169,7 @@ class SpatioTemporalVoxelGrid
169169

170170
mutable openvdb::DoubleGrid::Ptr _grid;
171171
int _decay_model;
172-
double _background_value, _voxel_size, _min_age_outside_frustrum, _voxel_decay;
172+
double _background_value, _voxel_size, _min_age_outside_frustum, _voxel_decay;
173173
bool _pub_voxels;
174174
std::vector<geometry_msgs::Point32>* _grid_points;
175175
std::unordered_map<occupany_cell, uint>* _cost_map;

include/spatio_temporal_voxel_layer/spatio_temporal_voxel_layer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -161,7 +161,7 @@ class SpatioTemporalVoxelLayer : public costmap_2d::CostmapLayer
161161
ros::Duration _map_save_duration;
162162
ros::Time _last_map_save_time;
163163
std::string _global_frame;
164-
double _voxel_size, _min_age_outside_frustrum, _voxel_decay;
164+
double _voxel_size, _min_age_outside_frustum, _voxel_decay;
165165
int _combination_method, _mark_threshold;
166166
volume_grid::GlobalDecayModel _decay_model;
167167
bool _update_footprint_enabled, _enabled;

src/spatio_temporal_voxel_grid.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,12 +43,12 @@ namespace volume_grid
4343
/*****************************************************************************/
4444
SpatioTemporalVoxelGrid::SpatioTemporalVoxelGrid(const float& voxel_size, \
4545
const double& background_value, const int& decay_model,\
46-
const double& min_age_outside_frustrum, \
46+
const double& min_age_outside_frustum, \
4747
const double& voxel_decay, const bool& pub_voxels) :
4848
_background_value(background_value), \
4949
_voxel_size(voxel_size), \
5050
_decay_model(decay_model), \
51-
_min_age_outside_frustrum(min_age_outside_frustrum), \
51+
_min_age_outside_frustum(min_age_outside_frustum), \
5252
_voxel_decay(voxel_decay), \
5353
_pub_voxels(pub_voxels), \
5454
_grid_points(new std::vector<geometry_msgs::Point32>), \
@@ -224,13 +224,13 @@ void SpatioTemporalVoxelGrid::TemporalClearAndGenerateCostmap( \
224224

225225
// if not inside any, check against nominal decay model, also clearing if
226226
// too young.
227-
// Depending on min_age_outside_frustrum value and cycle frequency,
227+
// Depending on min_age_outside_frustum value and cycle frequency,
228228
// a voxel too young means that it was marked without being in a frustrum
229229
// (or, edgy case, the point that marked the voxel was in a frustrum
230230
// but the center of that voxel was not), in that case : clearing
231231
if(!frustum_cycle)
232232
{
233-
if (base_duration_to_decay < 0. || time_since_marking < _min_age_outside_frustrum)
233+
if (base_duration_to_decay < 0. || time_since_marking < _min_age_outside_frustum)
234234
{
235235
// expired by temporal clearing
236236
if(!this->ClearGridPoint(pt_index))

src/spatio_temporal_voxel_layer.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -99,8 +99,8 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
9999
layered_costmap_->isTrackingUnknown());
100100
nh.param("decay_model", decay_model_int, 0);
101101
_decay_model = static_cast<volume_grid::GlobalDecayModel>(decay_model_int);
102-
// min_age_outside_frustrum param
103-
nh.param("min_age_outside_frustrum", _min_age_outside_frustrum, 0.05);
102+
// min_age_outside_frustum param
103+
nh.param("min_age_outside_frustum", _min_age_outside_frustum, 0.05);
104104
// decay param
105105
nh.param("voxel_decay", _voxel_decay, -1.);
106106
// whether to map or navigate
@@ -132,7 +132,7 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
132132
_voxel_grid = new volume_grid::SpatioTemporalVoxelGrid(_voxel_size, \
133133
(double)default_value_, \
134134
_decay_model, \
135-
_min_age_outside_frustrum, \
135+
_min_age_outside_frustum, \
136136
_voxel_decay, \
137137
_publish_voxels);
138138
matchSize();
@@ -623,15 +623,15 @@ void SpatioTemporalVoxelLayer::DynamicReconfigureCallback( \
623623
costmap_2d::NO_INFORMATION : costmap_2d::FREE_SPACE;
624624
default_value_ = default_value;
625625
_voxel_size = config.voxel_size;
626-
_min_age_outside_frustrum = config.min_age_outside_frustrum;
626+
_min_age_outside_frustum = config.min_age_outside_frustum;
627627
_voxel_decay = config.voxel_decay;
628628
_decay_model = static_cast<volume_grid::GlobalDecayModel>(config.decay_model);
629629
_publish_voxels = config.publish_voxel_map;
630630

631631
delete _voxel_grid;
632632
_voxel_grid = new volume_grid::SpatioTemporalVoxelGrid(_voxel_size, \
633633
static_cast<double>(default_value_), _decay_model, \
634-
_min_age_outside_frustrum, _voxel_decay, _publish_voxels);
634+
_min_age_outside_frustum, _voxel_decay, _publish_voxels);
635635
}
636636
}
637637

0 commit comments

Comments
 (0)