ardupilot/ArduCopter/sensors.pde

107 lines
3.7 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// Sensors are not available in HIL_MODE_ATTITUDE
#if HIL_MODE != HIL_MODE_ATTITUDE
2012-08-16 21:50:03 -03:00
static void ReadSCP1000(void) {
}
2012-08-16 21:50:03 -03:00
#if CONFIG_SONAR == ENABLED
static void init_sonar(void)
{
2012-08-16 21:50:03 -03:00
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
sonar.calculate_scaler(g.sonar_type, 3.3);
#else
sonar.calculate_scaler(g.sonar_type, 5.0);
#endif
}
2012-08-16 21:50:03 -03:00
#endif
static void init_barometer(void)
{
barometer.calibrate(mavlink_delay);
ahrs.set_barometer(&barometer);
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
}
// return barometric altitude in centimeters
static int32_t read_barometer(void)
{
2012-08-16 21:50:03 -03:00
barometer.read();
return baro_filter.apply(barometer.get_altitude() * 100.0);
}
#endif // HIL_MODE != HIL_MODE_ATTITUDE
static void init_compass()
{
2012-08-16 21:50:03 -03:00
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init() || !compass.read()) {
// make sure we don't pass a broken compass to DCM
Serial.println_P(PSTR("COMPASS INIT ERROR"));
return;
}
ahrs.set_compass(&compass);
#if SECONDARY_DMP_ENABLED == ENABLED
ahrs2.set_compass(&compass);
#endif
}
static void init_optflow()
{
#ifdef OPTFLOW_ENABLED
if( optflow.init(false, &timer_scheduler, &spi_semaphore, &spi3_semaphore) == false ) {
2012-08-16 21:50:03 -03:00
g.optflow_enabled = false;
Serial.print_P(PSTR("\nFailed to Init OptFlow "));
2012-08-16 21:50:03 -03:00
}
// suspend timer while we set-up SPI communication
timer_scheduler.suspend_timer();
2012-08-16 21:50:03 -03:00
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
optflow.set_frame_rate(2000); // set minimum update rate (which should lead to maximum low light performance
optflow.set_resolution(OPTFLOW_RESOLUTION); // set optical flow sensor's resolution
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
// resume timer
timer_scheduler.resume_timer();
#endif
}
2012-11-13 10:43:54 -04:00
// read_battery - check battery voltage and current and invoke failsafe if necessary
// called at 10hz
#define BATTERY_FS_COUNTER 100 // 100 iterations at 10hz is 10 seconds
static void read_battery(void)
{
2012-11-13 10:43:54 -04:00
static uint8_t low_battery_counter = 0;
2012-08-16 21:50:03 -03:00
if(g.battery_monitoring == 0) {
battery_voltage1 = 0;
return;
}
2012-01-24 04:13:56 -04:00
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
static AP_AnalogSource_Arduino batt_volt_pin(g.battery_volt_pin);
batt_volt_pin.set_pin(g.battery_volt_pin);
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin.read_average());
}
2012-08-16 21:50:03 -03:00
if(g.battery_monitoring == 4) {
static AP_AnalogSource_Arduino batt_curr_pin(g.battery_curr_pin);
batt_curr_pin.set_pin(g.battery_curr_pin);
current_amps1 = CURRENT_AMPS(batt_curr_pin.read_average());
2012-08-16 21:50:03 -03:00
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
}
2012-11-13 10:43:54 -04:00
// check for low voltage or current if the low voltage check hasn't already been triggered
if (!ap.low_battery && ( battery_voltage1 < g.low_voltage || (g.battery_monitoring == 4 && current_total1 > g.pack_capacity))) {
low_battery_counter++;
if( low_battery_counter >= BATTERY_FS_COUNTER ) {
low_battery_counter = BATTERY_FS_COUNTER; // ensure counter does not overflow
low_battery_event();
2012-08-16 21:50:03 -03:00
}
2012-11-13 10:43:54 -04:00
}else{
// reset low_battery_counter in case it was a temporary voltage dip
low_battery_counter = 0;
2012-08-16 21:50:03 -03:00
}
}