mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
mod barometer.Init() based on hardware
This commit is contained in:
parent
004a4425cd
commit
32073eaa51
@ -187,13 +187,18 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
init_camera();
|
init_camera();
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
// begin filtering the ADC Gyros
|
// begin filtering the ADC Gyros
|
||||||
adc.filter_result = true;
|
adc.filter_result = true;
|
||||||
|
adc.Init(); // APM ADC library initialization
|
||||||
|
|
||||||
adc.Init(); // APM ADC library initialization
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE
|
||||||
barometer.Init(); // APM Abs Pressure sensor initialization
|
barometer.Init(1, true);
|
||||||
#endif
|
#else
|
||||||
|
barometer.Init(1, false);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
// Do GPS init
|
// Do GPS init
|
||||||
g_gps = &g_gps_driver;
|
g_gps = &g_gps_driver;
|
||||||
|
@ -137,8 +137,14 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#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) {
|
if (g.compass_enabled==true) {
|
||||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||||
|
Loading…
Reference in New Issue
Block a user