ray_to_pixel_mask.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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/ray_to_pixel_mask.h"
00018 
00019 #include "Eigen/Dense"
00020 
00021 namespace cartographer {
00022 namespace mapping {
00023 namespace {
00024 
00025 bool isEqual(const Eigen::Array2i& lhs, const Eigen::Array2i& rhs) {
00026   return ((lhs - rhs).matrix().lpNorm<1>() == 0);
00027 }
00028 }  // namespace
00029 
00030 // Compute all pixels that contain some part of the line segment connecting
00031 // 'scaled_begin' and 'scaled_end'. 'scaled_begin' and 'scaled_end' are scaled
00032 // by 'subpixel_scale'. 'scaled_begin' and 'scaled_end' are expected to be
00033 // greater than zero. Return values are in pixels and not scaled.
00034 std::vector<Eigen::Array2i> RayToPixelMask(const Eigen::Array2i& scaled_begin,
00035                                            const Eigen::Array2i& scaled_end,
00036                                            int subpixel_scale) {
00037   // For simplicity, we order 'scaled_begin' and 'scaled_end' by their x
00038   // coordinate.
00039   if (scaled_begin.x() > scaled_end.x()) {
00040     return RayToPixelMask(scaled_end, scaled_begin, subpixel_scale);
00041   }
00042 
00043   CHECK_GE(scaled_begin.x(), 0);
00044   CHECK_GE(scaled_begin.y(), 0);
00045   CHECK_GE(scaled_end.y(), 0);
00046   std::vector<Eigen::Array2i> pixel_mask;
00047   // Special case: We have to draw a vertical line in full pixels, as
00048   // 'scaled_begin' and 'scaled_end' have the same full pixel x coordinate.
00049   if (scaled_begin.x() / subpixel_scale == scaled_end.x() / subpixel_scale) {
00050     Eigen::Array2i current(
00051         scaled_begin.x() / subpixel_scale,
00052         std::min(scaled_begin.y(), scaled_end.y()) / subpixel_scale);
00053     pixel_mask.push_back(current);
00054     const int end_y =
00055         std::max(scaled_begin.y(), scaled_end.y()) / subpixel_scale;
00056     for (; current.y() <= end_y; ++current.y()) {
00057       if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00058     }
00059     return pixel_mask;
00060   }
00061 
00062   const int64 dx = scaled_end.x() - scaled_begin.x();
00063   const int64 dy = scaled_end.y() - scaled_begin.y();
00064   const int64 denominator = 2 * subpixel_scale * dx;
00065 
00066   // The current full pixel coordinates. We scaled_begin at 'scaled_begin'.
00067   Eigen::Array2i current = scaled_begin / subpixel_scale;
00068   pixel_mask.push_back(current);
00069 
00070   // To represent subpixel centers, we use a factor of 2 * 'subpixel_scale' in
00071   // the denominator.
00072   // +-+-+-+ -- 1 = (2 * subpixel_scale) / (2 * subpixel_scale)
00073   // | | | |
00074   // +-+-+-+
00075   // | | | |
00076   // +-+-+-+ -- top edge of first subpixel = 2 / (2 * subpixel_scale)
00077   // | | | | -- center of first subpixel = 1 / (2 * subpixel_scale)
00078   // +-+-+-+ -- 0 = 0 / (2 * subpixel_scale)
00079 
00080   // The center of the subpixel part of 'scaled_begin.y()' assuming the
00081   // 'denominator', i.e., sub_y / denominator is in (0, 1).
00082   int64 sub_y = (2 * (scaled_begin.y() % subpixel_scale) + 1) * dx;
00083 
00084   // The distance from the from 'scaled_begin' to the right pixel border, to be
00085   // divided by 2 * 'subpixel_scale'.
00086   const int first_pixel =
00087       2 * subpixel_scale - 2 * (scaled_begin.x() % subpixel_scale) - 1;
00088   // The same from the left pixel border to 'scaled_end'.
00089   const int last_pixel = 2 * (scaled_end.x() % subpixel_scale) + 1;
00090 
00091   // The full pixel x coordinate of 'scaled_end'.
00092   const int end_x = std::max(scaled_begin.x(), scaled_end.x()) / subpixel_scale;
00093 
00094   // Move from 'scaled_begin' to the next pixel border to the right.
00095   sub_y += dy * first_pixel;
00096   if (dy > 0) {
00097     while (true) {
00098       if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00099       while (sub_y > denominator) {
00100         sub_y -= denominator;
00101         ++current.y();
00102         if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00103       }
00104       ++current.x();
00105       if (sub_y == denominator) {
00106         sub_y -= denominator;
00107         ++current.y();
00108       }
00109       if (current.x() == end_x) {
00110         break;
00111       }
00112       // Move from one pixel border to the next.
00113       sub_y += dy * 2 * subpixel_scale;
00114     }
00115     // Move from the pixel border on the right to 'scaled_end'.
00116     sub_y += dy * last_pixel;
00117     if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00118     while (sub_y > denominator) {
00119       sub_y -= denominator;
00120       ++current.y();
00121       if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00122     }
00123     CHECK_NE(sub_y, denominator);
00124     CHECK_EQ(current.y(), scaled_end.y() / subpixel_scale);
00125     return pixel_mask;
00126   }
00127 
00128   // Same for lines non-ascending in y coordinates.
00129   while (true) {
00130     if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00131     while (sub_y < 0) {
00132       sub_y += denominator;
00133       --current.y();
00134       if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00135     }
00136     ++current.x();
00137     if (sub_y == 0) {
00138       sub_y += denominator;
00139       --current.y();
00140     }
00141     if (current.x() == end_x) {
00142       break;
00143     }
00144     sub_y += dy * 2 * subpixel_scale;
00145   }
00146   sub_y += dy * last_pixel;
00147   if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00148   while (sub_y < 0) {
00149     sub_y += denominator;
00150     --current.y();
00151     if (!isEqual(pixel_mask.back(), current)) pixel_mask.push_back(current);
00152   }
00153   CHECK_NE(sub_y, 0);
00154   CHECK_EQ(current.y(), scaled_end.y() / subpixel_scale);
00155   return pixel_mask;
00156 }
00157 
00158 }  // namespace mapping
00159 }  // namespace cartographer


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