mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: use mission singleton inside AP_AdvancedFailsafe
This commit is contained in:
parent
3013017369
commit
f21cddcf0f
|
@ -1094,7 +1094,7 @@ ParametersG2::ParametersG2(void)
|
|||
, proximity()
|
||||
#endif
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
,afs(copter.mode_auto.mission)
|
||||
,afs()
|
||||
#endif
|
||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||
,smart_rtl()
|
||||
|
|
|
@ -6,12 +6,6 @@
|
|||
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
|
||||
// Constructor
|
||||
AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission) :
|
||||
AP_AdvancedFailsafe(_mission)
|
||||
{}
|
||||
|
||||
|
||||
/*
|
||||
setup radio_out values for all channels to termination values
|
||||
*/
|
||||
|
|
|
@ -27,7 +27,8 @@
|
|||
class AP_AdvancedFailsafe_Copter : public AP_AdvancedFailsafe
|
||||
{
|
||||
public:
|
||||
AP_AdvancedFailsafe_Copter(AP_Mission &_mission);
|
||||
|
||||
using AP_AdvancedFailsafe::AP_AdvancedFailsafe;
|
||||
|
||||
// called to set all outputs to termination state
|
||||
void terminate_vehicle(void) override;
|
||||
|
|
Loading…
Reference in New Issue