Rover: use baro singleton

This commit is contained in:
Peter Barker 2018-03-06 07:36:56 +11:00 committed by Lucas De Marchi
parent e9ecc11b00
commit 81ba037582
6 changed files with 13 additions and 13 deletions

View File

@ -9,9 +9,9 @@
class AP_Arming_Rover : public AP_Arming class AP_Arming_Rover : public AP_Arming
{ {
public: public:
AP_Arming_Rover(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, AP_Arming_Rover(const AP_AHRS &ahrs_ref, Compass &compass,
const AP_BattMonitor &battery, const AC_Fence &fence) const AP_BattMonitor &battery, const AC_Fence &fence)
: AP_Arming(ahrs_ref, baro, compass, battery), : AP_Arming(ahrs_ref, compass, battery),
_fence(fence) _fence(fence)
{ {
} }

View File

@ -345,12 +345,12 @@ bool GCS_MAVLINK_Rover::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(rover.barometer); send_scaled_pressure();
break; break;
case MSG_RAW_IMU3: case MSG_RAW_IMU3:
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
send_sensor_offsets(rover.ins, rover.compass, rover.barometer); send_sensor_offsets(rover.ins, rover.compass);
break; break;
case MSG_SIMSTATE: case MSG_SIMSTATE:

View File

@ -216,7 +216,7 @@ void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
void Rover::Log_Write_Baro(void) void Rover::Log_Write_Baro(void)
{ {
DataFlash.Log_Write_Baro(barometer); DataFlash.Log_Write_Baro();
} }
// log ahrs home and EKF origin to dataflash // log ahrs home and EKF origin to dataflash

View File

@ -169,15 +169,15 @@ private:
// Inertial Navigation EKF // Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
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 ahrs{ins, EKF2, EKF3};
#else #else
AP_AHRS_DCM ahrs{ins, barometer}; AP_AHRS_DCM ahrs{ins};
#endif #endif
// Arming/Disarming management class // Arming/Disarming management class
AP_Arming_Rover arming{ahrs, barometer, compass, battery, g2.fence}; AP_Arming_Rover arming{ahrs, compass, battery, g2.fence};
AP_L1_Control L1_controller{ahrs, nullptr}; AP_L1_Control L1_controller{ahrs, nullptr};

View File

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

View File

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