32 #include <GLUT/glut.h> 43 #include <opencv2/highgui/highgui.hpp> 44 #include <opencv2/imgproc/imgproc.hpp> 45 #include <opencv2/calib3d/calib3d.hpp> 51 using namespace aruco;
52 void __glGetModelViewMatrix(
double modelview_matrix[16],
const cv::Mat &Rvec,
const cv::Mat &Tvec)
throw(cv::Exception) ;
68 void vResize( GLsizei iWidth, GLsizei iHeight );
69 void vMouse(
int b,
int s,
int x,
int y);
79 int main(
int argc,
char **argv)
84 cerr<<
"Invalid number of arguments"<<endl;
85 cerr<<
"Usage: (in.avi|live) markermap_config.yml intrinsics.yml size "<<endl;
86 cerr<<
"WARNING: this test creates a synthetic mask consisting of a single rectangle. "<<endl;
87 cerr<<
"WARNING: The only purpose is to show how to create an AR application with mask in OpenGL "<<endl;
93 TheMarkerSize=atof(argv[4]);
97 MMPoseTracker.
setParams(TheCameraParams,TheMMConfig);
99 if (
string(argv[1])==
"live")
100 TheVideoCapturer.open(0);
101 else TheVideoCapturer.open(argv[1]);
103 if (!TheVideoCapturer.isOpened())
throw std::runtime_error(
"could not open video");
109 TheCameraParams.
resize( TheInputImage.size());
119 params.
_subpix_wsize= (15./2000.)*float(TheInputImage.cols) ;
124 glutInit(&argc, argv);
125 glutInitWindowPosition( 0, 0);
126 glutInitWindowSize(TheInputImage.size().width,TheInputImage.size().height);
127 glutInitDisplayMode( GLUT_RGB | GLUT_DEPTH | GLUT_DOUBLE );
128 glutCreateWindow(
"AruCo" );
130 glutIdleFunc(
vIdle );
133 glClearColor( 0.0, 0.0, 0.0, 1.0 );
135 TheGlWindowSize=TheInputImage.size();
136 vResize(TheGlWindowSize.width,TheGlWindowSize.height);
139 }
catch (std::exception &ex)
142 cout<<
"Exception :"<<ex.what()<<endl;
155 if (b==GLUT_LEFT_BUTTON && s==GLUT_DOWN) {
171 glVertex3f(0.0
f, 0.0
f, 0.0
f);
172 glVertex3f(size,0.0
f, 0.0
f);
177 glVertex3f(0.0
f, 0.0
f, 0.0
f);
178 glVertex3f( 0.0
f,size, 0.0
f);
184 glVertex3f(0.0
f, 0.0
f, 0.0
f);
185 glVertex3f(0.0
f, 0.0
f, size);
200 if (TheCaptureFlag) {
202 TheVideoCapturer.grab();
203 TheVideoCapturer.retrieve( TheInputImage);
204 TheUndInputImage.create(TheInputImage.size(),CV_8UC3);
206 cv::cvtColor(TheInputImage,TheInputImage,CV_BGR2RGB);
210 TheMarkers=TheMarkerDetector.
detect(TheUndInputImage);
214 cv::resize(TheUndInputImage,TheResizedImage,TheGlWindowSize);
228 if (TheResizedImage.rows==0)
231 glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
233 glMatrixMode(GL_MODELVIEW);
235 glMatrixMode(GL_PROJECTION);
237 glOrtho(0, TheGlWindowSize.width, 0, TheGlWindowSize.height, -1.0, 1.0);
238 glViewport(0, 0, TheGlWindowSize.width , TheGlWindowSize.height);
239 glDisable(GL_TEXTURE_2D);
241 glRasterPos3f( 0, TheGlWindowSize.height - 0.5, -1.0 );
242 glDrawPixels ( TheGlWindowSize.width , TheGlWindowSize.height , GL_RGB , GL_UNSIGNED_BYTE , TheResizedImage.ptr(0) );
245 glMatrixMode(GL_PROJECTION);
246 double proj_matrix[16];
249 glLoadMatrixd(proj_matrix);
252 double modelview_matrix[16];
271 glMatrixMode(GL_MODELVIEW);
273 glLoadMatrixd(modelview_matrix);
277 glutWireCube( TheMarkerSize );
294 void vResize( GLsizei iWidth, GLsizei iHeight )
297 TheGlWindowSize=Size(iWidth,iHeight);
301 vResize(iWidth,TheGlWindowSize.height);
305 if (TheUndInputImage.rows!=0)
306 cv::resize(TheUndInputImage,TheResizedImage,TheGlWindowSize);
312 assert(Tvec.type()==CV_32F);
314 Mat Rot(3, 3, CV_32FC1);
315 Rodrigues(Rvec, Rot);
318 for (
int i = 0; i < 3; i++)
319 for (
int j = 0; j < 3; j++)
320 para[i][j] = Rot.at<
float >(i, j);
322 para[0][3] = Tvec.ptr<
float >(0)[0];
323 para[1][3] = Tvec.ptr<
float >(0)[1];
324 para[2][3] = Tvec.ptr<
float >(0)[2];
327 modelview_matrix[0 + 0 * 4] = para[0][0];
329 modelview_matrix[0 + 1 * 4] = para[0][1];
330 modelview_matrix[0 + 2 * 4] = para[0][2];
331 modelview_matrix[0 + 3 * 4] = para[0][3];
333 modelview_matrix[1 + 0 * 4] = para[1][0];
334 modelview_matrix[1 + 1 * 4] = para[1][1];
335 modelview_matrix[1 + 2 * 4] = para[1][2];
336 modelview_matrix[1 + 3 * 4] = para[1][3];
338 modelview_matrix[2 + 0 * 4] = -para[2][0];
339 modelview_matrix[2 + 1 * 4] = -para[2][1];
340 modelview_matrix[2 + 2 * 4] = -para[2][2];
341 modelview_matrix[2 + 3 * 4] = -para[2][3];
342 modelview_matrix[3 + 0 * 4] = 0.0;
343 modelview_matrix[3 + 1 * 4] = 0.0;
344 modelview_matrix[3 + 2 * 4] = 0.0;
345 modelview_matrix[3 + 3 * 4] = 1.0;
347 modelview_matrix[12] *= scale;
348 modelview_matrix[13] *= scale;
349 modelview_matrix[14] *= scale;
int main(int argc, char **argv)
void setThresholdParams(double param1, double param2)
const cv::Mat getTvec() const
void resize(cv::Size size)
CameraParameters TheCameraParams
bool isExpressedInPixels() const
MarkerDetector TheMarkerDetector
const cv::Mat getRvec() const
void glGetProjectionMatrix(cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar, bool invert=false)
void setDictionary(std::string dict_type, float error_correction_rate=0)
std::vector< aruco::Marker > detect(const cv::Mat &input)
void readFromFile(string sfile)
void vMouse(int b, int s, int x, int y)
cv::Mat getRTMatrix() const
bool estimatePose(const vector< Marker > &v_m)
void readFromXMLFile(string filePath)
void setParams(const CameraParameters &cam_params, const MarkerMap &msconf, float markerSize=-1)
void __glGetModelViewMatrix(double modelview_matrix[16], const cv::Mat &Rvec, const cv::Mat &Tvec)
MarkerMap convertToMeters(float markerSize)
MarkerMapPoseTracker MMPoseTracker
Main class for marker detection.
Parameters of the camera.
VideoCapture TheVideoCapturer
std::string getDictionary() const
double _thresParam1_range
void vResize(GLsizei iWidth, GLsizei iHeight)
vector< Marker > TheMarkers
CornerRefinementMethod _cornerMethod
This class defines a set of markers whose locations are attached to a common reference system...