Program Listing for File Edge.h

Return to documentation for file (include/apriltag_mit/AprilTags/Edge.h)

#ifndef APRILTAGS_EDGE_H_
#define APRILTAGS_EDGE_H_

#include <vector>
#include <unordered_set>

#include "apriltag_mit/AprilTags/FloatImage.h"
#include "apriltag_mit/AprilTags/DisjointSets.h"

namespace AprilTags {


struct Edge {
  // minimum intensity gradient for an edge to be recognized
  // float const Edge::minMag = 0.004f;
  static constexpr float kMinMag = 0.06f;

  // maximum acceptable difference in local orientation
  static constexpr float kMaxThetaDiff = 25.f * M_PI / 180.f;
  // used to convert cost to int
  static constexpr int kWeightScale = 100;
  // theta threshold for merging edges
  static constexpr float kThetaThresh = 100;
  // magnitude threshold for merging edges
  //  static constexpr float kMagThresh = 1200;
  static constexpr float kMagThresh = 150;

  int pid0;
  int pid1;
  int cost = -1;

  Edge() = default;
  Edge(int pid0, int pid1, int cost) : pid0(pid0), pid1(pid1), cost(cost) {}

  inline bool operator<(const Edge &other) const { return cost < other.cost; }

  static int EdgeCost(float theta0, float theta1, float mag1);

  // so without exceeding the thetaThresh.
};

struct Stats {
  float mmin, mmax, tmin, tmax;
};

std::vector<Edge> CalcLocalEdges(int x, int y, const FloatImage &im_mag,
                                 const FloatImage &im_theta);

void MergeEdges(const std::vector<Edge> &edges, DisjointSets &dsets,
                std::vector<Stats> &stats, float mag_thresh,
                float theta_thresh);

}  // namespace AprilTags

#endif  // APRILTAGS_EDGE_H_