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.
This commit is contained in:
Tarik Agcayazi 2023-03-02 10:34:29 -05:00 committed by Randy Mackay
parent 6a20916a35
commit 2bb8294685
1 changed files with 0 additions and 4 deletions

View File

@ -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()