From 87fd0480bb9e1b2858106eb4cf72ecf56532dc63 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Sun, 6 Feb 2022 22:43:38 -0500 Subject: [PATCH] AP_Motors: Tradheli-update coll_land_min default --- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 4467229977..ce91b5e4c8 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -24,7 +24,7 @@ #define AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX 0.8f // maximum possible hover throttle #define AP_MOTORS_HELI_COLLECTIVE_MIN_DEG -90.0f // minimum collective blade pitch angle in deg #define AP_MOTORS_HELI_COLLECTIVE_MAX_DEG 90.0f // maximum collective blade pitch angle in deg -#define AP_MOTORS_HELI_COLLECTIVE_LAND_MIN -1.0f // minimum landed collective blade pitch angle in deg for modes using althold +#define AP_MOTORS_HELI_COLLECTIVE_LAND_MIN -2.0f // minimum landed collective blade pitch angle in deg for modes using althold // flybar types