Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_MAPPING_2D_MAP_LIMITS_H_
00018 #define CARTOGRAPHER_MAPPING_2D_MAP_LIMITS_H_
00019
00020 #include <utility>
00021 #include <vector>
00022
00023 #include "Eigen/Core"
00024 #include "Eigen/Geometry"
00025 #include "cartographer/common/math.h"
00026 #include "cartographer/mapping/2d/xy_index.h"
00027 #include "cartographer/mapping/proto/2d/map_limits.pb.h"
00028 #include "cartographer/mapping/trajectory_node.h"
00029 #include "cartographer/sensor/point_cloud.h"
00030 #include "cartographer/sensor/range_data.h"
00031 #include "cartographer/transform/rigid_transform.h"
00032 #include "cartographer/transform/transform.h"
00033 #include "glog/logging.h"
00034
00035 namespace cartographer {
00036 namespace mapping {
00037
00038
00039
00040 class MapLimits {
00041 public:
00042 MapLimits(const double resolution, const Eigen::Vector2d& max,
00043 const CellLimits& cell_limits)
00044 : resolution_(resolution), max_(max), cell_limits_(cell_limits) {
00045 CHECK_GT(resolution_, 0.);
00046 CHECK_GT(cell_limits.num_x_cells, 0.);
00047 CHECK_GT(cell_limits.num_y_cells, 0.);
00048 }
00049
00050 explicit MapLimits(const proto::MapLimits& map_limits)
00051 : resolution_(map_limits.resolution()),
00052 max_(transform::ToEigen(map_limits.max())),
00053 cell_limits_(map_limits.cell_limits()) {}
00054
00055
00056
00057 double resolution() const { return resolution_; }
00058
00059
00060
00061 const Eigen::Vector2d& max() const { return max_; }
00062
00063
00064 const CellLimits& cell_limits() const { return cell_limits_; }
00065
00066
00067
00068
00069 Eigen::Array2i GetCellIndex(const Eigen::Vector2f& point) const {
00070
00071
00072
00073 return Eigen::Array2i(
00074 common::RoundToInt((max_.y() - point.y()) / resolution_ - 0.5),
00075 common::RoundToInt((max_.x() - point.x()) / resolution_ - 0.5));
00076 }
00077
00078
00079 Eigen::Vector2f GetCellCenter(const Eigen::Array2i cell_index) const {
00080 return {max_.x() - resolution() * (cell_index[1] + 0.5),
00081 max_.y() - resolution() * (cell_index[0] + 0.5)};
00082 }
00083
00084
00085 bool Contains(const Eigen::Array2i& cell_index) const {
00086 return (Eigen::Array2i(0, 0) <= cell_index).all() &&
00087 (cell_index <
00088 Eigen::Array2i(cell_limits_.num_x_cells, cell_limits_.num_y_cells))
00089 .all();
00090 }
00091
00092 private:
00093 double resolution_;
00094 Eigen::Vector2d max_;
00095 CellLimits cell_limits_;
00096 };
00097
00098 inline proto::MapLimits ToProto(const MapLimits& map_limits) {
00099 proto::MapLimits result;
00100 result.set_resolution(map_limits.resolution());
00101 *result.mutable_max() = transform::ToProto(map_limits.max());
00102 *result.mutable_cell_limits() = ToProto(map_limits.cell_limits());
00103 return result;
00104 }
00105
00106 }
00107 }
00108
00109 #endif // CARTOGRAPHER_MAPPING_2D_MAP_LIMITS_H_