///////////////////////////////////////////////// ///////////////////////////////////////////////// #include #include #include #include #include #define _USE_MATH_DEFINES #include #include #include #include #include //#include "GLMetaseq.h" //MQO_MODEL gl_mqoModel; // MQOモデル #include using namespace std; #include "gl_main.h" #include "geometory.h" #include "opencv_inc.h" #include //Mainwindow int xBegin, yBegin; //mouseのXY座標 int mButton; //mouseのClick float distance_gl, twist, elevation, azimuth; //カメラの回転行列 float xOrig, yOrig, zOrig; //カメラの位置 //Subwindow float distance_gl2, twist2, elevation2, azimuth2; float xOrig2 = 0.0, yOrig2 = 0.0, zOrig2 = 0.0; int mButton2; int xBegin2, yBegin2; int WinID[2]; //ウィンドウID int WindowNum = 0; int WinFlag[2]; const char *WindowName[] = {"Sim_Main", "Camera"}; //Robot制御のパラメータ struct ROBOT myrobot; struct URG urg_area; struct URG urg_data; struct URG urg_data2; struct URG urg_data3; struct OBSTACLE obst; struct MOVE_OBSTACLE move_obst; extern double pantilt_pan_rot_speed; extern double pantilt_pan_init_deg; extern double pantilt_tilt_rot_speed; extern double pantilt_tilt_rot_sin_amp; extern double pantilt_tilt_rot_sin_speed; extern double pantilt_tilt_init_deg; extern ros::Time lrf_scantime; extern ros::Time pantilt_time; IplImage *capture_video_buf; IplImage *capture_video; int save_flg = 0; double robot_z = 0.0; struct pantilt pantable; int color_no = 0; int wait_sleep(double time) { usleep(time * 1000.0); return 0; } static double gettimeofday_sec() { struct timeval tv; gettimeofday(&tv, NULL); return tv.tv_sec + (double)tv.tv_usec * 1e-6; } void robot_view(struct ROBOT &robot) { double robot_height = 2.0; double xx, yy, theta; xx = robot.x; yy = robot.y; theta = robot.theta; static double radius = 0.5; glColor3f(0, 0, 0); //Yellow int grid = 24.0; glLineWidth(2.0); //ロボットの前方を線分で表現 glBegin(GL_LINES); glVertex3f_p(xx, yy, 0.0); glVertex3f_p(cos(theta + M_PI / 2.0) * radius + xx, sin(theta + M_PI / 2.0) * radius + yy, 0.0); glEnd(); glBegin(GL_LINES); glVertex3f_p(xx, yy, 2.0); glVertex3f_p(cos(theta + M_PI / 2.0) * radius + xx, sin(theta + M_PI / 2.0) * radius + yy, robot_height); glEnd(); glBegin(GL_LINE_LOOP); glVertex3f_p(xx, yy, 0.0); glVertex3f_p(xx, yy, 2.0); glEnd(); //glBegin(GL_LINE_LOOP); //glVertex3f_p(xx-radius, yy-radius, 2.0); //glVertex3f_p(xx+radius, yy-radius, 2.0); //glVertex3f_p(xx+radius, yy+radius, 2.0); //glVertex3f_p(xx-radius, yy+radius, 2.0); //glEnd(); //ロボットを円形で表現 for (int i = 0; i < grid; i++) { double rad_1 = 2.0 * M_PI * i / grid + theta; double rad_2 = 2.0 * M_PI * (i + 1) / grid + theta; //底面 glBegin(GL_LINES); glVertex3f_p(cos(rad_1) * radius + xx, sin(rad_1) * radius + yy, 0.0); glVertex3f_p(cos(rad_2) * radius + xx, sin(rad_2) * radius + yy, 0.0); glEnd(); //天井 glBegin(GL_LINES); glVertex3f_p(cos(rad_1) * radius + xx, sin(rad_1) * radius + yy, robot_height); glVertex3f_p(cos(rad_2) * radius + xx, sin(rad_2) * radius + yy, robot_height); glEnd(); } //Dummyの位置を表示(Odometory誤差あり) glColor3f(1, 0, 0); //Red for (int i = 0; i < grid; i++) { double rad_1 = 2.0 * M_PI * i / grid + theta; double rad_2 = 2.0 * M_PI * (i + 1) / grid + theta; //底面 glBegin(GL_LINES); glVertex3f_p(cos(rad_1) * radius + myrobot.x_dummy, sin(rad_1) * radius + myrobot.y_dummy, 0.0); glVertex3f_p(cos(rad_2) * radius + myrobot.x_dummy, sin(rad_2) * radius + myrobot.y_dummy, 0.0); glEnd(); } glBegin(GL_LINES); glVertex3f_p(cos(myrobot.theta_dummy + M_PI / 2.0) * radius + myrobot.x_dummy, sin(myrobot.theta_dummy + M_PI / 2.0) * radius + myrobot.y_dummy, 0.0); glVertex3f_p(myrobot.x_dummy, myrobot.y_dummy, 0.0); glEnd(); //for(int i = 0; i < grid; i++){ // double rad_1= 2.0*M_PI*i/grid*4+theta; // glBegin(GL_LINES); // glVertex3f_p(cos(rad_1) * radius+xx, sin(rad_1) * radius+yy, 0.0); // glVertex3f_p(cos(rad_1) * radius+xx, sin(rad_1) * radius+yy, robot_height); // glEnd(); //} glColor3f(1, 0, 0); //Red //xx=robot.x; //yy=robot.y; //theta=robot.theta; glLineWidth(1.0); } void urg_3d_view(URG &urg_data, double pan, double tilt, double robot_z) { static int log_cnt = 0; log_cnt++; if (log_cnt > 1) log_cnt = 0; //static double xxx[500][1081]={}; //static double yyy[500][1081]={}; //static double zzz[500][1081]={}; for (int i = 1; i < urg_data.data_num - 1; i++) { double dis = urg_data.leng[i]; if (dis < urg_data.leng_min) dis = urg_data.leng_max; if (isnan(urg_data.leng[i])) dis = urg_data.leng_max; double xx = (-1) * dis * sin(i * urg_data.reso + urg_data.start_rad); double yy = dis * cos(i * urg_data.reso + urg_data.start_rad); double zz = 0.0; double xx_r = xx; double yy_r = yy * cos(tilt) - zz * sin(tilt); double zz_r = yy * sin(tilt) + zz * cos(tilt); double xx1 = xx_r * cos(pan + myrobot.theta) - yy_r * sin(pan + myrobot.theta); double yy1 = xx_r * sin(pan + myrobot.theta) + yy_r * cos(pan + myrobot.theta); double zz1 = zz_r; double dis2 = urg_data.leng[i - 1]; if (dis2 < urg_data.leng_min) dis2 = urg_data.leng_max; if (isnan(urg_data.leng[i - 1])) dis2 = urg_data.leng_max; xx = (-1) * dis2 * sin((i - 1) * urg_data.reso + urg_data.start_rad); yy = dis2 * cos((i - 1) * urg_data.reso + urg_data.start_rad); zz = 0.0; xx_r = xx; yy_r = yy * cos(tilt) - zz * sin(tilt); zz_r = yy * sin(tilt) + zz * cos(tilt); double xx2 = xx_r * cos(pan + myrobot.theta) - yy_r * sin(pan + myrobot.theta); double yy2 = xx_r * sin(pan + myrobot.theta) + yy_r * cos(pan + myrobot.theta); double zz2 = zz_r; if (i > 2) { glColor4f(0, 0, 1, 0.5); glBegin(GL_POLYGON); glVertex3f_p(myrobot.x, myrobot.y, robot_z); glVertex3f_p(myrobot.x + xx1, myrobot.y + yy1, zz1 + robot_z); glVertex3f_p(myrobot.x + xx2, myrobot.y + yy2, zz2 + robot_z); glEnd(); } glColor3f(0, 1, 1); //Red glBegin(GL_POINTS); glVertex3f_p(myrobot.x + xx1, myrobot.y + yy1, zz1 + robot_z); glEnd(); //xxx[log_cnt][i]=myrobot.x+xx1; //yyy[log_cnt][i]=myrobot.y+yy1; //zzz[log_cnt][i]=robot_z+zz1; } } static double get_dtime() { struct timeval tv; gettimeofday(&tv, NULL); long double n_time = tv.tv_sec + tv.tv_usec * 1e-6; static long double o_time = n_time; double dt_msec = (n_time - o_time); //cout<= 0.2) { double xx1 = (-1) * length * sin(i * urg_data2.reso + urg_data2.start_rad + myrobot.theta); double yy1 = length * cos(i * urg_data2.reso + urg_data2.start_rad + myrobot.theta); glBegin(GL_POINTS); glVertex3f_p(myrobot.x + xx1, myrobot.y + yy1, 0.2); glEnd(); } } ////////////////////////////////////////////////// ////////////////////////////////////////////////// glColor4f(0, 0, 1, 0.5); //Red for (int i = 0; i < urg_data3.data_num - 1; i++) { double length = urg_data3.leng[i]; if (length == 0) length = urg_data3.leng_max; if (isnan(urg_data3.leng[i])) length = urg_data3.leng_max; double xx1 = (-1) * length * sin(i * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); double yy1 = length * cos(i * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); double xx2 = (-1) * length * sin((i + 1) * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); double yy2 = length * cos((i + 1) * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); glBegin(GL_POLYGON); glVertex3f_p(myrobot.x, myrobot.y, 1.2); glVertex3f_p(myrobot.x + xx1, myrobot.y + yy1, 0.15); glVertex3f_p(myrobot.x + xx2, myrobot.y + yy2, 0.15); glEnd(); } glColor3f(0, 1, 0); //Red glPointSize(3.0); for (int i = 0; i < urg_data3.data_num - 1; i++) { double length = urg_data3.leng[i] - 0.1; if (length >= 0.2) { double xx1 = (-1) * length * sin(i * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); double yy1 = length * cos(i * urg_data3.reso + urg_data3.start_rad + myrobot.theta+M_PI); glBegin(GL_POINTS); glVertex3f_p(myrobot.x + xx1, myrobot.y + yy1, 0.15); glEnd(); } } ////////////////////////////////////////////////// ////////////////////////////////////////////////// if (pantilt_tilt_init_deg == 0) { double tilt_ros_time = now_stock / pantilt_tilt_rot_sin_speed * 2 * 3.1415; double tilt_sin = pantilt_tilt_rot_sin_amp * sin(tilt_ros_time); pantable.tilt = tilt_sin; } pantable.pan += pantilt_pan_rot_speed * now; pantable.pan = fmod(pantable.pan, 2 * M_PI); pantilt_time = ros::Time::now(); /*URG urg_data_buff;*/ urg_calcurate_3d(myrobot, obst, move_obst, urg_data, pantable.pan, pantable.tilt, robot_z); urg_noise(urg_data); urg_3d_view(urg_data, pantable.pan, pantable.tilt, robot_z); lrf_scantime = ros::Time::now(); glDisable(GL_BLEND); glPointSize(1.0); glColor4f(1, 0, 0, 1); //Red robot_move(myrobot, now); glDisable(GL_DEPTH_TEST); glPopMatrix(); } Graphics::Graphics() { xOrig = 0.0, yOrig = 0.0, zOrig = 0.0; //始点中心 gui_start(); } Graphics::~Graphics() { gui_end(); } extern int read_buf_flg; void Graphics::display() { glClearColor(1, 1, 1, 1); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); glPushMatrix(); polarview(); glEnable(GL_DEPTH_TEST); //メイン描画の関数 main_draw(); //main_draw2(); //gl_disp_save(); read_buf_flg = 1; glReadPixels(0, 0, WIDTH, HEIGHT, GL_RGB, GL_UNSIGNED_BYTE, capture_video_buf->imageData); cvConvertImage(capture_video_buf, capture_video, CV_CVTIMG_FLIP + CV_CVTIMG_SWAP_RB); read_buf_flg = 0; glPopMatrix(); glutSwapBuffers(); glutPostRedisplay(); //cout< 0) { //printf("idle, loop=%d, WinFlag=%d\n", loop, WinFlag[loop]); glutSetWindow(WinID[loop]); glutPostRedisplay(); //再描画 (※display()関数を呼び出す関数 ) } } wait_sleep(10); } void Graphics::myInit(char *progname) { float aspect = (float)WIDTH / (float)HEIGHT; glutInitWindowPosition(0, 0); glutInitWindowSize(WIDTH, HEIGHT); glutInitDisplayMode(GLUT_DOUBLE | GLUT_RGBA | GLUT_DEPTH); capture_video_buf = cvCreateImage(cvSize(WIDTH, HEIGHT), IPL_DEPTH_8U, 3); capture_video = cvCreateImage(cvSize(WIDTH, HEIGHT), IPL_DEPTH_8U, 3); //WindowMain WinID[WindowNum] = glutCreateWindow(WindowName[WindowNum]); printf("%d,%d\n", WinID[WindowNum], glutGetWindow()); WinFlag[WindowNum] = 1; WindowNum = WindowNum + 1; glutDisplayFunc(display); glutReshapeFunc(reshape); glutIdleFunc(idle); glClearColor(1, 1, 1, 1); glutKeyboardFunc(myKbd); glutKeyboardUpFunc(myKbdup); glutSpecialFunc(mySkey); glutMouseFunc(myMouse); glutMotionFunc(myMotion); resetview(); glMatrixMode(GL_PROJECTION); glLoadIdentity(); gluPerspective(45.0, aspect, 1.0, 200.0); //画角等視野の設定 glMatrixMode(GL_MODELVIEW); //glEnable(GL_LIGHTING); //glEnable(GL_LIGHT0); mySetLight(); glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); // Window2 // glutInitWindowPosition(WIDTH, 0); glutInitWindowSize(320, 240); WinID[WindowNum] = glutCreateWindow(WindowName[WindowNum]); printf("%d,%d\n", WinID[WindowNum], glutGetWindow()); WinFlag[WindowNum] = 1; WindowNum = WindowNum + 1; glutDisplayFunc(display2); glutReshapeFunc(reshape2); glutIdleFunc(idle); //glutMouseFunc(myMouse2); //glutMotionFunc(myMotion2); // glutSpecialFunc( mySkey2 ); mySetLight(); pantable.pan = pantilt_pan_init_deg * M_PI * 2.0 / 360.0; pantable.tilt = pantilt_tilt_init_deg * M_PI * 2.0 / 360.0; } void Graphics::reshape(int, int) { //glutReshapeWindow( WIDTH, HEIGHT ); } int Graphics::GUImain() { // read_obstacle(obst); //read_moveobstacle(move_obst); int argc = 3; char *argv[] = {"program", "-display", ":0.0"}; glutInit(&argc, argv); read_obstacle(obst); char *win_name = "simulation"; myInit(win_name); //mqoInit(); //gl_mqoModel = mqoCreateModel("robot.mqo", 0.01); glutMainLoop(); return 0; } void Graphics::gui_start() { th1 = SDL_CreateThread((int (*)(void *))GUImain, this); } void Graphics::gui_end() { SDL_KillThread(th1); } double Graphics::timer_ms() { double timer_ms = cv::getTickCount(); return timer_ms; } void Graphics::myMouse(int button, int state, int x, int y) { double obj_x = 0, obj_y = 0, obj_z = 0; if (state == GLUT_DOWN) { switch (button) { case GLUT_LEFT_BUTTON: mButton = button; //click_pickup(x,y,obj_x,obj_y,obj_z); //goal_y=obj_y; //goal_x=obj_x; break; case GLUT_MIDDLE_BUTTON: break; case GLUT_RIGHT_BUTTON: mButton = button; break; } xBegin = x; yBegin = y; } if (state == GLUT_UP) { switch (button) { case GLUT_RIGHT_BUTTON: break; } } return; } void Graphics::myMotion(int x, int y) { int xDisp, yDisp; xDisp = x - xBegin; yDisp = y - yBegin; switch (mButton) { case GLUT_LEFT_BUTTON: azimuth -= (float)xDisp / 2.0; elevation -= (float)yDisp / 2.0; break; case GLUT_RIGHT_BUTTON: distance_gl -= (float)xDisp / 10.0; if (distance_gl < 0.000001) distance_gl = 0.000001; break; } xBegin = x; yBegin = y; glutPostRedisplay(); } void Graphics::myKbdup(unsigned char key, int x, int y) { switch (key) { //case 'w': //ROBOTの移動指令 // myrobot.v=0.0; // break; //case 's': //ROBOTの移動指令 // myrobot.v=-0.0; // break; //case 'a': //ROBOTの移動指令 // myrobot.w=-0.0; // break; //case 'd': //ROBOTの移動指令 // myrobot.w=+0.0; // break; } } void Graphics::myKbd(unsigned char key, int x, int y) { switch (key) { case 0x1B: //終了 // exit(0); break; case 'q': //視点をリセット // exit(0);; break; case 'z': //視点をリセット // gl_mode++; //myrobot.v=0; //myrobot.w=0; break; case 'x': //視点をリセット //gl_mode--; //myrobot.v=0; //myrobot.w=0; break; //case 'w': //ROBOTの移動指令 // myrobot.v=4.0; // // break; //case 's': //ROBOTの移動指令 // myrobot.v=-4.0; // // break; //case 'a': //ROBOTの移動指令 // myrobot.w=-1.0; // break; //case 'd': //ROBOTの移動指令 // myrobot.w=+1.0; // break; case 'c': //ROBOTの移動指令 if (save_flg == 0) save_flg = 1; else if (save_flg == 1) save_flg = 0; break; } } void Graphics::mySkey(int key, int x, int y) { switch (key) { case GLUT_KEY_LEFT: xOrig -= 1; break; case GLUT_KEY_RIGHT: xOrig += 1; break; case GLUT_KEY_UP: yOrig += 1; break; case GLUT_KEY_DOWN: yOrig -= 1; break; case GLUT_KEY_PAGE_UP: zOrig += 1; break; case GLUT_KEY_PAGE_DOWN: zOrig -= 1; break; } glutPostRedisplay(); } void Graphics::resetview(void) { distance_gl = 30.0; twist = 0.0; elevation = -60.0; azimuth = 25.0; } void Graphics::polarview(void) { //マウスで移動 glTranslatef(0.0, 0.0, -distance_gl); glRotatef(-twist, 0.0, 0.0, 1.0); glRotatef(-elevation, 1.0, 0.0, 0.0); glRotatef(-azimuth, 0.0, 1.0, 0.0); //キーボードで移動 glTranslatef(xOrig, zOrig, yOrig); } float Graphics::click_Depth(int x, int y) { //マウスのX/Y座標からDepthを算出 float z; GLint viewport[4]; //ビューポート //デバイス座標系とウィンドウ座標系の変換 glGetIntegerv(GL_VIEWPORT, viewport); //現在のビューポートを代入 glReadPixels(x, viewport[3] - y, 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &z); // デプスバッファの値を返す. return z; } void Graphics::click_pickup(int x, int y, double &ax, double &ay, double &az) { //マウスのX/Y座標からX/Y/Z座標を算出 GLdouble modelview[16]; GLdouble projection[16]; GLint viewport[4]; glGetDoublev(GL_MODELVIEW_MATRIX, modelview); glGetDoublev(GL_PROJECTION_MATRIX, projection); glGetIntegerv(GL_VIEWPORT, viewport); GLdouble winX, winY, winZ; GLdouble objX = 0.0, objY = 0.0, objZ = -distance_gl + yOrig; //原点のGLUT座標系を算出 gluProject(objX, objY, objZ, modelview, projection, viewport, &winX, &winY, &winZ); GLdouble objX1, objY1, objZ1; //gluUnProject((double)x,(double)y,0.0,modelview,projection,viewport,&objX1,&objY1,&objZ1); //cout<<"near_window:"<imageData, data, imgA->imageSize); cvCvtColor(imgA, imgA, CV_BGR2RGB); cvFlip(imgA, NULL, 0); // static int cnt = 0; char fname[256]; sprintf(fname, "img/img_%.5d.png", cnt); cvSaveImage(fname, imgA); cnt++; delete[] data; cvReleaseImage(&imgA); // save_flg=0; } void move_obstacle_view() { //int t_now= timeGetTime(); //msec int t_now = gettimeofday_sec(); static int t_start = t_now; static long double now = 0; now += (t_now - t_start) / 1000.0; //cout<