From 81ba0375826135f4173891df1b603c32b536dff8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 6 Mar 2018 07:36:56 +1100 Subject: [PATCH] Rover: use baro singleton --- APMrover2/AP_Arming.h | 4 ++-- APMrover2/GCS_Mavlink.cpp | 4 ++-- APMrover2/Log.cpp | 2 +- APMrover2/Rover.h | 10 +++++----- APMrover2/afs_rover.cpp | 4 ++-- APMrover2/afs_rover.h | 2 +- 6 files changed, 13 insertions(+), 13 deletions(-) diff --git a/APMrover2/AP_Arming.h b/APMrover2/AP_Arming.h index 8035deaac2..0b1af5e93b 100644 --- a/APMrover2/AP_Arming.h +++ b/APMrover2/AP_Arming.h @@ -9,9 +9,9 @@ class AP_Arming_Rover : public AP_Arming { 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) - : AP_Arming(ahrs_ref, baro, compass, battery), + : AP_Arming(ahrs_ref, compass, battery), _fence(fence) { } diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 073c577c1f..a7c1e68648 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -345,12 +345,12 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) case MSG_RAW_IMU2: CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); - send_scaled_pressure(rover.barometer); + send_scaled_pressure(); break; case MSG_RAW_IMU3: CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); - send_sensor_offsets(rover.ins, rover.compass, rover.barometer); + send_sensor_offsets(rover.ins, rover.compass); break; case MSG_SIMSTATE: diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 564bf1ca96..1014eb4043 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -216,7 +216,7 @@ void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code) void Rover::Log_Write_Baro(void) { - DataFlash.Log_Write_Baro(barometer); + DataFlash.Log_Write_Baro(); } // log ahrs home and EKF origin to dataflash diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 70f0905e59..c0e49d7dbf 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -169,15 +169,15 @@ 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 // 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}; diff --git a/APMrover2/afs_rover.cpp b/APMrover2/afs_rover.cpp index 3ad7d7951c..62f1e49fd2 100644 --- a/APMrover2/afs_rover.cpp +++ b/APMrover2/afs_rover.cpp @@ -7,8 +7,8 @@ #if ADVANCED_FAILSAFE == ENABLED // Constructor -AP_AdvancedFailsafe_Rover::AP_AdvancedFailsafe_Rover(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) : - AP_AdvancedFailsafe(_mission, _baro, _gps, _rcmap) +AP_AdvancedFailsafe_Rover::AP_AdvancedFailsafe_Rover(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap) : + AP_AdvancedFailsafe(_mission, _gps, _rcmap) {} diff --git a/APMrover2/afs_rover.h b/APMrover2/afs_rover.h index fdc77c6140..3367d8da71 100644 --- a/APMrover2/afs_rover.h +++ b/APMrover2/afs_rover.h @@ -27,7 +27,7 @@ class AP_AdvancedFailsafe_Rover : public AP_AdvancedFailsafe { 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 void terminate_vehicle(void) override;