hybrid_grid.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_
00018 #define CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_
00019 
00020 #include <array>
00021 #include <cmath>
00022 #include <limits>
00023 #include <utility>
00024 #include <vector>
00025 
00026 #include "Eigen/Core"
00027 #include "absl/memory/memory.h"
00028 #include "cartographer/common/math.h"
00029 #include "cartographer/common/port.h"
00030 #include "cartographer/mapping/probability_values.h"
00031 #include "cartographer/mapping/proto/3d/hybrid_grid.pb.h"
00032 #include "cartographer/transform/transform.h"
00033 #include "glog/logging.h"
00034 
00035 namespace cartographer {
00036 namespace mapping {
00037 
00038 // Converts an 'index' with each dimension from 0 to 2^'bits' - 1 to a flat
00039 // z-major index.
00040 inline int ToFlatIndex(const Eigen::Array3i& index, const int bits) {
00041   DCHECK((index >= 0).all() && (index < (1 << bits)).all()) << index;
00042   return (((index.z() << bits) + index.y()) << bits) + index.x();
00043 }
00044 
00045 // Converts a flat z-major 'index' to a 3-dimensional index with each dimension
00046 // from 0 to 2^'bits' - 1.
00047 inline Eigen::Array3i To3DIndex(const int index, const int bits) {
00048   DCHECK_LT(index, 1 << (3 * bits));
00049   const int mask = (1 << bits) - 1;
00050   return Eigen::Array3i(index & mask, (index >> bits) & mask,
00051                         (index >> bits) >> bits);
00052 }
00053 
00054 // A function to compare value to the default value. (Allows specializations).
00055 template <typename TValueType>
00056 bool IsDefaultValue(const TValueType& v) {
00057   return v == TValueType();
00058 }
00059 
00060 // Specialization to compare a std::vector to the default value.
00061 template <typename TElementType>
00062 bool IsDefaultValue(const std::vector<TElementType>& v) {
00063   return v.empty();
00064 }
00065 
00066 // A flat grid of '2^kBits' x '2^kBits' x '2^kBits' voxels storing values of
00067 // type 'ValueType' in contiguous memory. Indices in each dimension are 0-based.
00068 template <typename TValueType, int kBits>
00069 class FlatGrid {
00070  public:
00071   using ValueType = TValueType;
00072 
00073   // Creates a new flat grid with all values being default constructed.
00074   FlatGrid() {
00075     for (ValueType& value : cells_) {
00076       value = ValueType();
00077     }
00078   }
00079 
00080   FlatGrid(const FlatGrid&) = delete;
00081   FlatGrid& operator=(const FlatGrid&) = delete;
00082 
00083   // Returns the number of voxels per dimension.
00084   static int grid_size() { return 1 << kBits; }
00085 
00086   // Returns the value stored at 'index', each dimension of 'index' being
00087   // between 0 and grid_size() - 1.
00088   ValueType value(const Eigen::Array3i& index) const {
00089     return cells_[ToFlatIndex(index, kBits)];
00090   }
00091 
00092   // Returns a pointer to a value to allow changing it.
00093   ValueType* mutable_value(const Eigen::Array3i& index) {
00094     return &cells_[ToFlatIndex(index, kBits)];
00095   }
00096 
00097   // An iterator for iterating over all values not comparing equal to the
00098   // default constructed value.
00099   class Iterator {
00100    public:
00101     Iterator() : current_(nullptr), end_(nullptr) {}
00102 
00103     explicit Iterator(const FlatGrid& flat_grid)
00104         : current_(flat_grid.cells_.data()),
00105           end_(flat_grid.cells_.data() + flat_grid.cells_.size()) {
00106       while (!Done() && IsDefaultValue(*current_)) {
00107         ++current_;
00108       }
00109     }
00110 
00111     void Next() {
00112       DCHECK(!Done());
00113       do {
00114         ++current_;
00115       } while (!Done() && IsDefaultValue(*current_));
00116     }
00117 
00118     bool Done() const { return current_ == end_; }
00119 
00120     Eigen::Array3i GetCellIndex() const {
00121       DCHECK(!Done());
00122       const int index = (1 << (3 * kBits)) - (end_ - current_);
00123       return To3DIndex(index, kBits);
00124     }
00125 
00126     const ValueType& GetValue() const {
00127       DCHECK(!Done());
00128       return *current_;
00129     }
00130 
00131    private:
00132     const ValueType* current_;
00133     const ValueType* end_;
00134   };
00135 
00136  private:
00137   std::array<ValueType, 1 << (3 * kBits)> cells_;
00138 };
00139 
00140 // A grid consisting of '2^kBits' x '2^kBits' x '2^kBits' grids of type
00141 // 'WrappedGrid'. Wrapped grids are constructed on first access via
00142 // 'mutable_value()'.
00143 template <typename WrappedGrid, int kBits>
00144 class NestedGrid {
00145  public:
00146   using ValueType = typename WrappedGrid::ValueType;
00147 
00148   // Returns the number of voxels per dimension.
00149   static int grid_size() { return WrappedGrid::grid_size() << kBits; }
00150 
00151   // Returns the value stored at 'index', each dimension of 'index' being
00152   // between 0 and grid_size() - 1.
00153   ValueType value(const Eigen::Array3i& index) const {
00154     const Eigen::Array3i meta_index = GetMetaIndex(index);
00155     const WrappedGrid* const meta_cell =
00156         meta_cells_[ToFlatIndex(meta_index, kBits)].get();
00157     if (meta_cell == nullptr) {
00158       return ValueType();
00159     }
00160     const Eigen::Array3i inner_index =
00161         index - meta_index * WrappedGrid::grid_size();
00162     return meta_cell->value(inner_index);
00163   }
00164 
00165   // Returns a pointer to the value at 'index' to allow changing it. If
00166   // necessary a new wrapped grid is constructed to contain that value.
00167   ValueType* mutable_value(const Eigen::Array3i& index) {
00168     const Eigen::Array3i meta_index = GetMetaIndex(index);
00169     std::unique_ptr<WrappedGrid>& meta_cell =
00170         meta_cells_[ToFlatIndex(meta_index, kBits)];
00171     if (meta_cell == nullptr) {
00172       meta_cell = absl::make_unique<WrappedGrid>();
00173     }
00174     const Eigen::Array3i inner_index =
00175         index - meta_index * WrappedGrid::grid_size();
00176     return meta_cell->mutable_value(inner_index);
00177   }
00178 
00179   // An iterator for iterating over all values not comparing equal to the
00180   // default constructed value.
00181   class Iterator {
00182    public:
00183     Iterator() : current_(nullptr), end_(nullptr), nested_iterator_() {}
00184 
00185     explicit Iterator(const NestedGrid& nested_grid)
00186         : current_(nested_grid.meta_cells_.data()),
00187           end_(nested_grid.meta_cells_.data() + nested_grid.meta_cells_.size()),
00188           nested_iterator_() {
00189       AdvanceToValidNestedIterator();
00190     }
00191 
00192     void Next() {
00193       DCHECK(!Done());
00194       nested_iterator_.Next();
00195       if (!nested_iterator_.Done()) {
00196         return;
00197       }
00198       ++current_;
00199       AdvanceToValidNestedIterator();
00200     }
00201 
00202     bool Done() const { return current_ == end_; }
00203 
00204     Eigen::Array3i GetCellIndex() const {
00205       DCHECK(!Done());
00206       const int index = (1 << (3 * kBits)) - (end_ - current_);
00207       return To3DIndex(index, kBits) * WrappedGrid::grid_size() +
00208              nested_iterator_.GetCellIndex();
00209     }
00210 
00211     const ValueType& GetValue() const {
00212       DCHECK(!Done());
00213       return nested_iterator_.GetValue();
00214     }
00215 
00216    private:
00217     void AdvanceToValidNestedIterator() {
00218       for (; !Done(); ++current_) {
00219         if (*current_ != nullptr) {
00220           nested_iterator_ = typename WrappedGrid::Iterator(**current_);
00221           if (!nested_iterator_.Done()) {
00222             break;
00223           }
00224         }
00225       }
00226     }
00227 
00228     const std::unique_ptr<WrappedGrid>* current_;
00229     const std::unique_ptr<WrappedGrid>* end_;
00230     typename WrappedGrid::Iterator nested_iterator_;
00231   };
00232 
00233  private:
00234   // Returns the Eigen::Array3i (meta) index of the meta cell containing
00235   // 'index'.
00236   Eigen::Array3i GetMetaIndex(const Eigen::Array3i& index) const {
00237     DCHECK((index >= 0).all()) << index;
00238     const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
00239     DCHECK((meta_index < (1 << kBits)).all()) << index;
00240     return meta_index;
00241   }
00242 
00243   std::array<std::unique_ptr<WrappedGrid>, 1 << (3 * kBits)> meta_cells_;
00244 };
00245 
00246 // A grid consisting of 2x2x2 grids of type 'WrappedGrid' initially. Wrapped
00247 // grids are constructed on first access via 'mutable_value()'. If necessary,
00248 // the grid grows to twice the size in each dimension. The range of indices is
00249 // (almost) symmetric around the origin, i.e. negative indices are allowed.
00250 template <typename WrappedGrid>
00251 class DynamicGrid {
00252  public:
00253   using ValueType = typename WrappedGrid::ValueType;
00254 
00255   DynamicGrid() : bits_(1), meta_cells_(8) {}
00256   DynamicGrid(DynamicGrid&&) = default;
00257   DynamicGrid& operator=(DynamicGrid&&) = default;
00258 
00259   // Returns the current number of voxels per dimension.
00260   int grid_size() const { return WrappedGrid::grid_size() << bits_; }
00261 
00262   // Returns the value stored at 'index'.
00263   ValueType value(const Eigen::Array3i& index) const {
00264     const Eigen::Array3i shifted_index = index + (grid_size() >> 1);
00265     // The cast to unsigned is for performance to check with 3 comparisons
00266     // shifted_index.[xyz] >= 0 and shifted_index.[xyz] < grid_size.
00267     if ((shifted_index.cast<unsigned int>() >= grid_size()).any()) {
00268       return ValueType();
00269     }
00270     const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
00271     const WrappedGrid* const meta_cell =
00272         meta_cells_[ToFlatIndex(meta_index, bits_)].get();
00273     if (meta_cell == nullptr) {
00274       return ValueType();
00275     }
00276     const Eigen::Array3i inner_index =
00277         shifted_index - meta_index * WrappedGrid::grid_size();
00278     return meta_cell->value(inner_index);
00279   }
00280 
00281   // Returns a pointer to the value at 'index' to allow changing it, dynamically
00282   // growing the DynamicGrid and constructing new WrappedGrids as needed.
00283   ValueType* mutable_value(const Eigen::Array3i& index) {
00284     const Eigen::Array3i shifted_index = index + (grid_size() >> 1);
00285     // The cast to unsigned is for performance to check with 3 comparisons
00286     // shifted_index.[xyz] >= 0 and shifted_index.[xyz] < grid_size.
00287     if ((shifted_index.cast<unsigned int>() >= grid_size()).any()) {
00288       Grow();
00289       return mutable_value(index);
00290     }
00291     const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
00292     std::unique_ptr<WrappedGrid>& meta_cell =
00293         meta_cells_[ToFlatIndex(meta_index, bits_)];
00294     if (meta_cell == nullptr) {
00295       meta_cell = absl::make_unique<WrappedGrid>();
00296     }
00297     const Eigen::Array3i inner_index =
00298         shifted_index - meta_index * WrappedGrid::grid_size();
00299     return meta_cell->mutable_value(inner_index);
00300   }
00301 
00302   // An iterator for iterating over all values not comparing equal to the
00303   // default constructed value.
00304   class Iterator {
00305    public:
00306     explicit Iterator(const DynamicGrid& dynamic_grid)
00307         : bits_(dynamic_grid.bits_),
00308           current_(dynamic_grid.meta_cells_.data()),
00309           end_(dynamic_grid.meta_cells_.data() +
00310                dynamic_grid.meta_cells_.size()),
00311           nested_iterator_() {
00312       AdvanceToValidNestedIterator();
00313     }
00314 
00315     void Next() {
00316       DCHECK(!Done());
00317       nested_iterator_.Next();
00318       if (!nested_iterator_.Done()) {
00319         return;
00320       }
00321       ++current_;
00322       AdvanceToValidNestedIterator();
00323     }
00324 
00325     bool Done() const { return current_ == end_; }
00326 
00327     Eigen::Array3i GetCellIndex() const {
00328       DCHECK(!Done());
00329       const int outer_index = (1 << (3 * bits_)) - (end_ - current_);
00330       const Eigen::Array3i shifted_index =
00331           To3DIndex(outer_index, bits_) * WrappedGrid::grid_size() +
00332           nested_iterator_.GetCellIndex();
00333       return shifted_index - ((1 << (bits_ - 1)) * WrappedGrid::grid_size());
00334     }
00335 
00336     const ValueType& GetValue() const {
00337       DCHECK(!Done());
00338       return nested_iterator_.GetValue();
00339     }
00340 
00341     void AdvanceToEnd() { current_ = end_; }
00342 
00343     const std::pair<Eigen::Array3i, ValueType> operator*() const {
00344       return std::pair<Eigen::Array3i, ValueType>(GetCellIndex(), GetValue());
00345     }
00346 
00347     Iterator& operator++() {
00348       Next();
00349       return *this;
00350     }
00351 
00352     bool operator!=(const Iterator& it) const {
00353       return it.current_ != current_;
00354     }
00355 
00356    private:
00357     void AdvanceToValidNestedIterator() {
00358       for (; !Done(); ++current_) {
00359         if (*current_ != nullptr) {
00360           nested_iterator_ = typename WrappedGrid::Iterator(**current_);
00361           if (!nested_iterator_.Done()) {
00362             break;
00363           }
00364         }
00365       }
00366     }
00367 
00368     int bits_;
00369     const std::unique_ptr<WrappedGrid>* current_;
00370     const std::unique_ptr<WrappedGrid>* const end_;
00371     typename WrappedGrid::Iterator nested_iterator_;
00372   };
00373 
00374  private:
00375   // Returns the Eigen::Array3i (meta) index of the meta cell containing
00376   // 'index'.
00377   Eigen::Array3i GetMetaIndex(const Eigen::Array3i& index) const {
00378     DCHECK((index >= 0).all()) << index;
00379     const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
00380     DCHECK((meta_index < (1 << bits_)).all()) << index;
00381     return meta_index;
00382   }
00383 
00384   // Grows this grid by a factor of 2 in each of the 3 dimensions.
00385   void Grow() {
00386     const int new_bits = bits_ + 1;
00387     CHECK_LE(new_bits, 8);
00388     std::vector<std::unique_ptr<WrappedGrid>> new_meta_cells_(
00389         8 * meta_cells_.size());
00390     for (int z = 0; z != (1 << bits_); ++z) {
00391       for (int y = 0; y != (1 << bits_); ++y) {
00392         for (int x = 0; x != (1 << bits_); ++x) {
00393           const Eigen::Array3i original_meta_index(x, y, z);
00394           const Eigen::Array3i new_meta_index =
00395               original_meta_index + (1 << (bits_ - 1));
00396           new_meta_cells_[ToFlatIndex(new_meta_index, new_bits)] =
00397               std::move(meta_cells_[ToFlatIndex(original_meta_index, bits_)]);
00398         }
00399       }
00400     }
00401     meta_cells_ = std::move(new_meta_cells_);
00402     bits_ = new_bits;
00403   }
00404 
00405   int bits_;
00406   std::vector<std::unique_ptr<WrappedGrid>> meta_cells_;
00407 };
00408 
00409 template <typename ValueType>
00410 using GridBase = DynamicGrid<NestedGrid<FlatGrid<ValueType, 3>, 3>>;
00411 
00412 // Represents a 3D grid as a wide, shallow tree.
00413 template <typename ValueType>
00414 class HybridGridBase : public GridBase<ValueType> {
00415  public:
00416   using Iterator = typename GridBase<ValueType>::Iterator;
00417 
00418   // Creates a new tree-based probability grid with voxels having edge length
00419   // 'resolution' around the origin which becomes the center of the cell at
00420   // index (0, 0, 0).
00421   explicit HybridGridBase(const float resolution) : resolution_(resolution) {}
00422 
00423   float resolution() const { return resolution_; }
00424 
00425   // Returns the index of the cell containing the 'point'. Indices are integer
00426   // vectors identifying cells, for this the coordinates are rounded to the next
00427   // multiple of the resolution.
00428   Eigen::Array3i GetCellIndex(const Eigen::Vector3f& point) const {
00429     Eigen::Array3f index = point.array() / resolution_;
00430     return Eigen::Array3i(common::RoundToInt(index.x()),
00431                           common::RoundToInt(index.y()),
00432                           common::RoundToInt(index.z()));
00433   }
00434 
00435   // Returns one of the octants, (0, 0, 0), (1, 0, 0), ..., (1, 1, 1).
00436   static Eigen::Array3i GetOctant(const int i) {
00437     DCHECK_GE(i, 0);
00438     DCHECK_LT(i, 8);
00439     return Eigen::Array3i(static_cast<bool>(i & 1), static_cast<bool>(i & 2),
00440                           static_cast<bool>(i & 4));
00441   }
00442 
00443   // Returns the center of the cell at 'index'.
00444   Eigen::Vector3f GetCenterOfCell(const Eigen::Array3i& index) const {
00445     return index.matrix().cast<float>() * resolution_;
00446   }
00447 
00448   // Iterator functions for range-based for loops.
00449   Iterator begin() const { return Iterator(*this); }
00450 
00451   Iterator end() const {
00452     Iterator it(*this);
00453     it.AdvanceToEnd();
00454     return it;
00455   }
00456 
00457  private:
00458   // Edge length of each voxel.
00459   const float resolution_;
00460 };
00461 
00462 // A grid containing probability values stored using 15 bits, and an update
00463 // marker per voxel.
00464 // Points are expected to be close to the origin. Points far from the origin
00465 // require the grid to grow dynamically. For centimeter resolution, points
00466 // can only be tens of meters from the origin.
00467 // The hard limit of cell indexes is +/- 8192 around the origin.
00468 class HybridGrid : public HybridGridBase<uint16> {
00469  public:
00470   explicit HybridGrid(const float resolution)
00471       : HybridGridBase<uint16>(resolution) {}
00472 
00473   explicit HybridGrid(const proto::HybridGrid& proto)
00474       : HybridGrid(proto.resolution()) {
00475     CHECK_EQ(proto.values_size(), proto.x_indices_size());
00476     CHECK_EQ(proto.values_size(), proto.y_indices_size());
00477     CHECK_EQ(proto.values_size(), proto.z_indices_size());
00478     for (int i = 0; i < proto.values_size(); ++i) {
00479       // SetProbability does some error checking for us.
00480       SetProbability(Eigen::Vector3i(proto.x_indices(i), proto.y_indices(i),
00481                                      proto.z_indices(i)),
00482                      ValueToProbability(proto.values(i)));
00483     }
00484   }
00485 
00486   // Sets the probability of the cell at 'index' to the given 'probability'.
00487   void SetProbability(const Eigen::Array3i& index, const float probability) {
00488     *mutable_value(index) = ProbabilityToValue(probability);
00489   }
00490 
00491   // Finishes the update sequence.
00492   void FinishUpdate() {
00493     while (!update_indices_.empty()) {
00494       DCHECK_GE(*update_indices_.back(), kUpdateMarker);
00495       *update_indices_.back() -= kUpdateMarker;
00496       update_indices_.pop_back();
00497     }
00498   }
00499 
00500   // Applies the 'odds' specified when calling ComputeLookupTableToApplyOdds()
00501   // to the probability of the cell at 'index' if the cell has not already been
00502   // updated. Multiple updates of the same cell will be ignored until
00503   // FinishUpdate() is called. Returns true if the cell was updated.
00504   //
00505   // If this is the first call to ApplyOdds() for the specified cell, its value
00506   // will be set to probability corresponding to 'odds'.
00507   bool ApplyLookupTable(const Eigen::Array3i& index,
00508                         const std::vector<uint16>& table) {
00509     DCHECK_EQ(table.size(), kUpdateMarker);
00510     uint16* const cell = mutable_value(index);
00511     if (*cell >= kUpdateMarker) {
00512       return false;
00513     }
00514     update_indices_.push_back(cell);
00515     *cell = table[*cell];
00516     DCHECK_GE(*cell, kUpdateMarker);
00517     return true;
00518   }
00519 
00520   // Returns the probability of the cell with 'index'.
00521   float GetProbability(const Eigen::Array3i& index) const {
00522     return ValueToProbability(value(index));
00523   }
00524 
00525   // Returns true if the probability at the specified 'index' is known.
00526   bool IsKnown(const Eigen::Array3i& index) const { return value(index) != 0; }
00527 
00528   proto::HybridGrid ToProto() const {
00529     CHECK(update_indices_.empty()) << "Serializing a grid during an update is "
00530                                       "not supported. Finish the update first.";
00531     proto::HybridGrid result;
00532     result.set_resolution(resolution());
00533     for (const auto it : *this) {
00534       result.add_x_indices(it.first.x());
00535       result.add_y_indices(it.first.y());
00536       result.add_z_indices(it.first.z());
00537       result.add_values(it.second);
00538     }
00539     return result;
00540   }
00541 
00542  private:
00543   // Markers at changed cells.
00544   std::vector<ValueType*> update_indices_;
00545 };
00546 
00547 }  // namespace mapping
00548 }  // namespace cartographer
00549 
00550 #endif  // CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35