17 #ifndef CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_    18 #define CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_    31 #include "cartographer/mapping_3d/proto/hybrid_grid.pb.h"    33 #include "glog/logging.h"    36 namespace mapping_3d {
    40 inline int ToFlatIndex(
const Eigen::Array3i& index, 
const int bits) {
    41   DCHECK((index >= 0).all() && (index < (1 << bits)).all()) << index;
    42   return (((index.z() << bits) + index.y()) << bits) + index.x();
    47 inline Eigen::Array3i 
To3DIndex(
const int index, 
const int bits) {
    48   DCHECK_LT(index, 1 << (3 * bits));
    49   const int mask = (1 << bits) - 1;
    50   return Eigen::Array3i(index & mask, (index >> bits) & mask,
    51                         (index >> bits) >> bits);
    55 template <
typename TValueType>
    57   return v == TValueType();
    61 template <
typename TElementType>
    68 template <
typename TValueType, 
int kBits>
   122       const int index = (1 << (3 * kBits)) - (
end_ - 
current_);
   137   std::array<ValueType, 1 << (3 * kBits)> 
cells_;
   143 template <
typename WrappedGr
id, 
int kBits>
   149   static int grid_size() { 
return WrappedGrid::grid_size() << kBits; }
   154     const Eigen::Array3i meta_index = GetMetaIndex(index);
   155     const WrappedGrid* 
const meta_cell =
   157     if (meta_cell == 
nullptr) {
   160     const Eigen::Array3i inner_index =
   161         index - meta_index * WrappedGrid::grid_size();
   162     return meta_cell->value(inner_index);
   168     const Eigen::Array3i meta_index = GetMetaIndex(index);
   169     std::unique_ptr<WrappedGrid>& meta_cell =
   171     if (meta_cell == 
nullptr) {
   172       meta_cell = common::make_unique<WrappedGrid>();
   174     const Eigen::Array3i inner_index =
   175         index - meta_index * WrappedGrid::grid_size();
   176     return meta_cell->mutable_value(inner_index);
   186         : 
current_(nested_grid.meta_cells_.data()),
   187           end_(nested_grid.meta_cells_.data() + nested_grid.meta_cells_.size()),
   189       AdvanceToValidNestedIterator();
   194       nested_iterator_.Next();
   195       if (!nested_iterator_.Done()) {
   199       AdvanceToValidNestedIterator();
   206       const int index = (1 << (3 * kBits)) - (
end_ - 
current_);
   207       return To3DIndex(index, kBits) * WrappedGrid::grid_size() +
   208              nested_iterator_.GetCellIndex();
   213       return nested_iterator_.GetValue();
   220           nested_iterator_ = 
typename WrappedGrid::Iterator(**
current_);
   221           if (!nested_iterator_.Done()) {
   229     const std::unique_ptr<WrappedGrid>* 
end_;
   237     DCHECK((index >= 0).all()) << index;
   238     const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
   239     DCHECK((meta_index < (1 << kBits)).all()) << index;
   243   std::array<std::unique_ptr<WrappedGrid>, 1 << (3 * kBits)> meta_cells_;
   250 template <
typename WrappedGr
id>
   260   int grid_size()
 const { 
return WrappedGrid::grid_size() << bits_; }
   264     const Eigen::Array3i shifted_index = index + (
grid_size() >> 1);
   267     if ((shifted_index.cast<
unsigned int>() >= 
grid_size()).any()) {
   270     const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
   271     const WrappedGrid* 
const meta_cell =
   273     if (meta_cell == 
nullptr) {
   276     const Eigen::Array3i inner_index =
   277         shifted_index - meta_index * WrappedGrid::grid_size();
   278     return meta_cell->value(inner_index);
   284     const Eigen::Array3i shifted_index = index + (
grid_size() >> 1);
   287     if ((shifted_index.cast<
unsigned int>() >= 
grid_size()).any()) {
   291     const Eigen::Array3i meta_index = GetMetaIndex(shifted_index);
   292     std::unique_ptr<WrappedGrid>& meta_cell =
   294     if (meta_cell == 
nullptr) {
   295       meta_cell = common::make_unique<WrappedGrid>();
   297     const Eigen::Array3i inner_index =
   298         shifted_index - meta_index * WrappedGrid::grid_size();
   299     return meta_cell->mutable_value(inner_index);
   307         : bits_(dynamic_grid.bits_),
   308           current_(dynamic_grid.meta_cells_.data()),
   309           end_(dynamic_grid.meta_cells_.data() +
   310                dynamic_grid.meta_cells_.size()),
   312       AdvanceToValidNestedIterator();
   317       nested_iterator_.Next();
   318       if (!nested_iterator_.Done()) {
   322       AdvanceToValidNestedIterator();
   329       const int outer_index = (1 << (3 * bits_)) - (
end_ - 
current_);
   330       const Eigen::Array3i shifted_index =
   331           To3DIndex(outer_index, bits_) * WrappedGrid::grid_size() +
   332           nested_iterator_.GetCellIndex();
   333       return shifted_index - ((1 << (bits_ - 1)) * WrappedGrid::grid_size());
   338       return nested_iterator_.GetValue();
   343     const std::pair<Eigen::Array3i, ValueType> 
operator*()
 const {
   360           nested_iterator_ = 
typename WrappedGrid::Iterator(**
current_);
   361           if (!nested_iterator_.Done()) {
   370     const std::unique_ptr<WrappedGrid>* 
const end_;
   378     DCHECK((index >= 0).all()) << index;
   379     const Eigen::Array3i meta_index = index / WrappedGrid::grid_size();
   380     DCHECK((meta_index < (1 << bits_)).all()) << index;
   386     const int new_bits = bits_ + 1;
   387     CHECK_LE(new_bits, 8);
   388     std::vector<std::unique_ptr<WrappedGrid>> new_meta_cells_(
   389         8 * meta_cells_.size());
   390     for (
int z = 0; z != (1 << bits_); ++z) {
   391       for (
int y = 0; y != (1 << bits_); ++y) {
   392         for (
int x = 0; x != (1 << bits_); ++x) {
   393           const Eigen::Array3i original_meta_index(x, y, z);
   394           const Eigen::Array3i new_meta_index =
   395               original_meta_index + (1 << (bits_ - 1));
   396           new_meta_cells_[
ToFlatIndex(new_meta_index, new_bits)] =
   397               std::move(meta_cells_[
ToFlatIndex(original_meta_index, bits_)]);
   401     meta_cells_ = std::move(new_meta_cells_);
   409 template <
typename ValueType>
   413 template <
typename ValueType>
   429     Eigen::Array3f index = point.array() / resolution_;
   439     return Eigen::Array3i(static_cast<bool>(i & 1), static_cast<bool>(i & 2),
   440                           static_cast<bool>(i & 4));
   445     return index.matrix().cast<
float>() * resolution_;
   471     CHECK_EQ(proto.values_size(), proto.x_indices_size());
   472     CHECK_EQ(proto.values_size(), proto.y_indices_size());
   473     CHECK_EQ(proto.values_size(), proto.z_indices_size());
   475     for (
int i = 0; i < proto.values_size(); ++i) {
   477       SetProbability(Eigen::Vector3i(proto.x_indices(i), proto.y_indices(i),
   490     while (!update_indices_.empty()) {
   493       update_indices_.pop_back();
   505                         const std::vector<uint16>& table) {
   511     update_indices_.push_back(cell);
   512     *cell = table[*cell];
   523   bool IsKnown(
const Eigen::Array3i& index)
 const { 
return value(index) != 0; }
   531   proto::HybridGrid result;
   533   for (
const auto it : grid) {
   534     result.add_x_indices(it.first.x());
   535     result.add_y_indices(it.first.y());
   536     result.add_z_indices(it.first.z());
   537     result.add_values(it.second);
   545 #endif  // CARTOGRAPHER_MAPPING_3D_HYBRID_GRID_H_ 
std::array< ValueType, 1<< (3 *kBits)> cells_
FlatGrid & operator=(const FlatGrid &)=delete
Eigen::Vector3f GetCenterOfCell(const Eigen::Array3i &index) const 
Eigen::Array3i GetCellIndex(const Eigen::Vector3f &point) const 
const std::unique_ptr< WrappedGrid > * current_
HybridGridBase(const float resolution)
ValueType * mutable_value(const Eigen::Array3i &index)
float GetProbability(const Eigen::Array3i &index) const 
Eigen::Array3i To3DIndex(const int index, const int bits)
Iterator(const DynamicGrid &dynamic_grid)
const ValueType * current_
const std::unique_ptr< WrappedGrid > * end_
bool operator!=(const Iterator &it) const 
void AdvanceToValidNestedIterator()
int RoundToInt(const float x)
const std::pair< Eigen::Array3i, ValueType > operator*() const 
Eigen::Array3i GetMetaIndex(const Eigen::Array3i &index) const 
bool IsKnown(const Eigen::Array3i &index) const 
Eigen::Array3i GetCellIndex() const 
WrappedGrid::Iterator nested_iterator_
const std::unique_ptr< WrappedGrid > *const end_
float ValueToProbability(const uint16 value)
const std::unique_ptr< WrappedGrid > * current_
Iterator(const NestedGrid &nested_grid)
ValueType * mutable_value(const Eigen::Array3i &index)
const ValueType & GetValue() const 
typename Grid< cartographer::io::OutlierRemovingPointsProcessor::VoxelData >::Iterator Iterator
const ValueType & GetValue() const 
std::vector< std::unique_ptr< WrappedGrid > > meta_cells_
int ToFlatIndex(const Eigen::Array3i &index, const int bits)
typename WrappedGrid::ValueType ValueType
void AdvanceToValidNestedIterator()
void SetProbability(const Eigen::Array3i &index, const float probability)
std::vector< ValueType * > update_indices_
Eigen::Array3i GetCellIndex() const 
WrappedGrid::Iterator nested_iterator_
HybridGrid(const float resolution)
Eigen::Array3i GetMetaIndex(const Eigen::Array3i &index) const 
static Eigen::Array3i GetOctant(const int i)
ValueType * mutable_value(const Eigen::Array3i &index)
typename WrappedGrid::ValueType ValueType
uint16 ProbabilityToValue(const float probability)
ValueType value(const Eigen::Array3i &index) const 
constexpr uint16 kUpdateMarker
const ValueType & GetValue() const 
proto::HybridGrid ToProto(const HybridGrid &grid)
ValueType value(const Eigen::Array3i &index) const 
Iterator(const FlatGrid &flat_grid)
ValueType value(const Eigen::Array3i &index) const 
bool ApplyLookupTable(const Eigen::Array3i &index, const std::vector< uint16 > &table)
HybridGrid(const proto::HybridGrid &proto)
bool IsDefaultValue(const TValueType &v)
Eigen::Array3i GetCellIndex() const