normal_estimation_2d.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 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 #include "cartographer/mapping/internal/2d/normal_estimation_2d.h"
00018 
00019 namespace cartographer {
00020 namespace mapping {
00021 namespace {
00022 
00023 float NormalTo2DAngle(const Eigen::Vector3f& v) {
00024   return std::atan2(v[1], v[0]);
00025 }
00026 
00027 // Estimate the normal of an estimation_point as the arithmetic mean of the the
00028 // normals of the vectors from estimation_point to each point in the
00029 // sample_window.
00030 float EstimateNormal(const sensor::PointCloud& returns,
00031                      const size_t estimation_point_index,
00032                      const size_t sample_window_begin,
00033                      const size_t sample_window_end,
00034                      const Eigen::Vector3f& sensor_origin) {
00035   const Eigen::Vector3f& estimation_point =
00036       returns[estimation_point_index].position;
00037   if (sample_window_end - sample_window_begin < 2) {
00038     return NormalTo2DAngle(sensor_origin - estimation_point);
00039   }
00040   Eigen::Vector3f mean_normal = Eigen::Vector3f::Zero();
00041   const Eigen::Vector3f& estimation_point_to_observation =
00042       sensor_origin - estimation_point;
00043   for (size_t sample_point_index = sample_window_begin;
00044        sample_point_index < sample_window_end; ++sample_point_index) {
00045     if (sample_point_index == estimation_point_index) continue;
00046     const Eigen::Vector3f& sample_point = returns[sample_point_index].position;
00047     const Eigen::Vector3f& tangent = estimation_point - sample_point;
00048     Eigen::Vector3f sample_normal = {-tangent[1], tangent[0], 0.f};
00049     constexpr float kMinNormalLength = 1e-6f;
00050     if (sample_normal.norm() < kMinNormalLength) {
00051       continue;
00052     }
00053     // Ensure sample_normal points towards 'sensor_origin'.
00054     if (sample_normal.dot(estimation_point_to_observation) < 0) {
00055       sample_normal = -sample_normal;
00056     }
00057     sample_normal.normalize();
00058     mean_normal += sample_normal;
00059   }
00060   return NormalTo2DAngle(mean_normal);
00061 }
00062 }  // namespace
00063 
00064 proto::NormalEstimationOptions2D CreateNormalEstimationOptions2D(
00065     common::LuaParameterDictionary* parameter_dictionary) {
00066   proto::NormalEstimationOptions2D options;
00067   options.set_num_normal_samples(
00068       parameter_dictionary->GetInt("num_normal_samples"));
00069   options.set_sample_radius(parameter_dictionary->GetDouble("sample_radius"));
00070   CHECK_GT(options.num_normal_samples(), 0);
00071   CHECK_GT(options.sample_radius(), 0.0);
00072   return options;
00073 }
00074 
00075 // Estimates the normal for each 'return' in 'range_data'.
00076 // Assumes the angles in the range data returns are sorted with respect to
00077 // the orientation of the vector from 'origin' to 'return'.
00078 std::vector<float> EstimateNormals(
00079     const sensor::RangeData& range_data,
00080     const proto::NormalEstimationOptions2D& normal_estimation_options) {
00081   std::vector<float> normals;
00082   normals.reserve(range_data.returns.size());
00083   const size_t max_num_samples = normal_estimation_options.num_normal_samples();
00084   const float sample_radius = normal_estimation_options.sample_radius();
00085   for (size_t current_point = 0; current_point < range_data.returns.size();
00086        ++current_point) {
00087     const Eigen::Vector3f& hit = range_data.returns[current_point].position;
00088     size_t sample_window_begin = current_point;
00089     for (; sample_window_begin > 0 &&
00090            current_point - sample_window_begin < max_num_samples / 2 &&
00091            (hit - range_data.returns[sample_window_begin - 1].position).norm() <
00092                sample_radius;
00093          --sample_window_begin) {
00094     }
00095     size_t sample_window_end = current_point;
00096     for (;
00097          sample_window_end < range_data.returns.size() &&
00098          sample_window_end - current_point < ceil(max_num_samples / 2.0) + 1 &&
00099          (hit - range_data.returns[sample_window_end].position).norm() <
00100              sample_radius;
00101          ++sample_window_end) {
00102     }
00103     const float normal_estimate =
00104         EstimateNormal(range_data.returns, current_point, sample_window_begin,
00105                        sample_window_end, range_data.origin);
00106     normals.push_back(normal_estimate);
00107   }
00108   return normals;
00109 }
00110 
00111 }  // namespace mapping
00112 }  // namespace cartographer


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