diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 787b034e01..9fd7429027 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1063,7 +1063,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // param2 : new speed in m/s // param3 : unused // param4 : unused - if (packet.param2 > 0.0f) { + if (packet.param2 >= 0.0f) { wp_nav.set_speed_xy(packet.param2 * 100.0f); result = MAV_RESULT_ACCEPTED; } else {