Browse Source

ArduPlane: use mission singleton inside AP_AdvancedFailsafe

gps-1.3.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
cfe25f71e3
  1. 2
      ArduPlane/Plane.h
  2. 5
      ArduPlane/afs_plane.cpp
  3. 3
      ArduPlane/afs_plane.h

2
ArduPlane/Plane.h

@ -644,7 +644,7 @@ private: @@ -644,7 +644,7 @@ private:
// Outback Challenge Failsafe Support
#if ADVANCED_FAILSAFE == ENABLED
AP_AdvancedFailsafe_Plane afs {mission};
AP_AdvancedFailsafe_Plane afs;
#endif
/*

5
ArduPlane/afs_plane.cpp

@ -5,11 +5,6 @@ @@ -5,11 +5,6 @@
#include "Plane.h"
#if ADVANCED_FAILSAFE == ENABLED
// Constructor
AP_AdvancedFailsafe_Plane::AP_AdvancedFailsafe_Plane(AP_Mission &_mission) :
AP_AdvancedFailsafe(_mission)
{}
/*
setup radio_out values for all channels to termination values

3
ArduPlane/afs_plane.h

@ -27,7 +27,8 @@ @@ -27,7 +27,8 @@
class AP_AdvancedFailsafe_Plane : public AP_AdvancedFailsafe
{
public:
AP_AdvancedFailsafe_Plane(AP_Mission &_mission);
using AP_AdvancedFailsafe::AP_AdvancedFailsafe;
// called to set all outputs to termination state
void terminate_vehicle(void) override;

Loading…
Cancel
Save