int main(int argc, char *argv[]) { (void)argc; (void)argv; struct aa_rx_win * win = aa_rx_win_default_create ( "Sync Test", SCREEN_WIDTH, SCREEN_HEIGHT ); struct aa_rx_sg *sg0 = aa_rx_dl_sg__scenegraph (NULL); aa_rx_sg_init(sg0); /* initialize scene graph internal structures */ aa_rx_win_sg_gl_init(win, sg0); /* Initialize scene graph GL-rendering objects */ aa_rx_win_set_sg(win, sg0); /* Set the scenegraph for the window */ // start display aa_rx_win_start(win); int n_thread = 10; pthread_t thread[n_thread]; for( size_t i = 0; i < n_thread; i ++ ) { pthread_create( thread + i, NULL, fun, win ); } for( size_t i = 0; i < n_thread; i ++ ) { pthread_join(thread[i], NULL ); } // Cleanup aa_rx_win_join(win); aa_rx_win_destroy(win); SDL_Quit(); return 0; }
int main(int argc, char *argv[]) { (void)argc; (void)argv; // Enable collision checking aa_rx_cl_init(); // Initialize scene graph struct aa_rx_sg *scenegraph = aa_rx_dl_sg__scenegraph(NULL); aa_rx_sg_init(scenegraph); aa_rx_sg_cl_init(scenegraph); // setup window struct aa_rx_win * win = baxter_demo_setup_window(scenegraph); struct aa_gl_globals *globals = aa_rx_win_gl_globals(win); aa_gl_globals_set_show_visual(globals, 0); aa_gl_globals_set_show_collision(globals, 1); struct display_cx cx = {0}; cx.win = win; cx.scenegraph = scenegraph; cx.i_q = aa_rx_sg_config_id(scenegraph, "left_s0"); cx.cl = aa_rx_cl_create( scenegraph ); { aa_rx_frame_id n = aa_rx_sg_frame_count(scenegraph); aa_rx_frame_id m = aa_rx_sg_config_count(scenegraph); double q[m]; AA_MEM_ZERO(q,m); double TF_rel[7*n]; double TF_abs[7*n]; aa_rx_sg_tf(scenegraph, m, q, n, TF_rel, 7, TF_abs, 7 ); struct aa_rx_cl_set *allowed = aa_rx_cl_set_create( scenegraph ); int col = aa_rx_cl_check( cx.cl, n, TF_abs, 7, allowed ); aa_rx_cl_allow_set( cx.cl, allowed ); aa_rx_cl_set_destroy( allowed ); } aa_rx_win_set_display( win, display, &cx ); aa_rx_win_display_loop(win); // Cleanup aa_rx_cl_destroy( cx.cl ); aa_rx_sg_destroy(scenegraph); aa_rx_win_destroy(win); SDL_Quit(); return 0; }
static void* fun( void *arg ) { fprintf(stderr, "+ worker thread starting\n"); struct aa_rx_win * win = (struct aa_rx_win * ) arg; struct aa_rx_sg *sg0 = aa_rx_dl_sg__scenegraph (NULL); for( size_t i = 0; i < 102400; i ++ ) { struct aa_rx_sg *sg1 = aa_rx_dl_sg__scenegraph(NULL); aa_rx_sg_init(sg1); /* initialize scene graph internal structures */ aa_rx_win_sg_gl_init(win, sg1); /* Initialize scene graph GL-rendering objects */ aa_rx_win_set_sg(win, sg1); aa_rx_sg_destroy(sg0); sg0 = sg1; } fprintf(stderr, "- worker thread finished\n"); }
int main(int argc, char *argv[]) { (void)argc; (void)argv; // Initialize scene graph struct aa_rx_sg *scenegraph = aa_rx_dl_sg__scenegraph(NULL); // setup window struct aa_rx_win * win = baxter_demo_setup_window(scenegraph); // start display aa_rx_win_start(win); // Cleanup aa_rx_win_join(win); aa_rx_sg_destroy(scenegraph); aa_rx_win_destroy(win); SDL_Quit(); return 0; }