From 2bb8294685c1771b4fb05808d8ae2c6382893108 Mon Sep 17 00:00:00 2001 From: Tarik Agcayazi <48362458+ohitstarik@users.noreply.github.com> Date: Thu, 2 Mar 2023 10:34:29 -0500 Subject: [PATCH] AP_Winch: Fix baud rate handling Correct baud rate is 38400. Confirmed with manufacturer, and with a winch on v1.02. Also confirmed w/ manufacturer that newest winches on v1.04 also use 38400. Removed if statement forcing baud rate of 115200 to be consistent with documentation, and to avoid issues in future if manufacturer changes baud rate again. --- libraries/AP_Winch/AP_Winch_Daiwa.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index df1ce04484..67c274506d 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -23,10 +23,6 @@ void AP_Winch_Daiwa::init() // initialise serial connection to winch const AP_SerialManager &serial_manager = AP::serialmanager(); uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Winch, 0); - if (uart != nullptr) { - // always use baudrate of 115200 - uart->begin(115200); - } } void AP_Winch_Daiwa::update()