Skip to content
Snippets Groups Projects
Commit 435e2c28 authored by rmackay9's avatar rmackay9
Browse files

AP_Motors: enable throttle curve by default

parent 08f203a9
No related branches found
No related tags found
No related merge requests found
......@@ -46,7 +46,7 @@
// top-bottom ratio (for Y6)
#define AP_MOTORS_TOP_BOTTOM_RATIO 1.0
#define THROTTLE_CURVE_ENABLED 0 // throttle curve disabled by default
#define THROTTLE_CURVE_ENABLED 1 // throttle curve disabled by default
#define THROTTLE_CURVE_MID_THRUST 52 // throttle which produces 1/2 the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
#define THROTTLE_CURVE_MAX_THRUST 93 // throttle which produces the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment