From 842eed54265c32e7a72124161c56d808f1908c63 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 26 Oct 2017 21:07:24 +0900 Subject: [PATCH] Copter: accept do-winch commands with max rate --- ArduCopter/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2d387f5dc9..84d8fa38e0 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1217,7 +1217,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) break; } case WINCH_RATE_CONTROL: { - if (fabsf(packet.param4) < copter.g2.winch.get_rate_max()) { + if (fabsf(packet.param4) <= copter.g2.winch.get_rate_max()) { copter.g2.winch.set_desired_rate(packet.param4); copter.Log_Write_Event(DATA_WINCH_RATE_CONTROL); } else {