Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Friends | List of all members
aruco::Marker Class Reference

This class represents a marker. It is a vector of the fours corners ot the marker. More...

#include <marker.h>

Inheritance diagram for aruco::Marker:
Inheritance graph
[legend]

Public Member Functions

void calculateExtrinsics (float markerSize, const CameraParameters &CP, bool setYPerpendicular=true) throw (cv::Exception)
 
void calculateExtrinsics (float markerSize, cv::Mat CameraMatrix, cv::Mat Distorsion=cv::Mat(), bool setYPerpendicular=true) throw (cv::Exception)
 
void draw (cv::Mat &in, cv::Scalar color, int lineWidth=1, bool writeId=true) const
 
void fromStream (istream &str)
 
float getArea () const
 
cv::Point2f getCenter () const
 
float getPerimeter () const
 
void glGetModelViewMatrix (double modelview_matrix[16]) throw (cv::Exception)
 
bool isValid () const
 
 Marker ()
 
 Marker (int id)
 
 Marker (const Marker &M)
 
 Marker (const std::vector< cv::Point2f > &corners, int _id=-1)
 
void OgreGetPoseParameters (double position[3], double orientation[4]) throw (cv::Exception)
 
bool operator== (const Marker &m) const
 
void toStream (ostream &str) const
 
 ~Marker ()
 

Static Public Member Functions

static vector< cv::Point3f > get3DPoints (float msize)
 

Public Attributes

int id
 
cv::Mat Rvec
 
float ssize
 
cv::Mat Tvec
 

Private Member Functions

void rotateXAxis (cv::Mat &rotation)
 

Friends

bool operator< (const Marker &M1, const Marker &M2)
 
ostream & operator<< (ostream &str, const Marker &M)
 

Detailed Description

This class represents a marker. It is a vector of the fours corners ot the marker.

Definition at line 42 of file marker.h.

Constructor & Destructor Documentation

◆ Marker() [1/4]

aruco::Marker::Marker ( )

Definition at line 40 of file marker.cpp.

◆ Marker() [2/4]

aruco::Marker::Marker ( int  id)

Definition at line 51 of file marker.cpp.

◆ Marker() [3/4]

aruco::Marker::Marker ( const Marker M)

Definition at line 62 of file marker.cpp.

◆ Marker() [4/4]

aruco::Marker::Marker ( const std::vector< cv::Point2f > &  corners,
int  _id = -1 
)

Definition at line 72 of file marker.cpp.

◆ ~Marker()

aruco::Marker::~Marker ( )
inline

Definition at line 65 of file marker.h.

Member Function Documentation

◆ calculateExtrinsics() [1/2]

void aruco::Marker::calculateExtrinsics ( float  markerSize,
const CameraParameters CP,
bool  setYPerpendicular = true 
)
throw (cv::Exception
)

Calculates the extrinsics (Rvec and Tvec) of the marker with respect to the camera

Parameters
markerSizesize of the marker side expressed in meters
CPparmeters of the camera
setYPerpendicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis

Definition at line 253 of file marker.cpp.

◆ calculateExtrinsics() [2/2]

void aruco::Marker::calculateExtrinsics ( float  markerSize,
cv::Mat  CameraMatrix,
cv::Mat  Distorsion = cv::Mat(),
bool  setYPerpendicular = true 
)
throw (cv::Exception
)

Calculates the extrinsics (Rvec and Tvec) of the marker with respect to the camera

Parameters
markerSizesize of the marker side expressed in meters
CameraMatrixmatrix with camera parameters (fx,fy,cx,cy)
Distorsionmatrix with distorsion parameters (k1,k2,p1,p2)
setYPerpendicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis

Definition at line 263 of file marker.cpp.

◆ draw()

void aruco::Marker::draw ( cv::Mat &  in,
cv::Scalar  color,
int  lineWidth = 1,
bool  writeId = true 
) const

Draws this marker in the input image

Definition at line 226 of file marker.cpp.

◆ fromStream()

void aruco::Marker::fromStream ( istream &  str)

Definition at line 362 of file marker.cpp.

◆ get3DPoints()

vector< cv::Point3f > aruco::Marker::get3DPoints ( float  msize)
static

Definition at line 285 of file marker.cpp.

◆ getArea()

float aruco::Marker::getArea ( ) const

Returns the area

Definition at line 328 of file marker.cpp.

◆ getCenter()

cv::Point2f aruco::Marker::getCenter ( ) const

Returns the centroid of the marker

Definition at line 315 of file marker.cpp.

◆ getPerimeter()

float aruco::Marker::getPerimeter ( ) const

Returns the perimeter of the marker

Definition at line 341 of file marker.cpp.

◆ glGetModelViewMatrix()

void aruco::Marker::glGetModelViewMatrix ( double  modelview_matrix[16])
throw (cv::Exception
)

Given the extrinsic camera parameters returns the GL_MODELVIEW matrix for opengl. Setting this matrix, the reference coordinate system will be set in this marker

Definition at line 84 of file marker.cpp.

◆ isValid()

bool aruco::Marker::isValid ( ) const
inline

Indicates if this object is valid

Definition at line 68 of file marker.h.

◆ OgreGetPoseParameters()

void aruco::Marker::OgreGetPoseParameters ( double  position[3],
double  orientation[4] 
)
throw (cv::Exception
)

Returns position vector and orientation quaternion for an Ogre scene node or entity. Use: ... Ogre::Vector3 ogrePos (position[0], position[1], position[2]); Ogre::Quaternion ogreOrient (orientation[0], orientation[1], orientation[2], orientation[3]); mySceneNode->setPosition( ogrePos ); mySceneNode->setOrientation( ogreOrient ); ...

Definition at line 139 of file marker.cpp.

◆ operator==()

bool aruco::Marker::operator== ( const Marker m) const
inline

compares ids

Definition at line 116 of file marker.h.

◆ rotateXAxis()

void aruco::Marker::rotateXAxis ( cv::Mat &  rotation)
private

Definition at line 295 of file marker.cpp.

◆ toStream()

void aruco::Marker::toStream ( ostream &  str) const

Definition at line 349 of file marker.cpp.

Friends And Related Function Documentation

◆ operator<

bool operator< ( const Marker M1,
const Marker M2 
)
friend

Definition at line 119 of file marker.h.

◆ operator<<

ostream& operator<< ( ostream &  str,
const Marker M 
)
friend

Definition at line 122 of file marker.h.

Member Data Documentation

◆ id

int aruco::Marker::id

Definition at line 45 of file marker.h.

◆ Rvec

cv::Mat aruco::Marker::Rvec

Definition at line 49 of file marker.h.

◆ ssize

float aruco::Marker::ssize

Definition at line 47 of file marker.h.

◆ Tvec

cv::Mat aruco::Marker::Tvec

Definition at line 49 of file marker.h.


The documentation for this class was generated from the following files:


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Feb 28 2022 23:58:06