mirror of https://github.com/ArduPilot/ardupilot
Copter: disarm on landing regardless of pilot input
This commit is contained in:
parent
4a1ba9b186
commit
f2b0fc3566
|
@ -40,7 +40,7 @@
|
||||||
|
|
||||||
// other settings
|
// other settings
|
||||||
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
|
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
|
||||||
//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // when set to DISABLED vehicle will disarm after landing (in LAND mode or RTL) even if pilot has not put throttle to zero
|
//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED // when set to ENABLED vehicle will only disarm after landing (in AUTO, LAND or RTL) if pilot has put throttle to zero
|
||||||
|
|
||||||
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
|
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
|
||||||
|
|
||||||
|
|
|
@ -505,8 +505,8 @@
|
||||||
#ifndef LAND_DETECTOR_ROTATION_MAX
|
#ifndef LAND_DETECTOR_ROTATION_MAX
|
||||||
# define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed
|
# define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed
|
||||||
#endif
|
#endif
|
||||||
#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM // require pilot to reduce throttle to minimum before vehicle will disarm
|
#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM
|
||||||
# define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED
|
# define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // we do not require pilot to reduce throttle to minimum before vehicle will disarm in AUTO, LAND or RTL
|
||||||
#endif
|
#endif
|
||||||
#ifndef LAND_REPOSITION_DEFAULT
|
#ifndef LAND_REPOSITION_DEFAULT
|
||||||
# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing
|
# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing
|
||||||
|
|
Loading…
Reference in New Issue