unsigned int __stdcall ioThreadCheetah(void* inst) { bt_data *data; BioTac bt_err_code; double length_of_data_in_second; int number_of_samples; int number_of_loops; int i; // Set the duration of the run time length_of_data_in_second = 0.01; number_of_samples = (int)(BT_SAMPLE_RATE_HZ_DEFAULT * length_of_data_in_second); /*************************************/ /* --- Configure the save buffer --- */ /*************************************/ data = bt_configure_save_buffer(number_of_samples); /*******************************/ /* --- Configure the batch --- */ /*******************************/ bt_err_code = bt_cheetah_configure_batch(ch_handle, &biotac, number_of_samples); if (bt_err_code < 0) { bt_display_errors(bt_err_code); exit(1); } else { printf("\nConfigured the batch\n"); } /***************************************************************/ /* --- Collect the batch and display the data (if desired) --- */ /***************************************************************/ number_of_loops = (int)(number_of_samples / ((double)(biotac.frame.frame_size * biotac.batch.batch_frame_count))); printf("Start collecting BioTac data for %.3f second(s)...\n", length_of_data_in_second); while (_ioThreadCheetahRun) { for (i = 0; i < number_of_loops; i++) { // To print out data on Terminal, set the fourth argument to YES (NO by default) bt_cheetah_collect_batch(ch_handle, &biotac, data, NO); ProcessMessage(data, number_of_samples); SaveBioTacData(); } bt_reset_save_buffer(); } /***********************/ /* --- Free memory --- */ /***********************/ free(data); return 0; }
bool InitBioTacCheetah() { BioTac bt_err_code; int i; /**************************************************************************/ /* --- Initialize BioTac settings (only default values are supported) --- */ /**************************************************************************/ biotac.spi_clock_speed = BT_SPI_BITRATE_KHZ_DEFAULT; biotac.number_of_biotacs = 0; biotac.sample_rate_Hz = BT_SAMPLE_RATE_HZ_DEFAULT; biotac.frame.frame_type = 0; biotac.batch.batch_frame_count = BT_FRAMES_IN_BATCH_DEFAULT; //biotac.batch.batch_ms = BT_BATCH_MS_DEFAULT; biotac.batch.batch_ms = 10; // 10msec, 1 frame per 1 batch // Check if any initial settings are wrong if (MAX_BIOTACS_PER_CHEETAH != 3 && MAX_BIOTACS_PER_CHEETAH != 5) { bt_err_code = BT_WRONG_MAX_BIOTAC_NUMBER; bt_display_errors(bt_err_code); //exit(1); return false; } /******************************************/ /* --- Initialize the Cheetah devices --- */ /******************************************/ ch_handle = bt_cheetah_initialize(&biotac); /*********************************************************/ /* --- Get and print out properties of the BioTac(s) --- */ /*********************************************************/ for (i = 0; i < MAX_BIOTACS_PER_CHEETAH; i++) { bt_err_code = bt_cheetah_get_properties(ch_handle, i+1, &(biotac_property[i])); if (biotac_property[i].bt_connected == YES) { (biotac.number_of_biotacs)++; } if (bt_err_code) { bt_display_errors(bt_err_code); //exit(1); return false; } } // Check if any BioTacs are detected if (biotac.number_of_biotacs == 0) { bt_err_code = BT_NO_BIOTAC_DETECTED; bt_display_errors(bt_err_code); //return bt_err_code; return false; } else { printf("\n%d BioTac(s) detected.\n\n", biotac.number_of_biotacs); } return true; }
//========================================================================= // MAIN PROGRAM //========================================================================= int main(void) { /****************************/ /* --- Define variables --- */ /****************************/ bt_info biotac; bt_property biotac_property[MAX_BIOTACS_PER_CHEETAH]; bt_data *data; BioTac bt_err_code; Cheetah ch_handle; int i; int length_of_data_in_second; int number_of_samples; int number_of_loops; /**************************************************************************/ /* --- Initialize BioTac settings (only default values are supported) --- */ /**************************************************************************/ biotac.spi_clock_speed = BT_SPI_BITRATE_KHZ_DEFAULT; biotac.number_of_biotacs = 0; biotac.sample_rate_Hz = BT_SAMPLE_RATE_HZ_DEFAULT; biotac.frame.frame_type = 0; biotac.batch.batch_frame_count = BT_FRAMES_IN_BATCH_DEFAULT; biotac.batch.batch_ms = BT_BATCH_MS_DEFAULT; // Set the duration of the run time length_of_data_in_second = 3; number_of_samples = (int)(BT_SAMPLE_RATE_HZ_DEFAULT * length_of_data_in_second); // Check if any initial settings are wrong if (MAX_BIOTACS_PER_CHEETAH != 3 && MAX_BIOTACS_PER_CHEETAH != 5) { bt_err_code = BT_WRONG_MAX_BIOTAC_NUMBER; bt_display_errors(bt_err_code); exit(1); } /******************************************/ /* --- Initialize the Cheetah devices --- */ /******************************************/ ch_handle = bt_cheetah_initialize(&biotac); /*********************************************************/ /* --- Get and print out properties of the BioTac(s) --- */ /*********************************************************/ for (i = 0; i < MAX_BIOTACS_PER_CHEETAH; i++) { bt_err_code = bt_cheetah_get_properties(ch_handle, i+1, &(biotac_property[i])); if (biotac_property[i].bt_connected == YES) { (biotac.number_of_biotacs)++; } if (bt_err_code) { bt_display_errors(bt_err_code); exit(1); } } // Check if any BioTacs are detected if (biotac.number_of_biotacs == 0) { bt_err_code = BT_NO_BIOTAC_DETECTED; bt_display_errors(bt_err_code); return bt_err_code; } else { printf("\n%d BioTac(s) detected.\n\n", biotac.number_of_biotacs); } // The programs stops here until it accepts [Enter] key hit printf("Press [Enter] to continue ..."); fflush(stdout); getchar(); /*************************************/ /* --- Configure the save buffer --- */ /*************************************/ data = bt_configure_save_buffer(number_of_samples); /*******************************/ /* --- Configure the batch --- */ /*******************************/ bt_err_code = bt_cheetah_configure_batch(ch_handle, &biotac, number_of_samples); if (bt_err_code < 0) { bt_display_errors(bt_err_code); exit(1); } else { printf("\nConfigured the batch\n"); } /***************************************************************/ /* --- Collect the batch and display the data (if desired) --- */ /***************************************************************/ number_of_loops = (int)(number_of_samples / ((double)(biotac.frame.frame_size * biotac.batch.batch_frame_count))); printf("Start collecting BioTac data for %d second(s)...\n", length_of_data_in_second); for (i = 0; i < number_of_loops; i++) { // To print out data on Terminal, set the fourth argument to YES (NO by default) bt_cheetah_collect_batch(ch_handle, &biotac, data, NO); } /*********************/ /* --- Save data --- */ /*********************/ bt_save_buffer_data("output.txt", data, number_of_samples); /**************************/ /* --- Close and exit --- */ /**************************/ printf("Press [Enter] to close the program"); fflush(stdout); getchar(); free(data); bt_cheetah_close(ch_handle); return 0; }