Copter: use baro singleton

This commit is contained in:
Peter Barker 2018-03-06 07:37:25 +11:00 committed by Lucas De Marchi
parent 81ba037582
commit d88bd52a53
7 changed files with 13 additions and 13 deletions

View File

@ -7,10 +7,10 @@ class AP_Arming_Copter : public AP_Arming
public:
friend class Copter;
friend class ToyMode;
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, const AP_Baro &baro, Compass &compass,
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, Compass &compass,
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav,
const AP_InertialSensor &ins)
: AP_Arming(ahrs_ref, baro, compass, battery)
: AP_Arming(ahrs_ref, compass, battery)
, _inav(inav)
, _ins(ins)
, _ahrs_navekf(ahrs_ref)

View File

@ -239,9 +239,9 @@ private:
AP_RPM rpm_sensor;
// Inertial Navigation EKF
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
AP_AHRS_NavEKF ahrs{ins, barometer, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
NavEKF2 EKF2{&ahrs, rangefinder};
NavEKF3 EKF3{&ahrs, rangefinder};
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl;
@ -266,7 +266,7 @@ private:
#endif
// Arming/Disarming mangement class
AP_Arming_Copter arming{ahrs, barometer, compass, battery, inertial_nav, ins};
AP_Arming_Copter arming{ahrs, compass, battery, inertial_nav, ins};
// Optical flow sensor
#if OPTFLOW == ENABLED

View File

@ -345,12 +345,12 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
case MSG_RAW_IMU2:
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
send_scaled_pressure(copter.barometer);
send_scaled_pressure();
break;
case MSG_RAW_IMU3:
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
send_sensor_offsets(copter.ins, copter.compass, copter.barometer);
send_sensor_offsets(copter.ins, copter.compass);
break;
case MSG_RANGEFINDER:
@ -1652,7 +1652,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
ins.set_accel(0, accels);
copter.barometer.setHIL(packet.alt*0.001f);
AP::baro().setHIL(packet.alt*0.001f);
copter.compass.setHIL(0, packet.roll, packet.pitch, packet.yaw);
copter.compass.setHIL(1, packet.roll, packet.pitch, packet.yaw);

View File

@ -380,7 +380,7 @@ void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
void Copter::Log_Write_Baro(void)
{
if (!ahrs.have_ekf_logging()) {
DataFlash.Log_Write_Baro(barometer);
DataFlash.Log_Write_Baro();
}
}

View File

@ -1002,7 +1002,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
constructor for g2 object
*/
ParametersG2::ParametersG2(void)
: temp_calibration(copter.barometer, copter.ins)
: temp_calibration(copter.ins)
#if BEACON_ENABLED == ENABLED
, beacon(copter.serial_manager)
#endif

View File

@ -7,7 +7,7 @@
#if ADVANCED_FAILSAFE == ENABLED
// Constructor
AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap) :
AP_AdvancedFailsafe(_mission, _baro, _gps, _rcmap)
{}

View File

@ -27,7 +27,7 @@
class AP_AdvancedFailsafe_Copter : public AP_AdvancedFailsafe
{
public:
AP_AdvancedFailsafe_Copter(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap);
AP_AdvancedFailsafe_Copter(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap);
// called to set all outputs to termination state
void terminate_vehicle(void);