17 #ifndef CARTOGRAPHER_MAPPING_2D_PROBABILITY_GRID_H_ 18 #define CARTOGRAPHER_MAPPING_2D_PROBABILITY_GRID_H_ 32 #include "cartographer/mapping_2d/proto/probability_grid.pb.h" 34 #include "glog/logging.h" 37 namespace mapping_2d {
45 limits_.cell_limits().num_y_cells,
56 proto.update_indices().end()),
61 cells_.reserve(proto.cells_size());
62 for (
const auto cell : proto.cells()) {
63 CHECK_LE(cell, std::numeric_limits<uint16>::max());
82 void SetProbability(
const Eigen::Array2i& xy_index,
const float probability) {
97 const std::vector<uint16>& table) {
125 bool IsKnown(
const Eigen::Array2i& xy_index)
const {
154 const int offset = x_offset + stride * y_offset;
157 std::vector<uint16> new_cells(new_size,
161 new_cells[offset + j + i * stride] =
175 proto::ProbabilityGrid result;
177 result.mutable_cells()->Reserve(
cells_.size());
178 for (
const auto cell :
cells_) {
179 result.mutable_cells()->Add(cell);
183 result.mutable_update_indices()->Add(update);
201 min_y_ = std::min(min_y_, xy_index.y());
202 max_x_ = std::max(max_x_, xy_index.x());
203 max_y_ = std::max(max_y_, xy_index.y());
221 #endif // CARTOGRAPHER_MAPPING_2D_PROBABILITY_GRID_H_
void UpdateBounds(const Eigen::Array2i &xy_index)
const Eigen::Vector2d & max() const
ProbabilityGrid(const MapLimits &limits)
constexpr float kMinProbability
bool ApplyLookupTable(const Eigen::Array2i &xy_index, const std::vector< uint16 > &table)
proto::ProbabilityGrid ToProto() const
Eigen::Array2i GetXYIndexOfCellContainingPoint(const double x, const double y) const
int GetIndexOfCell(const Eigen::Array2i &xy_index) const
float ValueToProbability(const uint16 value)
double resolution() const
void ComputeCroppedLimits(Eigen::Array2i *const offset, CellLimits *const limits) const
float GetProbability(const double x, const double y) const
float GetProbability(const Eigen::Array2i &xy_index) const
const CellLimits & cell_limits() const
void GrowLimits(const double x, const double y)
void SetProbability(const Eigen::Array2i &xy_index, const float probability)
bool IsKnown(const Eigen::Array2i &xy_index) const
constexpr uint16 kUnknownProbabilityValue
ProbabilityGrid(const proto::ProbabilityGrid &proto)
std::vector< int > update_indices_
const MapLimits & limits() const
std::vector< uint16 > cells_
bool Contains(const Eigen::Array2i &xy_index) const
proto::MapLimits ToProto(const MapLimits &map_limits)
uint16 ProbabilityToValue(const float probability)
constexpr uint16 kUpdateMarker