mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Sub: use baro singleton
This commit is contained in:
parent
f558bbca2e
commit
06f6135daa
@ -4,9 +4,9 @@
|
|||||||
|
|
||||||
class AP_Arming_Sub : public AP_Arming {
|
class AP_Arming_Sub : public AP_Arming {
|
||||||
public:
|
public:
|
||||||
AP_Arming_Sub(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
AP_Arming_Sub(const AP_AHRS &ahrs_ref, Compass &compass,
|
||||||
const AP_BattMonitor &battery)
|
const AP_BattMonitor &battery)
|
||||||
: AP_Arming(ahrs_ref, baro, compass, battery)
|
: AP_Arming(ahrs_ref, compass, battery)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -544,13 +544,13 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||||||
|
|
||||||
case MSG_RAW_IMU2:
|
case MSG_RAW_IMU2:
|
||||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||||
send_scaled_pressure(sub.barometer);
|
send_scaled_pressure();
|
||||||
sub.send_temperature(chan);
|
sub.send_temperature(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RAW_IMU3:
|
case MSG_RAW_IMU3:
|
||||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||||
send_sensor_offsets(sub.ins, sub.compass, sub.barometer);
|
send_sensor_offsets(sub.ins, sub.compass);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RANGEFINDER:
|
case MSG_RANGEFINDER:
|
||||||
|
@ -318,7 +318,7 @@ void Sub::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
|
|||||||
void Sub::Log_Write_Baro(void)
|
void Sub::Log_Write_Baro(void)
|
||||||
{
|
{
|
||||||
if (!ahrs.have_ekf_logging()) {
|
if (!ahrs.have_ekf_logging()) {
|
||||||
DataFlash.Log_Write_Baro(barometer);
|
DataFlash.Log_Write_Baro();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -186,9 +186,9 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
NavEKF2 EKF2{&ahrs, rangefinder};
|
||||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
NavEKF3 EKF3{&ahrs, rangefinder};
|
||||||
AP_AHRS_NavEKF ahrs{ins, barometer, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
SITL::SITL sitl;
|
SITL::SITL sitl;
|
||||||
@ -330,7 +330,7 @@ private:
|
|||||||
// Battery Sensors
|
// Battery Sensors
|
||||||
AP_BattMonitor battery{MASK_LOG_CURRENT};
|
AP_BattMonitor battery{MASK_LOG_CURRENT};
|
||||||
|
|
||||||
AP_Arming_Sub arming{ahrs, barometer, compass, battery};
|
AP_Arming_Sub arming{ahrs, compass, battery};
|
||||||
|
|
||||||
// Altitude
|
// Altitude
|
||||||
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
||||||
|
Loading…
Reference in New Issue
Block a user