Browse Source

Copter: remove ability to disable PosHold flight mode

This flight mode is stable and regularly used so it is unlikely that we ever want to disable it
master
Randy Mackay 7 years ago
parent
commit
0ac708b5a0
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/Copter.h
  3. 2
      ArduCopter/FlightMode.h
  4. 2
      ArduCopter/Parameters.cpp
  5. 3
      ArduCopter/config.h
  6. 4
      ArduCopter/control_poshold.cpp
  7. 2
      ArduCopter/flight_mode.cpp

1
ArduCopter/APM_Config.h

@ -11,7 +11,6 @@ @@ -11,7 +11,6 @@
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash
//#define PROXIMITY_ENABLED DISABLED // disable proximity sensors
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
//#define AC_TERRAIN DISABLED // disable terrain library
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash

2
ArduCopter/Copter.h

@ -973,9 +973,7 @@ private: @@ -973,9 +973,7 @@ private:
Copter::FlightMode_Loiter flightmode_loiter{*this};
#if POSHOLD_ENABLED == ENABLED
Copter::FlightMode_PosHold flightmode_poshold{*this};
#endif
Copter::FlightMode_RTL flightmode_rtl{*this};

2
ArduCopter/FlightMode.h

@ -767,7 +767,6 @@ private: @@ -767,7 +767,6 @@ private:
};
#if POSHOLD_ENABLED == ENABLED
class FlightMode_PosHold : public FlightMode {
public:
@ -800,7 +799,6 @@ private: @@ -800,7 +799,6 @@ private:
void poshold_pitch_controller_to_pilot_override();
};
#endif
class FlightMode_RTL : public FlightMode {

2
ArduCopter/Parameters.cpp

@ -457,7 +457,6 @@ const AP_Param::Info Copter::var_info[] = { @@ -457,7 +457,6 @@ const AP_Param::Info Copter::var_info[] = {
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM),
#if POSHOLD_ENABLED == ENABLED
// @Param: PHLD_BRAKE_RATE
// @DisplayName: PosHold braking rate
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
@ -473,7 +472,6 @@ const AP_Param::Info Copter::var_info[] = { @@ -473,7 +472,6 @@ const AP_Param::Info Copter::var_info[] = {
// @Range: 2000 4500
// @User: Advanced
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
#endif
// @Param: LAND_REPOSITION
// @DisplayName: Land repositioning

3
ArduCopter/config.h

@ -499,9 +499,6 @@ @@ -499,9 +499,6 @@
//////////////////////////////////////////////////////////////////////////////
// PosHold parameter defaults
//
#ifndef POSHOLD_ENABLED
# define POSHOLD_ENABLED ENABLED // PosHold flight mode enabled by default
#endif
#ifndef POSHOLD_BRAKE_RATE_DEFAULT
# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec
#endif

4
ArduCopter/control_poshold.cpp

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
#include "Copter.h"
#if POSHOLD_ENABLED == ENABLED
/*
* Init and run calls for PosHold flight mode
* PosHold tries to improve upon regular loiter by mixing the pilot input with the loiter controller
@ -672,5 +670,3 @@ void Copter::FlightMode_PosHold::poshold_pitch_controller_to_pilot_override() @@ -672,5 +670,3 @@ void Copter::FlightMode_PosHold::poshold_pitch_controller_to_pilot_override()
// store final loiter outputs for mixing with pilot input
poshold.controller_final_pitch = poshold.pitch;
}
#endif // POSHOLD_ENABLED == ENABLED

2
ArduCopter/flight_mode.cpp

@ -65,11 +65,9 @@ Copter::FlightMode *Copter::flightmode_for_mode(const uint8_t mode) @@ -65,11 +65,9 @@ Copter::FlightMode *Copter::flightmode_for_mode(const uint8_t mode)
break;
#endif
#if POSHOLD_ENABLED == ENABLED
case POSHOLD:
ret = &flightmode_poshold;
break;
#endif
case BRAKE:
ret = &flightmode_brake;

Loading…
Cancel
Save