diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index b7f78ec98b..cad0e36f55 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1518,6 +1518,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) { + // Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short + // For that matter, send an invalid signal to all channels to prevent undesired/unexpected behavior + hal.rcout->cork(); + for(int i=0; iwrite(i, 0); + } + hal.rcout->push(); + AP_Notify::flags.firmware_update = 1; sub.update_notify(); hal.scheduler->delay(200);