Browse Source

Plane: correct compilation when parachute disabled

mission-4.1.18
Peter Barker 8 years ago committed by Tom Pittenger
parent
commit
af9729c126
  1. 4
      ArduPlane/Plane.h
  2. 6
      ArduPlane/parachute.cpp

4
ArduPlane/Plane.h

@ -1092,10 +1092,12 @@ private: @@ -1092,10 +1092,12 @@ private:
void init_capabilities(void);
void dataflash_periodic(void);
uint16_t throttle_min(void) const;
void do_parachute(const AP_Mission::Mission_Command& cmd);
void parachute_check();
#if PARACHUTE == ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);
void parachute_release();
bool parachute_manual_release();
#endif
void accel_cal_update(void);
void update_soft_armed();

6
ArduPlane/parachute.cpp

@ -6,9 +6,13 @@ @@ -6,9 +6,13 @@
*/
void Plane::parachute_check()
{
#if PARACHUTE == ENABLED
parachute.update();
#endif
}
#if PARACHUTE == ENABLED
/*
parachute_release - trigger the release of the parachute
*/
@ -49,3 +53,5 @@ bool Plane::parachute_manual_release() @@ -49,3 +53,5 @@ bool Plane::parachute_manual_release()
return true;
}
#endif

Loading…
Cancel
Save