mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: fix tuning knob rate control of winch
This commit is contained in:
parent
787954fa37
commit
47bbf49aa6
@ -215,11 +215,11 @@ void Copter::tuning() {
|
|||||||
|
|
||||||
case TUNING_WINCH: {
|
case TUNING_WINCH: {
|
||||||
float desired_rate = 0.0f;
|
float desired_rate = 0.0f;
|
||||||
if (v > 0.8f) {
|
if (v > 0.6f) {
|
||||||
desired_rate = g2.winch.get_rate_max();
|
desired_rate = g2.winch.get_rate_max() * (v - 0.6f) / 0.4f;
|
||||||
}
|
}
|
||||||
if (v < 0.2f) {
|
if (v < 0.4f) {
|
||||||
desired_rate = -g2.winch.get_rate_max();
|
desired_rate = g2.winch.get_rate_max() * (v - 0.4) / 0.4f;
|
||||||
}
|
}
|
||||||
g2.winch.set_desired_rate(desired_rate);
|
g2.winch.set_desired_rate(desired_rate);
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user