int send_rr_app(int equalize, int segmentNumber, char* buf) { int i = 0; if(equalize == 0) { for(i = 0; i < ll.sequenceNumber; i++) ll.compFrame[i] = buf[i]; return llwrite(equalize,buf,0); } else if (equalize == 1) { if(checkFrames(buf) == 0) { if(segmentNumber > 0) saveChunk(buf,ll.sequenceNumber); } return llwrite(equalize,buf,0); } return -1; }
int main(int argc, char **argv) { ros::init(argc, argv, "oculus_image_viewer"); ros::NodeHandle node; image_transport::ImageTransport image_transport(node); std::string camera_topic = "/ardrone/front/image_raw"; ros::NodeHandle local_node("~"); local_node.getParam("camera_topic", camera_topic); ros::Subscriber sub_hmd_info = node.subscribe("/oculus/hmd_info", 1, &HMDInfoCallback); if (SDL_Init(SDL_INIT_VIDEO) < 0) { // Initialize SDL's Video subsystem std::cout << "Unable to initialize SDL"; return 1; } // Request opengl 4.4 context. SDL_GL_SetAttribute(SDL_GL_ACCELERATED_VISUAL, 1); SDL_GL_SetAttribute(SDL_GL_CONTEXT_MAJOR_VERSION, 3); SDL_GL_SetAttribute(SDL_GL_CONTEXT_MINOR_VERSION, 3); if (hmd_connected) { mainwindow = SDL_CreateWindow("oculus_viewer", SDL_WINDOWPOS_CENTERED_DISPLAY(hmd_info->DisplayId), SDL_WINDOWPOS_CENTERED_DISPLAY(hmd_info->DisplayId), hmd_info->HResolution, hmd_info->VResolution, SDL_WINDOW_FULLSCREEN_DESKTOP | SDL_WINDOW_OPENGL); } else { // Create our window centered mainwindow = SDL_CreateWindow("oculus_viewer", SDL_WINDOWPOS_CENTERED, SDL_WINDOWPOS_CENTERED, 1280, 800, SDL_WINDOW_OPENGL | SDL_WINDOW_SHOWN); // | SDL_WINDOW_RESIZABLE } if (!mainwindow) { // Die if creation failed std::cout << "SDL Error: " << SDL_GetError() << std::endl; SDL_Quit(); return 1; } bool quit = false; // image_transport::Subscriber sub_camera_image = image_transport.subscribe( // "/ardrone/front/image_raw", 1, &CameraImageCallback); image_transport::Subscriber sub_camera_image = image_transport.subscribe( camera_topic, 1, &CameraImageCallback); if (hmd_connected) { renderView = new Render::RenderView(mainwindow, maincontext, hmd_info->HResolution, hmd_info->VResolution); } else { renderView = new Render::RenderView(mainwindow, maincontext, 1280, 800); } ros::Rate rate(60); SDL_Event event; while (!quit && ros::ok()) { #if SHOWFPS==1 checkFrames(); #endif // if (hmd_connected) { // renderView->display(); // } else { // renderView->display(); // } renderView->display(); SDL_GL_SwapWindow(mainwindow); while (SDL_PollEvent(&event)) { switch (event.type) { case SDL_QUIT: quit = true; break; /*case SDL_WINDOWEVENT: if (event.window.event == SDL_WINDOWEVENT_RESIZED) renderView->reshape(event.window.data1, event.window.data2); break; */ case SDL_KEYDOWN: switch (event.key.keysym.sym) { case SDLK_UP: renderView->increaseScale(0.05); break; case SDLK_DOWN: renderView->increaseScale(-0.05); break; case SDLK_LEFT: renderView->increaseDistortionConstant(-0.05); break; case SDLK_RIGHT: renderView->increaseDistortionConstant(0.05); break; case SDLK_j: renderView->increaseInterpupillarDistance(-0.01); break; case SDLK_k: renderView->increaseInterpupillarDistance(0.01); break; } break; } } #if SHOWFPS==1 renderedFrames++; #endif ros::spinOnce(); rate.sleep(); } // Delete our opengl context, destroy our window, and shutdown SDL SDL_GL_DeleteContext(maincontext); SDL_DestroyWindow(mainwindow); SDL_Quit(); delete (renderView); return 0; }