int display( struct aa_rx_win *win, void *cx_, struct aa_sdl_display_params *params ) { (void)win; struct display_cx *cx = (struct display_cx *)cx_; const struct timespec *now = aa_sdl_display_params_get_time_now(params); const struct timespec *last = aa_sdl_display_params_get_time_last(params); const struct aa_rx_sg *scenegraph = cx->scenegraph; size_t n = aa_rx_sg_frame_count(scenegraph); size_t m = aa_rx_sg_config_count(scenegraph); double q[m]; AA_MEM_ZERO(q,m); int first = aa_sdl_display_params_is_first(params); if( ! first ) { double dt = aa_tm_timespec2sec( aa_tm_sub(*now, *last) ); cx->q += dt * 45 * (M_PI/180); } q[ cx->i_q ] = cx->q; double TF_rel[7*n]; double TF_abs[7*n]; aa_rx_sg_tf(scenegraph, m, q, n, TF_rel, 7, TF_abs, 7 ); aa_rx_win_display_sg_tf( cx->win, params, scenegraph, n, TF_abs, 7 ); int col = aa_rx_cl_check( cx->cl, n, TF_abs, 7, NULL ); printf("in collision: %s\n", col ? "yes" : "no" ); return 0; }
AA_API struct timespec aa_tock(void) { struct timespec t = aa_tm_sub( aa_tm_now(), aa_tick_tock_start ); fprintf( stderr, "%.6f ms\n", (double)t.tv_sec*1e3 + (double)t.tv_nsec / 1e6 ); return t; }