Skip to content

Commit ecd982d

Browse files
committed
remove redundant CellData::index_
1 parent caa8418 commit ecd982d

File tree

3 files changed

+19
-24
lines changed

3 files changed

+19
-24
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -60,18 +60,16 @@ class CellData
6060
public:
6161
/**
6262
* @brief Constructor for a CellData objects
63-
* @param i The index of the cell in the cost map
6463
* @param x The x coordinate of the cell in the cost map
6564
* @param y The y coordinate of the cell in the cost map
6665
* @param sx The x coordinate of the closest obstacle cell in the costmap
6766
* @param sy The y coordinate of the closest obstacle cell in the costmap
6867
* @return
6968
*/
70-
CellData(double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
71-
: index_(static_cast<unsigned int>(i)), x_(x), y_(y), src_x_(sx), src_y_(sy)
69+
CellData(unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
70+
: x_(x), y_(y), src_x_(sx), src_y_(sy)
7271
{
7372
}
74-
unsigned int index_;
7573
unsigned int x_, y_;
7674
unsigned int src_x_, src_y_;
7775
};

nav2_costmap_2d/plugins/inflation_layer.cpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -236,7 +236,7 @@ InflationLayer::updateCosts(
236236
int index = static_cast<int>(master_grid.getIndex(i, j));
237237
unsigned char cost = master_array[index];
238238
if (cost == LETHAL_OBSTACLE || (inflate_around_unknown_ && cost == NO_INFORMATION)) {
239-
obs_bin.emplace_back(index, i, j, i, j);
239+
obs_bin.emplace_back(i, j, i, j);
240240
}
241241
}
242242
}
@@ -250,7 +250,12 @@ InflationLayer::updateCosts(
250250
// Do not use iterator or for-range based loops to
251251
// iterate though dist_bin, since it's size might
252252
// change when a new cell is enqueued, invalidating all iterators
253-
unsigned int index = dist_bin[i].index_;
253+
const CellData& cell = dist_bin[i];
254+
unsigned int mx = cell.x_;
255+
unsigned int my = cell.y_;
256+
unsigned int sx = cell.src_x_;
257+
unsigned int sy = cell.src_y_;
258+
unsigned int index = master_grid.getIndex(mx, my);
254259

255260
// ignore if already visited
256261
if (seen_[index]) {
@@ -259,11 +264,6 @@ InflationLayer::updateCosts(
259264

260265
seen_[index] = true;
261266

262-
unsigned int mx = dist_bin[i].x_;
263-
unsigned int my = dist_bin[i].y_;
264-
unsigned int sx = dist_bin[i].src_x_;
265-
unsigned int sy = dist_bin[i].src_y_;
266-
267267
// assign the cost associated with the distance from an obstacle to the cell
268268
unsigned char cost = costLookup(mx, my, sx, sy);
269269
unsigned char old_cost = master_array[index];
@@ -334,8 +334,8 @@ InflationLayer::enqueue(
334334
const unsigned int r = cell_inflation_radius_ + 2;
335335

336336
// push the cell data onto the inflation list and mark
337-
inflation_cells_[distance_matrix_[mx - src_x + r][my - src_y + r]].emplace_back(
338-
index, mx, my, src_x, src_y);
337+
const auto dist = distance_matrix_[mx - src_x + r][my - src_y + r];
338+
inflation_cells_[dist].emplace_back(mx, my, src_x, src_y);
339339
}
340340
}
341341

nav2_costmap_2d/test/integration/inflation_tests.cpp

+8-11
Original file line numberDiff line numberDiff line change
@@ -125,15 +125,16 @@ void TestNode::validatePointInflation(
125125
bool * seen = new bool[costmap->getSizeInCellsX() * costmap->getSizeInCellsY()];
126126
memset(seen, false, costmap->getSizeInCellsX() * costmap->getSizeInCellsY() * sizeof(bool));
127127
std::map<double, std::vector<CellData>> m;
128-
CellData initial(costmap->getIndex(mx, my), mx, my, mx, my);
128+
CellData initial(mx, my, mx, my);
129129
m[0].push_back(initial);
130130
for (std::map<double, std::vector<CellData>>::iterator bin = m.begin();
131131
bin != m.end(); ++bin)
132132
{
133133
for (unsigned int i = 0; i < bin->second.size(); ++i) {
134134
const CellData cell = bin->second[i];
135-
if (!seen[cell.index_]) {
136-
seen[cell.index_] = true;
135+
const auto index = costmap->getIndex(cell.x_, cell.y_);
136+
if (!seen[index]) {
137+
seen[index] = true;
137138
unsigned int dx = (cell.x_ > cell.src_x_) ? cell.x_ - cell.src_x_ : cell.src_x_ - cell.x_;
138139
unsigned int dy = (cell.y_ > cell.src_y_) ? cell.y_ - cell.src_y_ : cell.src_y_ - cell.y_;
139140
double dist = std::hypot(dx, dy);
@@ -152,23 +153,19 @@ void TestNode::validatePointInflation(
152153
}
153154

154155
if (cell.x_ > 0) {
155-
CellData data(costmap->getIndex(cell.x_ - 1, cell.y_),
156-
cell.x_ - 1, cell.y_, cell.src_x_, cell.src_y_);
156+
CellData data(cell.x_ - 1, cell.y_, cell.src_x_, cell.src_y_);
157157
m[dist].push_back(data);
158158
}
159159
if (cell.y_ > 0) {
160-
CellData data(costmap->getIndex(cell.x_, cell.y_ - 1),
161-
cell.x_, cell.y_ - 1, cell.src_x_, cell.src_y_);
160+
CellData data(cell.x_, cell.y_ - 1, cell.src_x_, cell.src_y_);
162161
m[dist].push_back(data);
163162
}
164163
if (cell.x_ < costmap->getSizeInCellsX() - 1) {
165-
CellData data(costmap->getIndex(cell.x_ + 1, cell.y_),
166-
cell.x_ + 1, cell.y_, cell.src_x_, cell.src_y_);
164+
CellData data(cell.x_ + 1, cell.y_, cell.src_x_, cell.src_y_);
167165
m[dist].push_back(data);
168166
}
169167
if (cell.y_ < costmap->getSizeInCellsY() - 1) {
170-
CellData data(costmap->getIndex(cell.x_, cell.y_ + 1),
171-
cell.x_, cell.y_ + 1, cell.src_x_, cell.src_y_);
168+
CellData data(cell.x_, cell.y_ + 1, cell.src_x_, cell.src_y_);
172169
m[dist].push_back(data);
173170
}
174171
}

0 commit comments

Comments
 (0)