00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/3d/submap_3d.h"
00018
00019 #include <cmath>
00020 #include <limits>
00021
00022 #include "cartographer/common/math.h"
00023 #include "cartographer/mapping/internal/3d/scan_matching/rotational_scan_matcher.h"
00024 #include "cartographer/sensor/range_data.h"
00025 #include "glog/logging.h"
00026
00027 namespace cartographer {
00028 namespace mapping {
00029 namespace {
00030
00031 struct PixelData {
00032 int min_z = INT_MAX;
00033 int max_z = INT_MIN;
00034 int count = 0;
00035 float probability_sum = 0.f;
00036 float max_probability = 0.5f;
00037 };
00038
00039
00040
00041
00042 sensor::RangeData FilterRangeDataByMaxRange(const sensor::RangeData& range_data,
00043 const float max_range) {
00044 sensor::RangeData result{range_data.origin, {}, {}};
00045 for (const sensor::RangefinderPoint& hit : range_data.returns) {
00046 if ((hit.position - range_data.origin).norm() <= max_range) {
00047 result.returns.push_back(hit);
00048 }
00049 }
00050 return result;
00051 }
00052
00053 std::vector<PixelData> AccumulatePixelData(
00054 const int width, const int height, const Eigen::Array2i& min_index,
00055 const Eigen::Array2i& max_index,
00056 const std::vector<Eigen::Array4i>& voxel_indices_and_probabilities) {
00057 std::vector<PixelData> accumulated_pixel_data(width * height);
00058 for (const Eigen::Array4i& voxel_index_and_probability :
00059 voxel_indices_and_probabilities) {
00060 const Eigen::Array2i pixel_index = voxel_index_and_probability.head<2>();
00061 if ((pixel_index < min_index).any() || (pixel_index > max_index).any()) {
00062
00063 continue;
00064 }
00065 const int x = max_index.x() - pixel_index[0];
00066 const int y = max_index.y() - pixel_index[1];
00067 PixelData& pixel = accumulated_pixel_data[x * width + y];
00068 ++pixel.count;
00069 pixel.min_z = std::min(pixel.min_z, voxel_index_and_probability[2]);
00070 pixel.max_z = std::max(pixel.max_z, voxel_index_and_probability[2]);
00071 const float probability =
00072 ValueToProbability(voxel_index_and_probability[3]);
00073 pixel.probability_sum += probability;
00074 pixel.max_probability = std::max(pixel.max_probability, probability);
00075 }
00076 return accumulated_pixel_data;
00077 }
00078
00079
00080
00081
00082 std::vector<Eigen::Array4i> ExtractVoxelData(
00083 const HybridGrid& hybrid_grid, const transform::Rigid3f& transform,
00084 Eigen::Array2i* min_index, Eigen::Array2i* max_index) {
00085 std::vector<Eigen::Array4i> voxel_indices_and_probabilities;
00086 const float resolution_inverse = 1.f / hybrid_grid.resolution();
00087
00088 constexpr float kXrayObstructedCellProbabilityLimit = 0.501f;
00089 for (auto it = HybridGrid::Iterator(hybrid_grid); !it.Done(); it.Next()) {
00090 const uint16 probability_value = it.GetValue();
00091 const float probability = ValueToProbability(probability_value);
00092 if (probability < kXrayObstructedCellProbabilityLimit) {
00093
00094 continue;
00095 }
00096
00097 const Eigen::Vector3f cell_center_submap =
00098 hybrid_grid.GetCenterOfCell(it.GetCellIndex());
00099 const Eigen::Vector3f cell_center_global = transform * cell_center_submap;
00100 const Eigen::Array4i voxel_index_and_probability(
00101 common::RoundToInt(cell_center_global.x() * resolution_inverse),
00102 common::RoundToInt(cell_center_global.y() * resolution_inverse),
00103 common::RoundToInt(cell_center_global.z() * resolution_inverse),
00104 probability_value);
00105
00106 voxel_indices_and_probabilities.push_back(voxel_index_and_probability);
00107 const Eigen::Array2i pixel_index = voxel_index_and_probability.head<2>();
00108 *min_index = min_index->cwiseMin(pixel_index);
00109 *max_index = max_index->cwiseMax(pixel_index);
00110 }
00111 return voxel_indices_and_probabilities;
00112 }
00113
00114
00115
00116 std::string ComputePixelValues(
00117 const std::vector<PixelData>& accumulated_pixel_data) {
00118 std::string cell_data;
00119 cell_data.reserve(2 * accumulated_pixel_data.size());
00120 constexpr float kMinZDifference = 3.f;
00121 constexpr float kFreeSpaceWeight = 0.15f;
00122 for (const PixelData& pixel : accumulated_pixel_data) {
00123
00124
00125
00126 const float z_difference = pixel.count > 0 ? pixel.max_z - pixel.min_z : 0;
00127 if (z_difference < kMinZDifference) {
00128 cell_data.push_back(0);
00129 cell_data.push_back(0);
00130 continue;
00131 }
00132 const float free_space = std::max(z_difference - pixel.count, 0.f);
00133 const float free_space_weight = kFreeSpaceWeight * free_space;
00134 const float total_weight = pixel.count + free_space_weight;
00135 const float free_space_probability = 1.f - pixel.max_probability;
00136 const float average_probability = ClampProbability(
00137 (pixel.probability_sum + free_space_probability * free_space_weight) /
00138 total_weight);
00139 const int delta = 128 - ProbabilityToLogOddsInteger(average_probability);
00140 const uint8 alpha = delta > 0 ? 0 : -delta;
00141 const uint8 value = delta > 0 ? delta : 0;
00142 cell_data.push_back(value);
00143 cell_data.push_back((value || alpha) ? alpha : 1);
00144 }
00145 return cell_data;
00146 }
00147
00148 void AddToTextureProto(
00149 const HybridGrid& hybrid_grid, const transform::Rigid3d& global_submap_pose,
00150 proto::SubmapQuery::Response::SubmapTexture* const texture) {
00151
00152
00153 const float resolution = hybrid_grid.resolution();
00154 texture->set_resolution(resolution);
00155
00156
00157 Eigen::Array2i min_index(INT_MAX, INT_MAX);
00158 Eigen::Array2i max_index(INT_MIN, INT_MIN);
00159 const std::vector<Eigen::Array4i> voxel_indices_and_probabilities =
00160 ExtractVoxelData(hybrid_grid, global_submap_pose.cast<float>(),
00161 &min_index, &max_index);
00162
00163 const int width = max_index.y() - min_index.y() + 1;
00164 const int height = max_index.x() - min_index.x() + 1;
00165 texture->set_width(width);
00166 texture->set_height(height);
00167
00168 const std::vector<PixelData> accumulated_pixel_data = AccumulatePixelData(
00169 width, height, min_index, max_index, voxel_indices_and_probabilities);
00170 const std::string cell_data = ComputePixelValues(accumulated_pixel_data);
00171
00172 common::FastGzipString(cell_data, texture->mutable_cells());
00173 *texture->mutable_slice_pose() = transform::ToProto(
00174 global_submap_pose.inverse() *
00175 transform::Rigid3d::Translation(Eigen::Vector3d(
00176 max_index.x() * resolution, max_index.y() * resolution,
00177 global_submap_pose.translation().z())));
00178 }
00179
00180 }
00181
00182 proto::SubmapsOptions3D CreateSubmapsOptions3D(
00183 common::LuaParameterDictionary* parameter_dictionary) {
00184 proto::SubmapsOptions3D options;
00185 options.set_high_resolution(
00186 parameter_dictionary->GetDouble("high_resolution"));
00187 options.set_high_resolution_max_range(
00188 parameter_dictionary->GetDouble("high_resolution_max_range"));
00189 options.set_low_resolution(parameter_dictionary->GetDouble("low_resolution"));
00190 options.set_num_range_data(
00191 parameter_dictionary->GetNonNegativeInt("num_range_data"));
00192 *options.mutable_range_data_inserter_options() =
00193 CreateRangeDataInserterOptions3D(
00194 parameter_dictionary->GetDictionary("range_data_inserter").get());
00195 CHECK_GT(options.num_range_data(), 0);
00196 return options;
00197 }
00198
00199 Submap3D::Submap3D(const float high_resolution, const float low_resolution,
00200 const transform::Rigid3d& local_submap_pose,
00201 const Eigen::VectorXf& rotational_scan_matcher_histogram)
00202 : Submap(local_submap_pose),
00203 high_resolution_hybrid_grid_(
00204 absl::make_unique<HybridGrid>(high_resolution)),
00205 low_resolution_hybrid_grid_(
00206 absl::make_unique<HybridGrid>(low_resolution)),
00207 rotational_scan_matcher_histogram_(rotational_scan_matcher_histogram) {}
00208
00209 Submap3D::Submap3D(const proto::Submap3D& proto)
00210 : Submap(transform::ToRigid3(proto.local_pose())) {
00211 UpdateFromProto(proto);
00212 }
00213
00214 proto::Submap Submap3D::ToProto(
00215 const bool include_probability_grid_data) const {
00216 proto::Submap proto;
00217 auto* const submap_3d = proto.mutable_submap_3d();
00218 *submap_3d->mutable_local_pose() = transform::ToProto(local_pose());
00219 submap_3d->set_num_range_data(num_range_data());
00220 submap_3d->set_finished(insertion_finished());
00221 if (include_probability_grid_data) {
00222 *submap_3d->mutable_high_resolution_hybrid_grid() =
00223 high_resolution_hybrid_grid().ToProto();
00224 *submap_3d->mutable_low_resolution_hybrid_grid() =
00225 low_resolution_hybrid_grid().ToProto();
00226 }
00227 for (Eigen::VectorXf::Index i = 0;
00228 i != rotational_scan_matcher_histogram_.size(); ++i) {
00229 submap_3d->add_rotational_scan_matcher_histogram(
00230 rotational_scan_matcher_histogram_(i));
00231 }
00232 return proto;
00233 }
00234
00235 void Submap3D::UpdateFromProto(const proto::Submap& proto) {
00236 CHECK(proto.has_submap_3d());
00237 UpdateFromProto(proto.submap_3d());
00238 }
00239
00240 void Submap3D::UpdateFromProto(const proto::Submap3D& submap_3d) {
00241 set_num_range_data(submap_3d.num_range_data());
00242 set_insertion_finished(submap_3d.finished());
00243 if (submap_3d.has_high_resolution_hybrid_grid()) {
00244 high_resolution_hybrid_grid_ =
00245 absl::make_unique<HybridGrid>(submap_3d.high_resolution_hybrid_grid());
00246 }
00247 if (submap_3d.has_low_resolution_hybrid_grid()) {
00248 low_resolution_hybrid_grid_ =
00249 absl::make_unique<HybridGrid>(submap_3d.low_resolution_hybrid_grid());
00250 }
00251 rotational_scan_matcher_histogram_ =
00252 Eigen::VectorXf::Zero(submap_3d.rotational_scan_matcher_histogram_size());
00253 for (Eigen::VectorXf::Index i = 0;
00254 i != submap_3d.rotational_scan_matcher_histogram_size(); ++i) {
00255 rotational_scan_matcher_histogram_(i) =
00256 submap_3d.rotational_scan_matcher_histogram(i);
00257 }
00258 }
00259
00260 void Submap3D::ToResponseProto(
00261 const transform::Rigid3d& global_submap_pose,
00262 proto::SubmapQuery::Response* const response) const {
00263 response->set_submap_version(num_range_data());
00264
00265 AddToTextureProto(*high_resolution_hybrid_grid_, global_submap_pose,
00266 response->add_textures());
00267 AddToTextureProto(*low_resolution_hybrid_grid_, global_submap_pose,
00268 response->add_textures());
00269 }
00270
00271 void Submap3D::InsertData(const sensor::RangeData& range_data_in_local,
00272 const RangeDataInserter3D& range_data_inserter,
00273 const float high_resolution_max_range,
00274 const Eigen::Quaterniond& local_from_gravity_aligned,
00275 const Eigen::VectorXf& scan_histogram_in_gravity) {
00276 CHECK(!insertion_finished());
00277
00278 const sensor::RangeData transformed_range_data = sensor::TransformRangeData(
00279 range_data_in_local, local_pose().inverse().cast<float>());
00280 range_data_inserter.Insert(
00281 FilterRangeDataByMaxRange(transformed_range_data,
00282 high_resolution_max_range),
00283 high_resolution_hybrid_grid_.get());
00284 range_data_inserter.Insert(transformed_range_data,
00285 low_resolution_hybrid_grid_.get());
00286 set_num_range_data(num_range_data() + 1);
00287 const float yaw_in_submap_from_gravity = transform::GetYaw(
00288 local_pose().inverse().rotation() * local_from_gravity_aligned);
00289 rotational_scan_matcher_histogram_ +=
00290 scan_matching::RotationalScanMatcher::RotateHistogram(
00291 scan_histogram_in_gravity, yaw_in_submap_from_gravity);
00292 }
00293
00294 void Submap3D::Finish() {
00295 CHECK(!insertion_finished());
00296 set_insertion_finished(true);
00297 }
00298
00299 ActiveSubmaps3D::ActiveSubmaps3D(const proto::SubmapsOptions3D& options)
00300 : options_(options),
00301 range_data_inserter_(options.range_data_inserter_options()) {}
00302
00303 std::vector<std::shared_ptr<const Submap3D>> ActiveSubmaps3D::submaps() const {
00304 return std::vector<std::shared_ptr<const Submap3D>>(submaps_.begin(),
00305 submaps_.end());
00306 }
00307
00308 std::vector<std::shared_ptr<const Submap3D>> ActiveSubmaps3D::InsertData(
00309 const sensor::RangeData& range_data,
00310 const Eigen::Quaterniond& local_from_gravity_aligned,
00311 const Eigen::VectorXf& rotational_scan_matcher_histogram_in_gravity) {
00312 if (submaps_.empty() ||
00313 submaps_.back()->num_range_data() == options_.num_range_data()) {
00314 AddSubmap(transform::Rigid3d(range_data.origin.cast<double>(),
00315 local_from_gravity_aligned),
00316 rotational_scan_matcher_histogram_in_gravity.size());
00317 }
00318 for (auto& submap : submaps_) {
00319 submap->InsertData(range_data, range_data_inserter_,
00320 options_.high_resolution_max_range(),
00321 local_from_gravity_aligned,
00322 rotational_scan_matcher_histogram_in_gravity);
00323 }
00324 if (submaps_.front()->num_range_data() == 2 * options_.num_range_data()) {
00325 submaps_.front()->Finish();
00326 }
00327 return submaps();
00328 }
00329
00330 void ActiveSubmaps3D::AddSubmap(
00331 const transform::Rigid3d& local_submap_pose,
00332 const int rotational_scan_matcher_histogram_size) {
00333 if (submaps_.size() >= 2) {
00334
00335
00336 CHECK(submaps_.front()->insertion_finished());
00337 submaps_.erase(submaps_.begin());
00338 }
00339 const Eigen::VectorXf initial_rotational_scan_matcher_histogram =
00340 Eigen::VectorXf::Zero(rotational_scan_matcher_histogram_size);
00341 submaps_.emplace_back(new Submap3D(
00342 options_.high_resolution(), options_.low_resolution(), local_submap_pose,
00343 initial_rotational_scan_matcher_histogram));
00344 }
00345
00346 }
00347 }