Program Listing for File marker.h

Return to documentation for file (/tmp/ws/src/aruco_ros/aruco/include/aruco/marker.h)

#ifndef _Aruco_Marker_H
#define _Aruco_Marker_H

#include "aruco_export.h"

#include <opencv2/core/core.hpp>

#include <cstdint>
#include <iostream>
#include <vector>

namespace aruco
{
class CameraParameters;
class ARUCO_EXPORT Marker : public std::vector<cv::Point2f>
{
public:
  // id of  the marker
  int id;
  // size of the markers sides in meters
  float ssize;
  // matrices of rotation and translation respect to the camera
  cv::Mat Rvec, Tvec;
  // additional info about the dictionary
  std::string dict_info;
  // points of the contour
  vector<cv::Point> contourPoints;

  Marker();
  Marker(int id);
  Marker(const Marker& M);
  Marker(const std::vector<cv::Point2f>& corners, int _id = -1);
  ~Marker()
  {
  }
  bool isValid() const
  {
    return id != -1 && size() == 4;
  }

  bool isPoseValid() const
  {
    return !Rvec.empty() && !Tvec.empty();
  }
  void draw(cv::Mat& in, cv::Scalar color = cv::Scalar(0, 0, 255), int lineWidth = -1,
            bool writeId = true, bool writeInfo = false) const;

  void calculateExtrinsics(float markerSize, const CameraParameters& CP,
                           bool setYPerpendicular = true);
  void calculateExtrinsics(float markerSize, cv::Mat CameraMatrix,
                           cv::Mat Distorsion = cv::Mat(), cv::Mat Extrinsics = cv::Mat(),
                           bool setYPerpendicular = true, bool correctFisheye = false);

  void glGetModelViewMatrix(double modelview_matrix[16]);

  void OgreGetPoseParameters(double position[3], double orientation[4]);

  cv::Point2f getCenter() const;
  float getPerimeter() const;
  float getArea() const;
  float getRadius() const;
  bool operator==(const Marker& m) const
  {
    return m.id == id;
  }

  void copyTo(Marker& m) const;
  Marker& operator=(const Marker& m);

  friend bool operator<(const Marker& M1, const Marker& M2)
  {
    return M1.id < M2.id;
  }
  friend std::ostream& operator<<(std::ostream& str, const Marker& M)
  {
    str << M.id << "=";
    for (int i = 0; i < 4; i++)
      str << "(" << M[i].x << "," << M[i].y << ") ";
    if (!M.Tvec.empty() && !M.Rvec.empty())
    {
      str << "Txyz=";
      for (int i = 0; i < 3; i++)
        str << M.Tvec.ptr<float>(0)[i] << " ";
      str << "Rxyz=";
      for (int i = 0; i < 3; i++)
        str << M.Rvec.ptr<float>(0)[i] << " ";
    }
    return str;
  }


  // saves to a binary stream
  void toStream(std::ostream& str) const;
  // reads from a binary stream
  void fromStream(std::istream& str);

  // returns the 3d points of a marker wrt its center
  static vector<cv::Point3f> get3DPoints(float msize);
  // returns the 3d points of this marker wrt its center
  inline vector<cv::Point3f> get3DPoints() const
  {
    return get3DPoints(ssize);
  }

  // returns the SE3 (4x4) transform matrix

  cv::Mat getTransformMatrix() const;

private:
  void rotateXAxis(cv::Mat& rotation);
};
}  // namespace aruco
#endif