mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_Baro: allow selection of primary barometer and add 3rd baro
this is useful for external I2C barometers on a PH2
This commit is contained in:
parent
61441ab35d
commit
a5462fec0b
@ -55,6 +55,12 @@ const AP_Param::GroupInfo AP_Baro::var_info[] PROGMEM = {
|
|||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
|
AP_GROUPINFO("ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
|
||||||
|
|
||||||
|
// @Param: PRIMARY
|
||||||
|
// @DisplayName: Primary barometer
|
||||||
|
// @Description: This selects which barometer will be the primary if multiple barometers are found
|
||||||
|
// @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
|
||||||
|
AP_GROUPINFO("PRIMARY", 6, AP_Baro, _primary_baro, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -342,7 +348,15 @@ void AP_Baro::update(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// ensure the climb rate filter is updated
|
||||||
|
if (healthy()) {
|
||||||
|
_climb_rate_filter.update(get_altitude(), get_last_update());
|
||||||
|
}
|
||||||
|
|
||||||
// choose primary sensor
|
// choose primary sensor
|
||||||
|
if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {
|
||||||
|
_primary = _primary_baro;
|
||||||
|
} else {
|
||||||
_primary = 0;
|
_primary = 0;
|
||||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||||
if (healthy(i)) {
|
if (healthy(i)) {
|
||||||
@ -350,10 +364,6 @@ void AP_Baro::update(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ensure the climb rate filter is updated
|
|
||||||
if (healthy()) {
|
|
||||||
_climb_rate_filter.update(get_altitude(), get_last_update());
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -12,7 +12,7 @@
|
|||||||
#if HAL_CPU_CLASS == HAL_CPU_CLASS_16
|
#if HAL_CPU_CLASS == HAL_CPU_CLASS_16
|
||||||
#define BARO_MAX_INSTANCES 1
|
#define BARO_MAX_INSTANCES 1
|
||||||
#else
|
#else
|
||||||
#define BARO_MAX_INSTANCES 2
|
#define BARO_MAX_INSTANCES 3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// maximum number of drivers. Note that a single driver can provide
|
// maximum number of drivers. Note that a single driver can provide
|
||||||
@ -151,6 +151,7 @@ private:
|
|||||||
} sensors[BARO_MAX_INSTANCES];
|
} sensors[BARO_MAX_INSTANCES];
|
||||||
|
|
||||||
AP_Float _alt_offset;
|
AP_Float _alt_offset;
|
||||||
|
AP_Int8 _primary_baro; // primary chosen by user
|
||||||
float _last_altitude_EAS2TAS;
|
float _last_altitude_EAS2TAS;
|
||||||
float _EAS2TAS;
|
float _EAS2TAS;
|
||||||
float _external_temperature;
|
float _external_temperature;
|
||||||
|
@ -26,8 +26,9 @@ AP_Baro_PX4::AP_Baro_PX4(AP_Baro &baro) :
|
|||||||
memset(instances, 0, sizeof(instances));
|
memset(instances, 0, sizeof(instances));
|
||||||
instances[0].fd = open(BARO_BASE_DEVICE_PATH"0", O_RDONLY);
|
instances[0].fd = open(BARO_BASE_DEVICE_PATH"0", O_RDONLY);
|
||||||
instances[1].fd = open(BARO_BASE_DEVICE_PATH"1", O_RDONLY);
|
instances[1].fd = open(BARO_BASE_DEVICE_PATH"1", O_RDONLY);
|
||||||
|
instances[2].fd = open(BARO_BASE_DEVICE_PATH"2", O_RDONLY);
|
||||||
|
|
||||||
for (uint8_t i=0; i<2; i++) {
|
for (uint8_t i=0; i<3; i++) {
|
||||||
if (instances[i].fd != -1) {
|
if (instances[i].fd != -1) {
|
||||||
_num_instances = i+1;
|
_num_instances = i+1;
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user