mod barometer.Init() based on hardware

This commit is contained in:
Andrew Tridgell 2011-11-13 13:47:54 +11:00 committed by Pat Hickey
parent 2d8ce38aeb
commit 89d2f0f849
2 changed files with 17 additions and 6 deletions

View File

@ -187,13 +187,18 @@ static void init_ardupilot()
init_camera();
#if HIL_MODE != HIL_MODE_ATTITUDE
#if HIL_MODE != HIL_MODE_ATTITUDE
// begin filtering the ADC Gyros
adc.filter_result = true;
adc.Init(); // APM ADC library initialization
adc.Init(); // APM ADC library initialization
barometer.Init(); // APM Abs Pressure sensor initialization
#endif
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE
barometer.Init(1, true);
#else
barometer.Init(1, false);
#endif
#endif
// Do GPS init
g_gps = &g_gps_driver;

View File

@ -137,8 +137,14 @@ static void init_ardupilot()
#if HIL_MODE != HIL_MODE_ATTITUDE
adc.Init(); // APM ADC library initialization
barometer.Init(); // APM Abs Pressure sensor initialization
adc.Init(); // APM ADC library initialization
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE
barometer.Init(1, true);
#else
barometer.Init(1, false);
#endif
if (g.compass_enabled==true) {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft