mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: Tradheli-update coll_land_min default
This commit is contained in:
parent
0a98561a9d
commit
87fd0480bb
@ -24,7 +24,7 @@
|
|||||||
#define AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX 0.8f // maximum possible hover throttle
|
#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_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_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
|
// flybar types
|
||||||
|
Loading…
Reference in New Issue
Block a user