void videoServer_endBroadcaster() { /* Signal broadcaster thread */ vp_os_mutex_lock(&frameBufferMutex); availVideoBuffer = NULL; vp_os_cond_signal(&frameBufferCond); vp_os_mutex_unlock(&frameBufferMutex); }
void video_stage_resume_thread(void) { vp_os_mutex_lock(&video_stage_mutex); vp_os_cond_signal(&video_stage_condition); video_stage_in_pause = FALSE; vp_os_mutex_unlock(&video_stage_mutex); }
C_RESULT academy_connect(const char *username, const char *password, academy_callback callback) { C_RESULT result = C_FAIL; if(academy_upload_started && (academy_upload.state.state == ACADEMY_STATE_NONE)) { if(!academy_upload.connected) { _ftp_t *academy_ftp = NULL; _ftp_status status; strcpy(academy_upload.user.username, username ? username : ""); strcpy(academy_upload.user.password, password ? password : ""); if(callback != NULL) academy_upload.callback = callback; academy_ftp = ftpConnectFromName(ACADEMY_SERVERNAME, ACADEMY_PORT, academy_upload.user.username, academy_upload.user.password, &status); if(academy_ftp != NULL) { ftpClose(&academy_ftp); vp_os_mutex_lock(&academy_upload.mutex); academy_upload.connected = TRUE; vp_os_cond_signal(&academy_upload.cond); vp_os_mutex_unlock(&academy_upload.mutex); result = C_OK; } } else result = C_OK; } return result; }
C_RESULT ardrone_navdata_client_resume(void) { vp_os_mutex_lock(&navdata_client_mutex); vp_os_cond_signal(&navdata_client_condition); navdata_thread_in_pause = FALSE; vp_os_mutex_unlock(&navdata_client_mutex); return C_OK; }
C_RESULT ardrone_navdata_client_shutdown(void) { bContinue = FALSE; vp_os_mutex_lock(&navdata_client_mutex); vp_os_cond_signal(&navdata_client_condition); vp_os_mutex_unlock(&navdata_client_mutex); return C_OK; }
void academy_upload_shutdown(void) { if(academy_upload_started) { academy_upload_started = FALSE; vp_os_mutex_lock(&academy_upload.mutex); vp_os_cond_signal(&academy_upload.cond); vp_os_mutex_unlock(&academy_upload.mutex); vp_os_thread_join(academy_upload_thread); } }
/** * \brief Signals the client control thread that new navdata were received. * Called by one of the navdata callbacks. */ C_RESULT ardrone_control_resume_on_navdata_received(uint32_t new_ardrone_state) { vp_os_mutex_lock(&control_mutex); if( control_waited ) { ardrone_state = new_ardrone_state; vp_os_cond_signal(&control_cond); } vp_os_mutex_unlock(&control_mutex); return C_OK; }
void test_callback(int res) { PRINT("<ArdroneTool callback>\n"); /* Make the test program continue */ if (res) { vp_os_cond_signal(&test_condition); } else { printf(" -- Configuration command is taking time to succeed ... ---\n"); } }
void videoServer_feedFrame_BGR24(uint64_t timeCode, int8_t *buffer) { availVideoBuffer = buffer; videoServer_lastFrameTimeCode = timeCode; vp_os_cond_signal(&frameBufferCond); }
DEFINE_THREAD_ROUTINE_STACK( vp_com_server, thread_params, VP_COM_THREAD_SERVER_STACK_SIZE ) { vp_com_socket_t client_sockets[VP_COM_THREAD_NUM_MAX_CLIENTS]; struct timeval tv, *ptv; // This thread setup connection then loop & wait for a socket event vp_com_server_thread_param_t* params = (vp_com_server_thread_param_t*) thread_params; int32_t i, rc, ncs, s, max = 0, num_server_sockets = params->num_servers, num_client_sockets = 0; vp_com_socket_t* server_sockets = params->servers; fd_set read_fs; vp_os_memset( client_sockets, 0, sizeof( client_sockets )); if(VP_FAILED(vp_com_init(params->com))) { DEBUG_PRINT_SDK("[VP_COM_SERVER] Failed to init com\n"); vp_com_shutdown(params->com); } else if(VP_FAILED(vp_com_local_config(params->com, params->config))) { DEBUG_PRINT_SDK("[VP_COM_SERVER] Failed to configure com\n"); vp_com_shutdown(params->com); } else if(VP_FAILED(vp_com_connect(params->com, params->connection, 1))) { DEBUG_PRINT_SDK("[VP_COM_SERVER] Failed to connect\n"); vp_com_shutdown(params->com); } else { vp_os_mutex_lock(&server_initialisation_mutex); vp_os_cond_signal(&server_initialisation_wait); vp_os_mutex_unlock(&server_initialisation_mutex); server_init_not_finished = FALSE; for( i = 0; i < num_server_sockets; i++ ) { if(VP_FAILED( vp_com_open_socket(&server_sockets[i], NULL, NULL) )) { DEBUG_PRINT_SDK("[VP_COM_SERVER] Unable to open server socket\n"); server_sockets[i].is_disable = TRUE; } else { listen((int32_t)server_sockets[i].priv, server_sockets[i].queue_length); } } params->run = TRUE; while( params->run == TRUE ) { if( params->timer_enable == FALSE || ( params->wait_sec == 0 && params->wait_usec == 0 ) ) { ptv = NULL; } else { tv.tv_sec = params->wait_sec; tv.tv_usec = params->wait_usec; ptv = &tv; } FD_ZERO(&read_fs); max = vp_com_fill_read_fs( &server_sockets[0], num_server_sockets, 0, &read_fs ); max = vp_com_fill_read_fs( &client_sockets[0], num_client_sockets, max, &read_fs ); rc = select( max + 1, &read_fs, NULL, NULL, ptv ); if( rc == -1 && ( errno == EINTR || errno == EAGAIN ) ) continue; if( rc == 0 ) { DEBUG_PRINT_SDK("[VP_COM_SERVER] select timeout\n"); vp_com_close_client_sockets(&client_sockets[0], num_client_sockets); num_client_sockets = 0; params->timer_enable = FALSE; vp_os_memset( client_sockets, 0, sizeof( client_sockets )); } for( i = 0; i < num_server_sockets && rc != 0; i++ ) { s = (int32_t) server_sockets[i].priv; if( ( !server_sockets[i].is_disable ) && FD_ISSET( s, &read_fs) ) { rc --; // Recycle previously released sockets for( ncs = 0; ncs < num_client_sockets && client_sockets[ncs].priv != NULL; ncs++ ); if( ncs < VP_COM_THREAD_NUM_MAX_CLIENTS) { if( VP_SUCCEEDED(vp_com_client_open_socket(&server_sockets[i], &client_sockets[ncs])) && ( ncs == num_client_sockets ) ) num_client_sockets ++; } } } for( i = 0; i < num_client_sockets && rc != 0; i++ ) { s = (int32_t) client_sockets[i].priv; if( ( !client_sockets[i].is_disable ) && FD_ISSET( s, &read_fs) ) { rc--; vp_com_client_receive( &client_sockets[i] ); } } } for( i = 0; i < num_server_sockets; i++ ) { vp_com_close_socket(&server_sockets[i]); } } vp_com_disconnect(params->com); vp_com_shutdown(params->com); THREAD_RETURN( 0 ); }
C_RESULT vp_stages_frame_pipe_sender_transform(vp_stages_frame_pipe_config_t *cfg, vp_api_io_data_t *in, vp_api_io_data_t *out) { int i; vp_os_mutex_lock(&out->lock); if(out->status == VP_API_STATUS_INIT) { /* Allocate an array to store pointers to the output buffers */ cfg->output_buffers = vp_os_malloc(cfg->nb_buffers*sizeof(*cfg->output_buffers)); /* Point to the first buffer */ cfg->index_buffer = 0; // initialize receiver vp_api_picture /* Copy the picture description */ vp_os_memcpy(&cfg->outPicture,cfg->inPicture,sizeof(cfg->outPicture)); /* Allocate memory to contain the copy picture */ vp_api_picture_alloc(&cfg->outPicture, cfg->inPicture->width, cfg->inPicture->height, cfg->inPicture->format ); /* fast mode uses a double buffer, allocate it if necessary */ if (cfg->mode == FAST) { for (i=0;i<cfg->nb_buffers;i++){ vp_api_picture_alloc(&cfg->copyPicture, cfg->inPicture->width, cfg->inPicture->height, cfg->inPicture->format ); cfg->output_buffers[i]=cfg->copyPicture.raw; } } cfg->frame_size = vp_api_picture_get_buffer_size(cfg->inPicture);//y_length + 2*cc_length; out->status = VP_API_STATUS_PROCESSING; } if (in->status == VP_API_STATUS_ERROR) { // previous stage gave an error vp_os_mutex_lock(&(cfg->pipe_mut)); { // signal receiver that sender is closed cfg->pipe_state = SENDER_ERROR; // resume receiver vp_os_cond_signal (&(cfg->buffer_sent)); } vp_os_mutex_unlock(&(cfg->pipe_mut)); PRINT("%s:%d sender error, close stage\n", __FILE__,__LINE__); } if( out->status == VP_API_STATUS_PROCESSING ) { vp_os_mutex_lock(&(cfg->pipe_mut)); { if (cfg->pipe_state == WAIT_RECEPTION || cfg->pipe_state == FETCH) { if (cfg->mode == LOW_LATENCY) { // in low latency mode, copy directly the frame in the destination buffer vp_os_memcpy(cfg->outPicture.raw,cfg->inPicture->raw,vp_api_picture_get_buffer_size(cfg->inPicture)); } else { // in fast mode, copy frame in the copy buffer cfg->index_buffer = (cfg->index_buffer+1)%cfg->nb_buffers; vp_api_picture_point_to_buf_address(&cfg->copyPicture,cfg->output_buffers[cfg->index_buffer]); vp_os_memcpy(cfg->copyPicture.raw,cfg->inPicture->raw,vp_api_picture_get_buffer_size(cfg->inPicture)); } // signal end of copy if (cfg->pipe_state == WAIT_RECEPTION) { cfg->pipe_state = PAUSE; vp_os_cond_signal (&(cfg->buffer_sent)); } else { cfg->pipe_state = FETCH_PAUSE; } } } vp_os_mutex_unlock(&(cfg->pipe_mut)); } /* wire in to out */ vp_os_memcpy (out, in, sizeof(vp_api_io_data_t)); vp_os_mutex_unlock(&out->lock); return C_OK; }