Plane: use baro singleton
This commit is contained in:
parent
d88bd52a53
commit
f558bbca2e
@ -8,9 +8,9 @@
|
||||
class AP_Arming_Plane : public AP_Arming
|
||||
{
|
||||
public:
|
||||
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||
AP_Arming_Plane(const AP_AHRS &ahrs_ref, Compass &compass,
|
||||
const AP_BattMonitor &battery)
|
||||
: AP_Arming(ahrs_ref, baro, compass, battery)
|
||||
: AP_Arming(ahrs_ref, compass, battery)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
@ -473,12 +473,12 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
|
||||
case MSG_RAW_IMU2:
|
||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||
send_scaled_pressure(plane.barometer);
|
||||
send_scaled_pressure();
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU3:
|
||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
send_sensor_offsets(plane.ins, plane.compass, plane.barometer);
|
||||
send_sensor_offsets(plane.ins, plane.compass);
|
||||
break;
|
||||
|
||||
case MSG_FENCE_STATUS:
|
||||
|
@ -297,7 +297,7 @@ void Plane::Log_Write_RC(void)
|
||||
void Plane::Log_Write_Baro(void)
|
||||
{
|
||||
if (!ahrs.have_ekf_logging()) {
|
||||
DataFlash.Log_Write_Baro(barometer);
|
||||
DataFlash.Log_Write_Baro();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -122,7 +122,7 @@
|
||||
class AP_AdvancedFailsafe_Plane : public AP_AdvancedFailsafe
|
||||
{
|
||||
public:
|
||||
AP_AdvancedFailsafe_Plane(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap);
|
||||
AP_AdvancedFailsafe_Plane(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap);
|
||||
|
||||
// called to set all outputs to termination state
|
||||
void terminate_vehicle(void);
|
||||
@ -214,11 +214,11 @@ private:
|
||||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, EKF2, EKF3};
|
||||
NavEKF2 EKF2{&ahrs, rangefinder};
|
||||
NavEKF3 EKF3{&ahrs, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3};
|
||||
#else
|
||||
AP_AHRS_DCM ahrs{ins, barometer};
|
||||
AP_AHRS_DCM ahrs{ins};
|
||||
#endif
|
||||
|
||||
AP_TECS TECS_controller{ahrs, aparm, landing, g2.soaring_controller};
|
||||
@ -632,7 +632,7 @@ private:
|
||||
AP_Avoidance_Plane avoidance_adsb{ahrs, adsb};
|
||||
|
||||
// Outback Challenge Failsafe Support
|
||||
AP_AdvancedFailsafe_Plane afs {mission, barometer, gps, rcmap};
|
||||
AP_AdvancedFailsafe_Plane afs {mission, gps, rcmap};
|
||||
|
||||
/*
|
||||
meta data to support counting the number of circles in a loiter
|
||||
@ -752,7 +752,7 @@ private:
|
||||
#endif
|
||||
|
||||
// Arming/Disarming mangement class
|
||||
AP_Arming_Plane arming{ahrs, barometer, compass, battery};
|
||||
AP_Arming_Plane arming{ahrs, compass, battery};
|
||||
|
||||
AP_Param param_loader {var_info};
|
||||
|
||||
|
@ -5,8 +5,8 @@
|
||||
#include "Plane.h"
|
||||
|
||||
// Constructor
|
||||
AP_AdvancedFailsafe_Plane::AP_AdvancedFailsafe_Plane(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
|
||||
AP_AdvancedFailsafe(_mission, _baro, _gps, _rcmap)
|
||||
AP_AdvancedFailsafe_Plane::AP_AdvancedFailsafe_Plane(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap) :
|
||||
AP_AdvancedFailsafe(_mission, _gps, _rcmap)
|
||||
{}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user