Skip to content

Commit

Permalink
renamed remaining updated_cells to cleared_cells
Browse files Browse the repository at this point in the history
  • Loading branch information
siferati committed Apr 14, 2021
1 parent e482f7e commit 019f1a7
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ class SpatioTemporalVoxelGrid
void Mark(const std::vector<observation::MeasurementReading>& marking_observations);
void operator()(const observation::MeasurementReading& obs);
void ClearFrustums(const std::vector<observation::MeasurementReading>& clearing_observations, \
std::unordered_set<occupany_cell>& updated_cells);
std::unordered_set<occupany_cell>& cleared_cells);

// Get the pointcloud of the underlying occupancy grid
void GetOccupancyPointCloud(sensor_msgs::PointCloud2::Ptr& pc2);
Expand Down Expand Up @@ -161,7 +161,7 @@ class SpatioTemporalVoxelGrid
double GetFrustumAcceleration(const double& time_delta, \
const double& acceleration_factor);
void TemporalClearAndGenerateCostmap(std::vector<frustum_model>& frustums, \
std::unordered_set<occupany_cell>& updated_cells);
std::unordered_set<occupany_cell>& cleared_cells);

// Populate the costmap ROS api and pointcloud with a marked point
void PopulateCostmapAndPointcloud(const openvdb::Coord& pt);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class SpatioTemporalVoxelLayer : public costmap_2d::CostmapLayer

// Functions to interact with maps
void UpdateROSCostmap(double* min_x, double* min_y, double* max_x, double* max_y, \
std::unordered_set<volume_grid::occupany_cell>& updated_cells);
std::unordered_set<volume_grid::occupany_cell>& cleared_cells);
bool updateFootprint(double robot_x, double robot_y, double robot_yaw, \
double* min_x, double* min_y, double* max_x, double* max_y);
void ResetGrid(void);
Expand Down

0 comments on commit 019f1a7

Please sign in to comment.