From 0b1091231c447c54bea1c79f5547885d644a8aa5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 5 May 2018 18:28:48 +1000 Subject: [PATCH] Rover: remove rcmap member from AP_AdvancedFailsafe Also correct constructor for barometer Also make it compile again --- APMrover2/Parameters.cpp | 2 +- APMrover2/afs_rover.cpp | 4 ++-- APMrover2/afs_rover.h | 2 +- APMrover2/failsafe.cpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 3935b98282..5f5d292aa1 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -562,7 +562,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { ParametersG2::ParametersG2(void) : #if ADVANCED_FAILSAFE == ENABLED - afs(rover.mission, rover.barometer, rover.gps, rover.rcmap), + afs(rover.mission, rover.gps), #endif beacon(rover.serial_manager), motors(rover.ServoRelayEvents), diff --git a/APMrover2/afs_rover.cpp b/APMrover2/afs_rover.cpp index 62f1e49fd2..6c588e013a 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, const AP_GPS &_gps, const RCMapper &_rcmap) : - AP_AdvancedFailsafe(_mission, _gps, _rcmap) +AP_AdvancedFailsafe_Rover::AP_AdvancedFailsafe_Rover(AP_Mission &_mission, const AP_GPS &_gps) : + AP_AdvancedFailsafe(_mission, _gps) {} diff --git a/APMrover2/afs_rover.h b/APMrover2/afs_rover.h index 3367d8da71..181551a910 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, const AP_GPS &_gps, const RCMapper &_rcmap); + AP_AdvancedFailsafe_Rover(AP_Mission &_mission, const AP_GPS &_gps); // called to set all outputs to termination state void terminate_vehicle(void) override; diff --git a/APMrover2/failsafe.cpp b/APMrover2/failsafe.cpp index d1ff2a3f25..af7ac46d01 100644 --- a/APMrover2/failsafe.cpp +++ b/APMrover2/failsafe.cpp @@ -123,7 +123,7 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action) #if ADVANCED_FAILSAFE == ENABLED char battery_type_str[17]; snprintf(battery_type_str, 17, "%s battery", type_str); - afs.gcs_terminate(true, battery_type_str); + g2.afs.gcs_terminate(true, battery_type_str); #else disarm_motors(); #endif // ADVANCED_FAILSAFE == ENABLED