Program Listing for File point2d.cpp

Return to documentation for file (src/tuw_geometry/point2d.cpp)

#include "tuw_geometry/point2d.hpp"

#include "tuw_geometry/polar2d.hpp"
using namespace tuw;

Point2D::Point2D()
: cv::Vec<double, 3>(0, 0, 1) {}
Point2D::Point2D(const cv::Point & p)
: cv::Vec<double, 3>(p.x, p.y, 1.) {}
Point2D::Point2D(double x, double y)
: cv::Vec<double, 3>(x, y, 1.) {}
Point2D::Point2D(double x, double y, double h)
: cv::Vec<double, 3>(x, y, h) {}
Point2D::Point2D(const Polar2D & p)
: cv::Vec<double, 3>(p.rho() * cos(p.alpha()), p.rho() * sin(p.alpha()), 1)
{
}

Point2D & Point2D::set(const Point2D & p)
{
  this->val[0] = p.x(), this->val[1] = p.y();
  return *this;
}
Point2D & Point2D::set(double x, double y)
{
  this->val[0] = x, this->val[1] = y;
  return *this;
}
Point2D & Point2D::set(double x, double y, double h)
{
  this->val[0] = x, this->val[1] = y, this->val[2] = h;
  return *this;
}
const double & Point2D::x() const {return this->val[0];}
double & Point2D::x() {return this->val[0];}
const double & Point2D::y() const {return this->val[1];}
double & Point2D::y() {return this->val[1];}
const double & Point2D::h() const {return this->val[2];}
double & Point2D::h() {return this->val[2];}

void Point2D::set_x(double v) {this->x() = v;}
double Point2D::get_x() const {return this->x();}
void Point2D::set_y(double v) {this->y() = v;}
double Point2D::get_y() const {return this->y();}
void Point2D::set_h(double v) {this->h() = v;}
double Point2D::get_h() const {return this->h();}
cv::Vec<double, 2> Point2D::vector() const {return cv::Vec<double, 2>(this->x(), this->y());}
double Point2D::distanceTo(const Point2D & p) const
{
  double dx = p.val[0] - this->val[0], dy = p.val[1] - this->val[1];
  return sqrt(dx * dx + dy * dy);
}
const cv::Point_<double> & Point2D::cv() const
{
  return reinterpret_cast<const cv::Point_<double> &>(*this);
}
cv::Point_<double> & Point2D::cv() {return reinterpret_cast<cv::Point_<double> &>(*this);}
double Point2D::angle() const {return atan2(this->val[1], this->val[0]);}
double Point2D::radius() const
{
  return sqrt(this->val[0] * this->val[0] + this->val[1] * this->val[1]);
}
bool Point2D::inside(double x0, double y0, double x1, double y1) const
{
  return (x() >= x0) && (x() <= x1) && (y() >= y0) && (y() <= y1);
}

std::string Point2D::str(const char * format) const
{
  char str[0xFF];
  sprintf(str, format, x(), y());
  return std::string(str);
}

bool Point2D::equal(const Point2D & o, double tolerance) const
{
  double d = cv::norm(o - *this);
  return d < tolerance;
}