hybrid_grid.hpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622
  1. /*
  2. * Copyright 2016 The Cartographer Authors
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #ifndef CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_
  17. #define CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_
  18. #include <array>
  19. #include <cmath>
  20. #include <limits>
  21. #include <utility>
  22. #include <vector>
  23. #include "Eigen/Core"
  24. #include "common/math.h"
  25. #include "common/port.h"
  26. //#include "probability_values.h"
  27. #include "glog/logging.h"
  28. // Converts an 'index' with each dimension from 0 to 2^'bits' - 1 to a flat
  29. // z-major index.
  30. inline int ToFlatIndex(const Eigen::Array3i& index, const int bits) {
  31. DCHECK((index >= 0).all() && (index < (1 << bits)).all()) << index;
  32. return (((index.z() << bits) + index.y()) << bits) + index.x();
  33. }
  34. // Converts a flat z-major 'index' to a 3-dimensional index with each dimension
  35. // from 0 to 2^'bits' - 1.
  36. inline Eigen::Array3i To3DIndex(const int index, const int bits) {
  37. DCHECK_LT(index, 1 << (3 * bits));
  38. const int mask = (1 << bits) - 1;
  39. return Eigen::Array3i(index & mask, (index >> bits) & mask,
  40. (index >> bits) >> bits);
  41. }
  42. // A function to compare value to the default value. (Allows specializations).
  43. template <typename TValueType>
  44. bool IsDefaultValue(const TValueType& v) {
  45. return v == TValueType();
  46. }
  47. // Specialization to compare a std::vector to the default value.
  48. template <typename TElementType>
  49. bool IsDefaultValue(const std::vector<TElementType>& v) {
  50. return v.empty();
  51. }
  52. // A flat grid of '2^kBits' x '2^kBits' x '2^kBits' voxels storing values of
  53. // type 'ValueType' in contiguous memory. Indices in each dimension are 0-based.
  54. // 包含自定义类型的数组
  55. template <typename TValueType, int kBits>
  56. class FlatGrid
  57. {
  58. public:
  59. using ValueType = TValueType;
  60. // Creates a new flat grid with all values being default constructed.
  61. FlatGrid()
  62. {
  63. for (ValueType &value : cells_)
  64. {
  65. value = ValueType();
  66. }
  67. }
  68. FlatGrid(const FlatGrid &) = delete;
  69. FlatGrid &operator=(const FlatGrid &) = delete;
  70. // Returns the number of voxels per dimension.
  71. static int grid_size()
  72. {
  73. return 1 << kBits;
  74. }
  75. // Returns the value stored at 'index', each dimension of 'index' being
  76. // between 0 and grid_size() - 1.
  77. ValueType value(const Eigen::Array3i &index) const
  78. {
  79. return cells_[ToFlatIndex(index, kBits)];
  80. }
  81. // Returns a pointer to a value to allow changing it.
  82. ValueType *mutable_value(const Eigen::Array3i &index)
  83. {
  84. return &cells_[ToFlatIndex(index, kBits)];
  85. }
  86. // An iterator for iterating over all values not comparing equal to the
  87. // default constructed value.
  88. class Iterator
  89. {
  90. public:
  91. Iterator() : current_(nullptr), end_(nullptr)
  92. {
  93. }
  94. explicit Iterator(const FlatGrid &flat_grid)
  95. : current_(flat_grid.cells_.data()),
  96. end_(flat_grid.cells_.data() + flat_grid.cells_.size())
  97. {
  98. while (!Done() && IsDefaultValue(*current_))
  99. {
  100. ++current_;
  101. }
  102. }
  103. void Next()
  104. {
  105. DCHECK(!Done());
  106. do
  107. {
  108. ++current_;
  109. } while (!Done() && IsDefaultValue(*current_));
  110. }
  111. bool Done() const
  112. {
  113. return current_ == end_;
  114. }
  115. Eigen::Array3i GetCellIndex() const
  116. {
  117. DCHECK(!Done());
  118. const int index = (1 << (3 * kBits)) - (end_ - current_);
  119. return To3DIndex(index, kBits);
  120. }
  121. const ValueType &GetValue() const
  122. {
  123. DCHECK(!Done());
  124. return *current_;
  125. }
  126. private:
  127. const ValueType *current_;
  128. const ValueType *end_;
  129. };
  130. private:
  131. std::array<ValueType, 1 << (3 * kBits)> cells_;
  132. };
  133. // A grid consisting of '2^kBits' x '2^kBits' x '2^kBits' grids of type
  134. // 'WrappedGrid'. Wrapped grids are constructed on first access via
  135. // 'mutable_value()'.
  136. // grid 的 grid
  137. template <typename WrappedGrid, int kBits>
  138. class NestedGrid
  139. {
  140. public:
  141. using ValueType = typename WrappedGrid::ValueType;
  142. // Returns the number of voxels per dimension.
  143. static int grid_size()
  144. {
  145. return WrappedGrid::grid_size() << kBits;
  146. }
  147. // Returns the value stored at 'index', each dimension of 'index' being
  148. // between 0 and grid_size() - 1.
  149. ValueType value(const Eigen::Array3i &index) const
  150. {
  151. const Eigen::Array3i meta_index = GetMetaIndex(index);
  152. const WrappedGrid *const meta_cell =
  153. meta_cells_[ToFlatIndex(meta_index, kBits)].get();
  154. if (meta_cell == nullptr)
  155. {
  156. return ValueType();
  157. }
  158. const Eigen::Array3i inner_index =
  159. index - meta_index * WrappedGrid::grid_size();
  160. return meta_cell->value(inner_index);
  161. }
  162. // Returns a pointer to the value at 'index' to allow changing it. If
  163. // necessary a new wrapped grid is constructed to contain that value.
  164. ValueType *mutable_value(const Eigen::Array3i &index)
  165. {
  166. const Eigen::Array3i meta_index = GetMetaIndex(index);
  167. std::unique_ptr<WrappedGrid> &meta_cell =
  168. meta_cells_[ToFlatIndex(meta_index, kBits)];
  169. if (meta_cell == nullptr)
  170. {
  171. meta_cell = std::make_unique<WrappedGrid>();
  172. }
  173. const Eigen::Array3i inner_index =
  174. index - meta_index * WrappedGrid::grid_size();
  175. return meta_cell->mutable_value(inner_index);
  176. }
  177. // An iterator for iterating over all values not comparing equal to the
  178. // default constructed value.
  179. class Iterator
  180. {
  181. public:
  182. Iterator() : current_(nullptr), end_(nullptr), nested_iterator_()
  183. {
  184. }
  185. explicit Iterator(const NestedGrid &nested_grid)
  186. : current_(nested_grid.meta_cells_.data()),
  187. end_(nested_grid.meta_cells_.data() + nested_grid.meta_cells_.size()),
  188. nested_iterator_()
  189. {
  190. AdvanceToValidNestedIterator();
  191. }
  192. void Next()
  193. {
  194. DCHECK(!Done());
  195. nested_iterator_.Next();
  196. if (!nested_iterator_.Done())
  197. {
  198. return;
  199. }
  200. ++current_;
  201. AdvanceToValidNestedIterator();
  202. }
  203. bool Done() const
  204. {
  205. return current_ == end_;
  206. }
  207. Eigen::Array3i GetCellIndex() const
  208. {
  209. DCHECK(!Done());
  210. const int index = (1 << (3 * kBits)) - (end_ - current_);
  211. return To3DIndex(index, kBits) * WrappedGrid::grid_size() +
  212. nested_iterator_.GetCellIndex();
  213. }
  214. const ValueType &GetValue() const
  215. {
  216. DCHECK(!Done());
  217. return nested_iterator_.GetValue();
  218. }
  219. private:
  220. void AdvanceToValidNestedIterator()
  221. {
  222. for (; !Done(); ++current_)
  223. {
  224. if (*current_ != nullptr)
  225. {
  226. nested_iterator_ = typename WrappedGrid::Iterator(**current_);
  227. if (!nested_iterator_.Done())
  228. {
  229. break;
  230. }
  231. }
  232. }
  233. }
  234. const std::unique_ptr<WrappedGrid> *current_;
  235. const std::unique_ptr<WrappedGrid> *end_;
  236. typename WrappedGrid::Iterator nested_iterator_;
  237. };
  238. private:
  239. // Returns the Eigen::Array3i (meta) index of the meta cell containing
  240. // 'index'.
  241. Eigen::Array3i GetMetaIndex(const Eigen::Array3i &index) const
  242. {
  243. DCHECK((index >= 0).all()) << index;
  244. const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
  245. DCHECK((meta_index < (1 << kBits)).all()) << index;
  246. return meta_index;
  247. }
  248. std::array<std::unique_ptr<WrappedGrid>, 1 << (3 * kBits)> meta_cells_;
  249. };
  250. // A grid consisting of 2x2x2 grids of type 'WrappedGrid' initially. Wrapped
  251. // grids are constructed on first access via 'mutable_value()'. If necessary,
  252. // the grid grows to twice the size in each dimension. The range of indices is
  253. // (almost) symmetric around the origin, i.e. negative indices are allowed.
  254. template <typename WrappedGrid>
  255. class DynamicGrid
  256. {
  257. public:
  258. using ValueType = typename WrappedGrid::ValueType;
  259. DynamicGrid() : bits_(1), meta_cells_(8)
  260. {
  261. }
  262. DynamicGrid(DynamicGrid &&) = default;
  263. DynamicGrid &operator=(DynamicGrid &&) = default;
  264. // Returns the current number of voxels per dimension.
  265. int grid_size() const
  266. {
  267. return WrappedGrid::grid_size() << bits_;
  268. }
  269. // Returns the value stored at 'index'.
  270. ValueType value(const Eigen::Array3i &index) const
  271. {
  272. const Eigen::Array3i shifted_index = index + (grid_size() >> 1);
  273. // The cast to unsigned is for performance to check with 3 comparisons
  274. // shifted_index.[xyz] >= 0 and shifted_index.[xyz] < grid_size.
  275. if ((shifted_index.cast<unsigned int>() >= grid_size()).any())
  276. {
  277. return ValueType();
  278. }
  279. const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
  280. const WrappedGrid *const meta_cell =
  281. meta_cells_[ToFlatIndex(meta_index, bits_)].get();
  282. if (meta_cell == nullptr)
  283. {
  284. return ValueType();
  285. }
  286. const Eigen::Array3i inner_index =
  287. shifted_index - meta_index * WrappedGrid::grid_size();
  288. return meta_cell->value(inner_index);
  289. }
  290. // Returns a pointer to the value at 'index' to allow changing it, dynamically
  291. // growing the DynamicGrid and constructing new WrappedGrids as needed.
  292. ValueType *mutable_value(const Eigen::Array3i &index)
  293. {
  294. const Eigen::Array3i shifted_index = index+ (grid_size() >> 1);
  295. // The cast to unsigned is for performance to check with 3 comparisons
  296. //shifted_index.[xyz] >= 0 and shifted_index.[xyz] < grid_size.
  297. if ((shifted_index.cast<unsigned int>() >= grid_size()).any())
  298. {
  299. LOG(ERROR)<<shifted_index.transpose()<<" bound:"<<grid_size();
  300. LOG(ERROR)<<" out of bound";
  301. //Grow();
  302. return 0;//mutable_value(index);
  303. }
  304. const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
  305. std::unique_ptr<WrappedGrid> &meta_cell =
  306. meta_cells_[ToFlatIndex(meta_index, bits_)];
  307. if (meta_cell == nullptr)
  308. {
  309. meta_cell = std::make_unique<WrappedGrid>();
  310. }
  311. const Eigen::Array3i inner_index =
  312. shifted_index - meta_index * WrappedGrid::grid_size();
  313. return meta_cell->mutable_value(inner_index);
  314. }
  315. // An iterator for iterating over all values not comparing equal to the
  316. // default constructed value.
  317. class Iterator
  318. {
  319. public:
  320. explicit Iterator(const DynamicGrid &dynamic_grid)
  321. : bits_(dynamic_grid.bits_),
  322. current_(dynamic_grid.meta_cells_.data()),
  323. end_(dynamic_grid.meta_cells_.data() +
  324. dynamic_grid.meta_cells_.size()),
  325. nested_iterator_()
  326. {
  327. AdvanceToValidNestedIterator();
  328. }
  329. void Next()
  330. {
  331. DCHECK(!Done());
  332. nested_iterator_.Next();
  333. if (!nested_iterator_.Done())
  334. {
  335. return;
  336. }
  337. ++current_;
  338. AdvanceToValidNestedIterator();
  339. }
  340. bool Done() const
  341. {
  342. return current_ == end_;
  343. }
  344. Eigen::Array3i GetCellIndex() const
  345. {
  346. DCHECK(!Done());
  347. const int outer_index = (1 << (3 * bits_)) - (end_ - current_);
  348. const Eigen::Array3i shifted_index =
  349. To3DIndex(outer_index, bits_) * WrappedGrid::grid_size() +
  350. nested_iterator_.GetCellIndex();
  351. return shifted_index - ((1 << (bits_ - 1)) * WrappedGrid::grid_size());
  352. }
  353. const ValueType &GetValue() const
  354. {
  355. DCHECK(!Done());
  356. return nested_iterator_.GetValue();
  357. }
  358. void AdvanceToEnd()
  359. {
  360. current_ = end_;
  361. }
  362. const std::pair<Eigen::Array3i, ValueType> operator*() const
  363. {
  364. return std::pair<Eigen::Array3i, ValueType>(GetCellIndex(), GetValue());
  365. }
  366. Iterator &operator++()
  367. {
  368. Next();
  369. return *this;
  370. }
  371. bool operator!=(const Iterator &it) const
  372. {
  373. return it.current_ != current_;
  374. }
  375. private:
  376. void AdvanceToValidNestedIterator()
  377. {
  378. for (; !Done(); ++current_)
  379. {
  380. if (*current_ != nullptr)
  381. {
  382. nested_iterator_ = typename WrappedGrid::Iterator(**current_);
  383. if (!nested_iterator_.Done())
  384. {
  385. break;
  386. }
  387. }
  388. }
  389. }
  390. int bits_;
  391. const std::unique_ptr<WrappedGrid> *current_;
  392. const std::unique_ptr<WrappedGrid> *const end_;
  393. typename WrappedGrid::Iterator nested_iterator_;
  394. };
  395. private:
  396. // Returns the Eigen::Array3i (meta) index of the meta cell containing
  397. // 'index'.
  398. Eigen::Array3i GetMetaIndex(const Eigen::Array3i &index) const
  399. {
  400. DCHECK((index >= 0).all()) << index;
  401. const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
  402. DCHECK((meta_index < (1 << bits_)).all()) << index;
  403. return meta_index;
  404. }
  405. // Grows this grid by a factor of 2 in each of the 3 dimensions.
  406. void Grow()
  407. {
  408. const int new_bits = bits_ + 1;
  409. CHECK_LE(new_bits, 8);
  410. std::vector<std::unique_ptr<WrappedGrid>> new_meta_cells_(
  411. 8 * meta_cells_.size());
  412. for (int z = 0; z != (1 << bits_); ++z)
  413. {
  414. for (int y = 0; y != (1 << bits_); ++y)
  415. {
  416. for (int x = 0; x != (1 << bits_); ++x)
  417. {
  418. const Eigen::Array3i original_meta_index(x, y, z);
  419. const Eigen::Array3i new_meta_index =
  420. original_meta_index + (1 << (bits_ - 1));
  421. new_meta_cells_[ToFlatIndex(new_meta_index, new_bits)] =
  422. std::move(meta_cells_[ToFlatIndex(original_meta_index, bits_)]);
  423. }
  424. }
  425. }
  426. meta_cells_ = std::move(new_meta_cells_);
  427. bits_ = new_bits;
  428. }
  429. int bits_;
  430. std::vector<std::unique_ptr<WrappedGrid>> meta_cells_;
  431. };
  432. template <typename ValueType>
  433. using GridBase = DynamicGrid<NestedGrid<FlatGrid<ValueType, 3>, 3>>;
  434. // Represents a 3D grid as a wide, shallow tree.
  435. template <typename ValueType>
  436. class HybridGridBase : public GridBase<ValueType>
  437. {
  438. public:
  439. using Iterator = typename GridBase<ValueType>::Iterator;
  440. // Creates a new tree-based probability grid with voxels having edge length
  441. // 'resolution' around the origin which becomes the center of the cell at
  442. // index (0, 0, 0).
  443. explicit HybridGridBase(const float resolution) : resolution_(resolution)
  444. {
  445. }
  446. float resolution() const
  447. {
  448. return resolution_;
  449. }
  450. // Returns the index of the cell containing the 'point'. Indices are integer
  451. // vectors identifying cells, for this the coordinates are rounded to the next
  452. // multiple of the resolution.
  453. Eigen::Array3i GetCellIndex(const Eigen::Vector3f &point) const
  454. {
  455. Eigen::Array3f index = point.array() / resolution_;
  456. return Eigen::Array3i(common::RoundToInt(index.x()),
  457. common::RoundToInt(index.y()),
  458. common::RoundToInt(index.z()));
  459. }
  460. // Returns one of the octants, (0, 0, 0), (1, 0, 0), ..., (1, 1, 1).
  461. static Eigen::Array3i GetOctant(const int i)
  462. {
  463. DCHECK_GE(i, 0);
  464. DCHECK_LT(i, 8);
  465. return Eigen::Array3i(static_cast<bool>(i & 1), static_cast<bool>(i & 2),
  466. static_cast<bool>(i & 4));
  467. }
  468. // Returns the center of the cell at 'index'.
  469. Eigen::Vector3f GetCenterOfCell(const Eigen::Array3i &index) const
  470. {
  471. return index.matrix().cast<float>() * resolution_;
  472. }
  473. // Iterator functions for range-based for loops.
  474. Iterator begin() const
  475. {
  476. return Iterator(*this);
  477. }
  478. Iterator end() const
  479. {
  480. Iterator it(*this);
  481. it.AdvanceToEnd();
  482. return it;
  483. }
  484. private:
  485. // Edge length of each voxel.
  486. const float resolution_;
  487. };
  488. class HybridGrid : public HybridGridBase<float>
  489. {
  490. public:
  491. explicit HybridGrid(const float resolution)
  492. : HybridGridBase<float>(resolution)
  493. {
  494. }
  495. // Sets the probability of the cell at 'index' to the given 'probability'.
  496. void SetProbability(const Eigen::Array3i &index, const float probability)
  497. {
  498. *mutable_value(index) = probability;
  499. }
  500. // Returns the probability of the cell with 'index'.
  501. float GetProbability(const Eigen::Array3i &index) const
  502. {
  503. return value(index);
  504. }
  505. // Returns true if the probability at the specified 'index' is known.
  506. bool IsKnown(const Eigen::Array3i &index) const
  507. {
  508. return value(index) != 0;
  509. }
  510. private:
  511. // Markers at changed cells.
  512. std::vector<ValueType *> update_indices_;
  513. };
  514. /*struct AverageIntensityData {
  515. float sum = 0.f;
  516. int count = 0;
  517. };
  518. class IntensityHybridGrid : public HybridGridBase<AverageIntensityData> {
  519. public:
  520. explicit IntensityHybridGrid(const float resolution)
  521. : HybridGridBase<AverageIntensityData>(resolution) {}
  522. void AddIntensity(const Eigen::Array3i& index, const float intensity) {
  523. AverageIntensityData* const cell = mutable_value(index);
  524. cell->count += 1;
  525. cell->sum += intensity;
  526. }
  527. float GetIntensity(const Eigen::Array3i& index) const {
  528. const AverageIntensityData& cell = value(index);
  529. if (cell.count == 0) {
  530. return 0.f;
  531. } else {
  532. return cell.sum / cell.count;
  533. }
  534. }
  535. };
  536. */
  537. #endif // CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_