mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: remove land detector bar climb rate definition
This commit is contained in:
parent
9d585700f8
commit
18f8ffab6f
@ -477,9 +477,6 @@
|
|||||||
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
|
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
|
||||||
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
|
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
|
||||||
#endif
|
#endif
|
||||||
#ifndef LAND_DETECTOR_BARO_CLIMBRATE_MAX
|
|
||||||
# define LAND_DETECTOR_BARO_CLIMBRATE_MAX 150 // barometer climb rate must be between -150cm/s ~ +150cm/s
|
|
||||||
#endif
|
|
||||||
#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
|
||||||
|
Loading…
Reference in New Issue
Block a user