Browse Source

Copter: remove rcmap member from AP_AdvancedFailsafe

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
dc61884303
  1. 2
      ArduCopter/Parameters.cpp
  2. 4
      ArduCopter/afs_copter.cpp
  3. 2
      ArduCopter/afs_copter.h

2
ArduCopter/Parameters.cpp

@ -1004,7 +1004,7 @@ ParametersG2::ParametersG2(void) @@ -1004,7 +1004,7 @@ ParametersG2::ParametersG2(void)
, proximity(copter.serial_manager)
#endif
#if ADVANCED_FAILSAFE == ENABLED
,afs(copter.mission, copter.gps, copter.rcmap)
,afs(copter.mission, copter.gps)
#endif
#if MODE_SMARTRTL_ENABLED == ENABLED
,smart_rtl()

4
ArduCopter/afs_copter.cpp

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

2
ArduCopter/afs_copter.h

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

Loading…
Cancel
Save