Program Listing for File bresenham.hpp

Return to documentation for file (include/beluga/algorithm/raycasting/bresenham.hpp)

// Copyright 2023 Ekumen, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BELUGA_ALGORITHM_RAYCASTING_BRESENHAM_HPP
#define BELUGA_ALGORITHM_RAYCASTING_BRESENHAM_HPP

#include <cstdint>
#include <utility>

#include <range/v3/view/all.hpp>
#include <range/v3/view/take_while.hpp>

#include <Eigen/Core>

namespace beluga {

class Bresenham2i {
 public:
  enum Variant : std::uint8_t {
    kStandard = 0,
    kModified
  };


  template <class Vector2, typename Integer = typename Vector2::Scalar>
  class Line : public ranges::view_interface<Line<Vector2, Integer>> {
   public:
    class iterator {  // NOLINT(readability-identifier-naming)
     public:
      struct sentinel {
        bool operator==(const iterator& other) const { return other == *this; }

        bool operator!=(const iterator& other) const { return !(other == *this); }
      };

      using iterator_category = std::forward_iterator_tag;

      using difference_type = std::ptrdiff_t;

      using value_type = Vector2;

      using pointer = Vector2*;

      using reference = Vector2&;

      iterator() = default;

      explicit iterator(const Line* line) : current_point_(line->p0_), x_(line->p0_.x()), y_(line->p0_.y()) {
        xspan_ = line->p1_.x() - line->p0_.x();
        xstep_ = static_cast<decltype(xspan_)>(1);
        if (xspan_ < 0) {
          xspan_ = -xspan_;
          xstep_ = -xstep_;
        }

        yspan_ = line->p1_.y() - line->p0_.y();
        ystep_ = static_cast<decltype(yspan_)>(1);
        if (yspan_ < 0) {
          yspan_ = -yspan_;
          ystep_ = -ystep_;
        }

        if (xspan_ < yspan_) {
          using std::swap;
          swap(x_, y_);
          swap(xspan_, yspan_);
          swap(xstep_, ystep_);
          reversed_ = true;
        }

        dxspan_ = 2 * xspan_;
        dyspan_ = 2 * yspan_;

        error_ = prev_error_ = xspan_;
        modified_ = line->variant_ == Bresenham2i::kModified;
      }

      iterator operator++(int) {
        iterator other = *this;
        this->operator++();
        return other;
      }

      iterator& operator++() {
        if (checks_ == 0) {
          if (++step_ > xspan_) {
            return *this;
          }
          x_ += xstep_;
          error_ += dyspan_;
          ++checks_;
          if (error_ > dxspan_) {
            y_ += ystep_;
            error_ -= dxspan_;
            if (modified_) {
              ++checks_;
              ++checks_;
            }
          }
        }

        if (checks_ > 1) {
          if (checks_ > 2) {
            --checks_;
            if (error_ + prev_error_ <= dxspan_) {
              step_to(x_, y_ - ystep_);
              return *this;
            }
          }

          --checks_;
          if (error_ + prev_error_ >= dxspan_) {
            step_to(x_ - xstep_, y_);
            return *this;
          }
        }

        --checks_;
        step_to(x_, y_);
        prev_error_ = error_;
        return *this;
      }

      const Vector2& operator*() const { return current_point_; }

      const Vector2* operator->() const { return &current_point_; }

      bool operator==(const iterator& other) const {
        return x_ == other.x_ && y_ == other.y_ && xstep_ == other.xstep_ && ystep_ == other.ystep_ &&
               xspan_ == other.xspan_ && yspan_ == other.yspan_ && step_ == other.step_ && checks_ == other.checks_ &&
               modified_ == other.modified_ && reversed_ == other.reversed_;
      }

      bool operator!=(const iterator& other) const { return !(*this == other); }

      bool operator==(const sentinel&) const { return step_ > xspan_; }

      bool operator!=(const sentinel& other) const { return !(*this == other); }

     private:
      void step_to(Integer x, Integer y) {
        if (reversed_) {
          using std::swap;
          swap(x, y);
        }
        current_point_.x() = x;
        current_point_.y() = y;
      }

      Vector2 current_point_{};
      Integer x_{}, y_{};
      Integer xspan_{}, yspan_{};
      Integer dxspan_, dyspan_{};
      Integer xstep_{}, ystep_{}, step_{};
      Integer prev_error_{}, error_{};

      std::size_t checks_{0};
      bool modified_{false};
      bool reversed_{false};
    };

    Line() = default;


    explicit Line(Vector2 p0, Vector2 p1, Variant variant)
        : p0_(std::move(p0)), p1_(std::move(p1)), variant_(variant) {}

    [[nodiscard]] auto begin() const { return Line::iterator{this}; }

    [[nodiscard]] auto end() const { return typename Line::iterator::sentinel{}; }

   private:
    friend class iterator;

    Vector2 p0_{};
    Vector2 p1_{};
    Variant variant_{};
  };

  Bresenham2i() noexcept = default;

  Bresenham2i(const Bresenham2i&) noexcept = default;

  Bresenham2i(Bresenham2i&&) noexcept = default;

  Bresenham2i& operator=(const Bresenham2i&) noexcept = default;

  Bresenham2i& operator=(Bresenham2i&&) noexcept = default;

  explicit Bresenham2i(Variant variant) noexcept : variant_(variant) {}


  template <class Vector2i = Eigen::Vector2i>
  auto operator()(Vector2i p0, Vector2i p1) const {
    return Line{std::move(p0), std::move(p1), variant_};
  }

 private:
  Variant variant_{};
};

}  // namespace beluga

#endif