void baro_init(void) { bmp085_init(&baro_bmp085, &i2c1, BMP085_SLAVE_ADDR); #ifdef BARO_LED LED_OFF(BARO_LED); #endif }
int main(void) { thread_t *sh = NULL; PollerData.temp = 0; PollerData.press = 0;/* PollerData.uTime = 0;*/ halInit(); chSysInit(); shellInit(); usbDisconnectBus(serusbcfg.usbp); chThdSleepMilliseconds(1000); usbStart(serusbcfg.usbp, &usbcfg); usbConnectBus(serusbcfg.usbp); sduObjectInit(&SDU1); sduStart(&SDU1, &serusbcfg); // SPI-related pins (for display) palSetPadMode(GPIOB, 11, PAL_MODE_OUTPUT_PUSHPULL); palSetPadMode(GPIOB, 10, PAL_MODE_OUTPUT_PUSHPULL); palSetPadMode(GPIOB, 13, PAL_MODE_ALTERNATE(5)); palSetPadMode(GPIOB, 14, PAL_MODE_OUTPUT_PUSHPULL); palSetPadMode(GPIOB, 15, PAL_MODE_ALTERNATE(5)); spiStart(&SPID1, &spi1cfg); spiStart(&SPID2, &spi2cfg); i2cStart(&I2CD1, &i2cconfig); initGyro(); initAccel(); initMag(); // nunchuk_status = nunchuk_init(); bmp085_status = bmp085_init(); lcd5110Init(); lcd5110SetPosXY(0, 0); lcd5110WriteText("P :: "); lcd5110SetPosXY(0, 1); lcd5110WriteText("T :: "); chThdCreateStatic(waThreadBlink, sizeof(waThreadBlink), NORMALPRIO, ThreadBlink, NULL); chThdCreateStatic(waThreadButton, sizeof(waThreadButton), NORMALPRIO, ThreadButton, NULL); chThdCreateStatic(waPoller, sizeof(waPoller), NORMALPRIO, ThreadPoller, NULL); while (TRUE) { if (!sh) { sh = shellCreate(&shCfg, SHELL_WA_SIZE, NORMALPRIO); } else if (chThdTerminatedX(sh)) { chThdRelease(sh); sh = NULL; } chThdSleepMilliseconds(1000); } return 0; // never returns, lol }
void baro_bmp_init(void) { bmp085_init(&baro_bmp, &BMP_I2C_DEV, BMP085_SLAVE_ADDR); baro_bmp_r = BARO_BMP_R; baro_bmp_sigma2 = BARO_BMP_SIGMA2; baro_bmp_enabled = TRUE; }
void TaskTWI(void) { OS_WaitTicks(OSALM_TWIWAIT,10); // BMP085 needs 10ms in advance. TWI_init(); bmp085_init(TaskTWIWait1ms); lsm303_config_accel(TaskTWIWait1ms); lsm303_config_magnet(TaskTWIWait1ms); // init ISR INTC_register_interrupt(&int_handler_ACC, AVR32_EIC_IRQ_0, AVR32_INTC_INTLEVEL_INT2); // activate and enable EIC pins: eic_enable_channel(0); // enable rising edge isr. TWI_RegisterReadyHandler(TWIreadyhandler); lsm303_TWI_trig_read_accel(); // restart interrupt TWIstate = etwi_readACC; lastACCSample = OS_GetTicks(); while(1) { if (OS_GetTicks()-lastACCSample > 400) { lsm303_TWI_trig_read_accel(); // restart interrupt TWIstate = etwi_readACC; } uint8_t ret = OS_WaitEventTimeout(OSEVT_TWIRDY,OSALM_TWITIMEOUT,200); if((ret & OSEVT_TWIRDY) == 0) { // timeout //asm("breakpoint"); fixme wtf why and why //emstop(5); // will hang up while flashing, if we stop here! } else { long bar = bmp085_calc_pressure(bmp085raw); // just read stuff from rx buffers out of ISR!!! (large calculation!) int32_t h_mm = bmp085_calcHeight_mm(bar); s_nHeight_mm = h_mm; // update global #if SIMULATION == 1 // do not update z position, this is done in TaskNavi to make it even more complicated. ;) #else NAV_UpdatePosition_z_m((float)h_mm*0.001); #endif } } }
int main( void ) { //set the length of the queues -> how many items the queue can hold const unsigned portBASE_TYPE measurementQueueLength = 5; //const unsigned portBASE_TYPE statusQueueLength = 5; xQueueHandle measurementQueue; //xQueueHandle statusQueue; // ...for temperature and pressure sensor double temperature = 0; int32_t pressure = 0; double altitude = 0; //configure time measurment pin as output //DDRD |= (1<<PB7); bmp085_init(); while( 1 ) { temperature = bmp085_gettemperature(); //pressure = bmp085_getpressure(); //altitude = bmp085_getaltitude(); //altitude = bmp085CalcAltitude ( pressure ); //_delay_ms(100); } //prvIncrementResetCount(); //create queues for intertask communication measurementQueue = xQueueCreate( measurementQueueLength, ( unsigned portBASE_TYPE ) sizeof( measurementQueueMsg * ) ); //statusQueue = xQueueCreate( statusQueueLength, ( unsigned portBASE_TYPE ) sizeof( statusQueueMsg * ) ); /* Create the tasks. */ startCommunicationTask( mainCOMMUNICATION_TASK_PRIORITY, &measurementQueue ); startNavigatorTask( mainNAVIGATOR_TASK_PRIORITY, &measurementQueue ); startOperatorTask( mainOPERATOR_TASK_PRIORITY, &measurementQueue ); startSensorTask( mainSENSOR_TASK_PRIORITY, &measurementQueue); /* In this port, to use preemptive scheduler define configUSE_PREEMPTION as 1 in portmacro.h. To use the cooperative scheduler define configUSE_PREEMPTION as 0. */ vTaskStartScheduler(); return 0; }
void baro_init(void) { bmp085_init(&baro_bmp085, &i2c2, BMP085_SLAVE_ADDR); /* setup eoc check function */ baro_bmp085.eoc = &baro_eoc; gpio_clear(GPIOB, GPIO0); gpio_setup_input_pulldown(GPIOB, GPIO0); #ifdef BARO_LED LED_OFF(BARO_LED); #endif }
void baro_init(void) { bmp085_init(&baro_bmp085, &i2c2, BMP085_SLAVE_ADDR); /* setup eoc check function */ baro_bmp085.eoc = &baro_eoc; gpio_clear(GPIOB, GPIO0); gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO0); #ifdef BARO_LED LED_OFF(BARO_LED); #endif }
void mwii_init(void){ //soc_init(); time_init(); uart_init(0, 38400, uart_buffer[0], 64, uart_buffer[1], 64); // setup printf stuff (specific to avr-libc) fdev_set_udata(&uart_fd, uart_get_serial_interface(0)); stdout = &uart_fd; stderr = &uart_fd; gpio_init(); //spi_init(); avr_i2c_init(0); pwm_init(); //adc0_init_default(); sei(); /* // setup stdout and stderr (avr-libc specific) fdev_setup_stream(stdout, _serial_fd_putc, _serial_fd_getc, _FDEV_SETUP_RW); fdev_set_udata(stdout, uart_get_serial_interface(0)); fdev_setup_stream(stderr, _serial_fd_putc, _serial_fd_getc, _FDEV_SETUP_RW); fdev_set_udata(stderr, uart_get_serial_interface(0)); */ // first thing must enable interrupts //kprintf("BOOT\n"); gpio_configure(GPIO_MWII_LED, GP_OUTPUT); //gpio_set(GPIO_MWII_LED); gpio_configure(GPIO_MWII_MOTOR0, GP_OUTPUT); gpio_configure(GPIO_MWII_MOTOR1, GP_OUTPUT); gpio_configure(GPIO_MWII_MOTOR2, GP_OUTPUT); gpio_configure(GPIO_MWII_MOTOR3, GP_OUTPUT); gpio_configure(GPIO_MWII_RX0, GP_INPUT | GP_PULLUP | GP_PCINT); gpio_configure(GPIO_MWII_RX1, GP_INPUT | GP_PULLUP | GP_PCINT); gpio_configure(GPIO_MWII_RX2, GP_INPUT | GP_PULLUP | GP_PCINT); gpio_configure(GPIO_MWII_RX3, GP_INPUT | GP_PULLUP | GP_PCINT); // calibrate escs //mwii_calibrate_escs(); // set initial motor speeds mwii_write_motors(MINCOMMAND, MINCOMMAND, MINCOMMAND, MINCOMMAND); brd->gpio0 = gpio_get_parallel_interface(); brd->twi0 = avr_i2c_get_interface(0); /* // I2C scanner for(int c = 0; c < 255; c++){ uint8_t buf[2]; i2c_start_read(brd->twi0, c, buf, 1); if(i2c_stop(brd->twi0) == 1 && c & 1){ kprintf("Device %x@i2c\n", c >> 1); } delay_us(10000); } */ gpio_set(GPIO_MWII_LED); i2cblk_init(&brd->mpublk, brd->twi0, MPU6050_ADDR, 8, I2CBLK_IADDR8); mpu6050_init(&brd->mpu, i2cblk_get_interface(&brd->mpublk)); //kdebug("MPU6050: %s\n", ((mpu6050_probe(&brd->mpu))?"found":"not found!")); i2cblk_init(&brd->bmpblk, brd->twi0, BMP085_ADDR, 8, I2CBLK_IADDR8); bmp085_init(&brd->bmp, i2cblk_get_interface(&brd->bmpblk)); //kdebug("BMP085: found\n"); i2cblk_init(&brd->hmcblk, brd->twi0, HMC5883L_ADDR, 8, I2CBLK_IADDR8); hmc5883l_init(&brd->hmc, i2cblk_get_interface(&brd->hmcblk)); gpio_clear(GPIO_MWII_LED); hcsr04_init(&brd->hcsr, brd->gpio0, GPIO_MWII_HCSR_TRIGGER, GPIO_MWII_HCSR_ECHO); ASYNC_PROCESS_INIT(&brd->process, mwii_task); ASYNC_QUEUE_WORK(&ASYNC_GLOBAL_QUEUE, &brd->process); //mwii_calibrate_mpu6050(); // let the escs init as well delay_us(500000L); }
void sensor_init(void) { mpu6050_init(); hmc5883l_init(); bmp085_init(); }
PROCESS_THREAD(default_app_process, ev, data) { PROCESS_BEGIN(); printf("Hello, world\n"); _delay_ms(100); #if DEBUG printf("Begin initialization:\n"); if (microSD_init() == 0) { printf(":microSD OK\n"); microSD_switchoff(); } else { printf(":microSD FAILURE\n"); } if (adxl345_init() == 0) { printf(":ADXL345 OK\n"); } else { printf(":ADXL345 FAILURE\n"); } if (at45db_init() == 0) { printf(":AT45DBxx OK\n"); } else { printf(":AT45DBxx FAILURE\n"); } // if (bmp085_init() == 0) { // printf(":BMP085 OK\n"); // } else { // printf(":BMP085 FAILURE\n"); // } // if (l3g4200d_init() == 0) { // printf(":L3G4200D OK\n"); // } else { // printf(":L3G4200D FAILURE\n"); // } #else adxl345_init(); microSD_switchoff(); at45db_init(); microSD_init(); bmp085_init(); l3g4200d_init(); #endif adc_init(ADC_SINGLE_CONVERSION, ADC_REF_2560MV_INT); etimer_set(&timer, CLOCK_SECOND * 0.05); while (1) { PROCESS_YIELD(); etimer_set(&timer, CLOCK_SECOND); int16_t tmp; /*############################################################*/ //ADXL345 serial Test printf("X:%+6d | Y:%+6d | Z:%+6d\n", adxl345_get_x_acceleration(), adxl345_get_y_acceleration(), adxl345_get_z_acceleration()); /*############################################################*/ //L3G4200d serial Test printf("X:%+6d | Y:%+6d | Z:%+6d\n", l3g4200d_get_x_angle(), l3g4200d_get_y_angle(), l3g4200d_get_z_angle()); printf("T1:%+3d\n", l3g4200d_get_temp()); /*############################################################*/ //BMP085 serial Test printf("P:%+6ld\n", (uint32_t) bmp085_read_pressure(BMP085_HIGH_RESOLUTION)); printf("T2:%+3d\n", bmp085_read_temperature()); /*############################################################*/ //Power Monitoring printf("V:%d\n", adc_get_value_from(PWR_MONITOR_ICC_ADC)); // tmp = adc_get_value_from(PWR_MONITOR_ICC_ADC); // // tmp = adc_get_value_from(PWR_MONITOR_VCC_ADC); // /*############################################################*/ //microSD Test // uint8_t buffer[512]; // uint16_t j; // microSD_init(); // for (j = 0; j < 512; j++) { // buffer[j] = 'u'; // buffer[j + 1] = 'e'; // buffer[j + 2] = 'r'; // buffer[j + 3] = '\n'; // // j = j + 3; // } // // microSD_write_block(2, buffer); // // microSD_read_block(2, buffer); // // for (j = 0; j < 512; j++) { // printf(buffer[j]); // } // microSD_deinit(); // /*############################################################*/ //Flash Test // uint8_t buffer[512]; // uint16_t j, i; // // for (i = 0; i < 10; i++) { // //at45db_erase_page(i); // for (j = 0; j < 512; j++) { // buffer[j] = i; // } // at45db_write_buffer(0, buffer, 512); // // at45db_buffer_to_page(i); // // at45db_read_page_bypassed(i, 0, buffer, 512); // // for (j = 0; j < 512; j++) { // printf("%02x", buffer[j]); // if (((j + 1) % 2) == 0) // printf(" "); // if (((j + 1) % 32) == 0) // printf("\n"); // } // } } PROCESS_END(); }
void boardsupport_init(central_data_t *central_data) { irq_initialize_vectors(); cpu_irq_enable(); Disable_global_interrupt(); // Initialize the sleep manager sleepmgr_init(); sysclk_init(); board_init(); delay_init(sysclk_get_cpu_hz()); time_keeper_init(); INTC_init_interrupts(); // Switch on the red LED LED_On(LED2); // servo_pwm_hardware_init(); pwm_servos_init( CS_ON_SERVO_7_8 ); // Init UART 0 for XBEE communication xbee_init(UART0); // Init UART 3 for GPS communication gps_ublox_init(&(central_data->gps), UART3); // Init UART 4 for wired communication //console_init(CONSOLE_UART4); // Init USB for wired communication console_init(CONSOLE_USB); // connect abstracted aliases to hardware ports central_data->telemetry_down_stream = xbee_get_out_stream(); central_data->telemetry_up_stream = xbee_get_in_stream(); central_data->debug_out_stream = console_get_out_stream(); central_data->debug_in_stream = console_get_in_stream(); // init debug output print_util_dbg_print_init(central_data->debug_out_stream); print_util_dbg_print("Debug stream initialised\r\n"); // Bind RC receiver with remote // spektrum_satellite_bind(); // RC receiver initialization spektrum_satellite_init(); // Init analog rails analog_monitor_conf_t analog_monitor_config = analog_monitor_default_config; //analog_monitor_config.conv_factor[ANALOG_RAIL_6] = 0.00023485f * 6.6f; //analog_monitor_config.conv_factor[ANALOG_RAIL_7] = 0.00023485f * 6.6f; //analog_monitor_config.conv_factor[ANALOG_RAIL_10] = -0.0002409f * 11.0f; //analog_monitor_config.conv_factor[ANALOG_RAIL_11] = -0.0002409f * 11.0f; analog_monitor_init(¢ral_data->analog_monitor, &analog_monitor_config); // init imu & compass i2c_driver_init(I2C0); lsm330dlc_init(); print_util_dbg_print("LSM330 initialised \r\n"); hmc5883l_init_slow(); print_util_dbg_print("HMC5883 initialised \r\n"); bmp085_init(¢ral_data->pressure); // init radar or ultrasound (not implemented yet) //i2c_driver_init(I2C1); // init 6V enable gpio_enable_gpio_pin(AVR32_PIN_PA04); gpio_set_gpio_pin(AVR32_PIN_PA04); Enable_global_interrupt(); // Init piezo speaker piezo_speaker_init_binary(); print_util_dbg_print("Board initialised\r\n"); }
/* * Application entry point. */ int main(void) { enum led_status lstat = LST_INIT; EventListener el0; alert_status_t proto_st = ALST_INIT; alert_status_t bmp085_st = ALST_INIT; alert_status_t mpu6050_st = ALST_INIT; alert_status_t hmc5883_st = ALST_INIT; /* * System initializations. * - HAL initialization, this also initializes the configured device drivers * and performs the board-specific initializations. * - Kernel initialization, the main() function becomes a thread and the * RTOS is active. */ halInit(); chSysInit(); #ifdef BOARD_IMU_AHRF /* Clear DRDY pad */ palClearPad(GPIOA, GPIOA_DRDY); /* Activates serial */ sdStart(&SD1, NULL); sdStart(&SD2, NULL); /* Activate pwm */ pwmStart(&PWMD1, &pwm1cfg); /* Activate i2c */ i2cStart(&I2CD1, &i2c1cfg); /* Activate exti */ extStart(&EXTD1, &extcfg); #endif /* BOARD_IMU_AHRF */ #ifdef BOARD_CAPTAIN_PRO2 /* Activates serial */ sdStart(&SD3, NULL); sdStart(&SD4, NULL); /* Activate pwm */ pwmStart(&PWMD3, &pwm3cfg); pwmStart(&PWMD4, &pwm4cfg); pwmStart(&PWMD5, &pwm5cfg); /* Activate i2c */ i2cStart(&I2CD1, &i2c1cfg); /* Activate exti */ extStart(&EXTD1, &extcfg); /* Activate adc */ adcStart(&ADCD1, NULL); #endif /* BOARD_CAPTAIN_PRO2 */ /* alert subsys */ chEvtInit(&alert_event_source); chEvtRegister(&alert_event_source, &el0, 0); /* init devices */ pt_init(); chThdSleepMilliseconds(10); /* power on delay */ #ifdef HAS_DEV_BMP085 bmp085_init(); chThdSleepMilliseconds(50); /* init delay */ #endif #ifdef HAS_DEV_MS5611 ms5611_init(&ms5611cfg); chThdSleepMilliseconds(50); /* init delay */ #endif #ifdef HAS_DEV_MPU6050 mpu6050_init(&mpu6050cfg); chThdSleepMilliseconds(250); /* give some time for mpu6050 configuration */ #endif #ifdef HAS_DEV_HMC5883 hmc5883_init(&hmc5883cfg); #endif #ifdef HAS_DEV_SERVOPWM servopwm_init(&servopwmcfg); #endif #ifdef HAS_DEV_NTC10K ntc10k_init(); #endif #ifdef HAS_DEV_RPM rpm_init(); #endif #ifdef BOARD_IMU_AHRF /* Set DRDY pad */ palSetPad(GPIOA, GPIOA_DRDY); #endif while (TRUE) { eventmask_t msk = chEvtWaitOneTimeout(ALL_EVENTS, MS2ST(100)); if (msk & EVENT_MASK(0)) { flagsmask_t fl = chEvtGetAndClearFlags(&el0); if (fl & ALERT_FLAG_PROTO) proto_st = pt_get_status(); #ifdef HAS_DEV_MPU6050 if (fl & ALERT_FLAG_MPU6050) mpu6050_st = mpu6050_get_status(); #endif #ifdef HAS_DEV_HMC5883 if (fl & ALERT_FLAG_HMC5883) hmc5883_st = hmc5883_get_status(); #endif #ifdef HAS_DEV_BMP085 if (fl & ALERT_FLAG_BMP085) bmp085_st = bmp085_get_status(); #endif #ifdef HAS_DEV_MS5611 if (fl & ALERT_FLAG_BMP085) bmp085_st = ms5611_get_status(); #endif pt_set_sens_state(mpu6050_st, hmc5883_st, bmp085_st); } if (proto_st == ALST_FAIL || mpu6050_st == ALST_FAIL || hmc5883_st == ALST_FAIL || bmp085_st == ALST_FAIL) lstat = LST_FAIL; else if (proto_st == ALST_INIT || mpu6050_st == ALST_INIT || hmc5883_st == ALST_INIT || bmp085_st == ALST_INIT) lstat = LST_INIT; else if (proto_st == ALST_NORMAL && mpu6050_st == ALST_NORMAL && hmc5883_st == ALST_NORMAL && bmp085_st == ALST_NORMAL) lstat = LST_NORMAL; led_update(lstat); } }
int main(void) { uint32_t count = 0; int32_t lat, lon, alt, temp1, temp2, pressure; uint8_t hour, minute, second; uint16_t mv; char msg[100]; uint8_t i, r; bmp085_t bmp; /* Set the LED pin for output */ DDRB |= _BV(DDB7); adc_init(); rtx_init(); bmp085_init(&bmp); #ifdef APRS_ENABLED ax25_init(); #endif #ifdef SSDV_ENABLED c3_init(); #endif sei(); gps_setup(); /* Enable the radio and let it settle */ rtx_enable(1); _delay_ms(1000); rtx_string_P(PSTR(RTTY_CALLSIGN " starting up\n")); /* Scan the 1-wire bus, up to 16 devices */ rtx_string_P(PSTR("Scanning 1-wire bus:\n")); for(i = 0; i < 16; i++) { r = ds_search_rom(id[i], i); if(r == DS_OK || r == DS_MORE) { /* A device was found, display the address */ rtx_wait(); snprintf_P(msg, 100, PSTR("%i> %02X-%02X-%02X-%02X-%02X-%02X-%02X-%02X\n"), i, id[i][0], id[i][1], id[i][2], id[i][3], id[i][4], id[i][5], id[i][6], id[i][7]); rtx_string(msg); } else { /* Device not responding or no devices found */ rtx_wait(); snprintf_P(msg, 100, PSTR("%i> Error %i\n"), i, r); rtx_string(msg); } /* No more devices? */ if(r != DS_MORE) break; } rtx_string_P(PSTR("Done\n")); while(1) { /* Set the GPS navmode every 10 strings */ if(count % 10 == 0) { /* Mode 6 is "Airborne with <1g Acceleration" */ if(gps_set_nav(6) != GPS_OK) { rtx_string_P(PSTR("$$" RTTY_CALLSIGN ",Error setting GPS navmode\n")); } } /* Get the latitude and longitude */ if(gps_get_pos(&lat, &lon, &alt) != GPS_OK) { rtx_string_P(PSTR("$$" RTTY_CALLSIGN ",No or invalid GPS response\n")); lat = lon = alt = 0; } /* Get the GPS time */ if(gps_get_time(&hour, &minute, &second) != GPS_OK) { rtx_string_P(PSTR("$$" RTTY_CALLSIGN ",No or invalid GPS response\n")); hour = minute = second = 0; } /* Read the battery voltage */ mv = adc_read(); /* Read the temperature from sensor 0 */ ds_read_temperature(&temp1, id[0]); /* Read the temperature from sensor 1 */ ds_read_temperature(&temp2, id[1]); /* Read the pressure from the BMP085 */ if(bmp085_sample(&bmp, 3) != BMP_OK) pressure = 0; else pressure = bmp085_calc_pressure(&bmp); /* Build up the string */ rtx_wait(); snprintf_P(msg, 100, PSTR("$$%s,%li,%02i:%02i:%02i,%s%li.%04li,%s%li.%04li,%li,%i.%01i,%li,%li,%li,%c"), RTTY_CALLSIGN, count++, hour, minute, second, (lat < 0 ? "-" : ""), labs(lat) / 10000000, labs(lat) % 10000000 / 1000, (lon < 0 ? "-" : ""), labs(lon) / 10000000, labs(lon) % 10000000 / 1000, alt / 1000, mv / 1000, mv / 100 % 10, temp1 / 10000, temp2 / 10000, pressure, (geofence_test(lat, lon) ? '1' : '0')); crccat(msg); rtx_string(msg); #ifdef APRS_ENABLED tx_aprs(lat, lon, alt); { int i; for(i = 0; i < 60; i++) _delay_ms(1000); } #endif #ifdef SSDV_ENABLED if(tx_image() == -1) { /* The camera goes to sleep while transmitting telemetry, * sync'ing here seems to prevent it. */ c3_sync(); } #endif } }