mirror of https://github.com/ArduPilot/ardupilot
Copter: enable precision landing by default
This commit is contained in:
parent
8b5fa9d23d
commit
e428abde42
|
@ -35,10 +35,10 @@
|
||||||
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
||||||
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
|
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
|
||||||
//#define ADSB_ENABLED DISABLED // disable ADSB support
|
//#define ADSB_ENABLED DISABLED // disable ADSB support
|
||||||
|
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
|
||||||
|
|
||||||
// features below are disabled by default on all boards
|
// features below are disabled by default on all boards
|
||||||
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
||||||
//#define PRECISION_LANDING ENABLED // enable precision landing using companion computer or IRLock sensor
|
|
||||||
//#define GNDEFFECT_COMPENSATION ENABLED // enable ground effect compensation for barometer (if propwash interferes with the barometer on the ground)
|
//#define GNDEFFECT_COMPENSATION ENABLED // enable ground effect compensation for barometer (if propwash interferes with the barometer on the ground)
|
||||||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
||||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||||
|
|
|
@ -307,7 +307,7 @@
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Precision Landing with companion computer or IRLock sensor
|
// Precision Landing with companion computer or IRLock sensor
|
||||||
#ifndef PRECISION_LANDING
|
#ifndef PRECISION_LANDING
|
||||||
# define PRECISION_LANDING DISABLED
|
# define PRECISION_LANDING ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
Loading…
Reference in New Issue