mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: use set_and_defualt
This commit is contained in:
parent
ad8b9f58df
commit
ca9aa41dd1
|
@ -468,13 +468,13 @@ void AP_SerialManager::init()
|
|||
break;
|
||||
case SerialProtocol_FrSky_D:
|
||||
// Note baudrate is hardcoded to 9600
|
||||
state[i].baud = AP_SERIALMANAGER_FRSKY_D_BAUD/1000; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_FRSKY_D_BAUD/1000); // update baud param in case user looks at it
|
||||
// begin is handled by AP_Frsky_telem library
|
||||
break;
|
||||
case SerialProtocol_FrSky_SPort:
|
||||
case SerialProtocol_FrSky_SPort_Passthrough:
|
||||
// Note baudrate is hardcoded to 57600
|
||||
state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000); // update baud param in case user looks at it
|
||||
// begin is handled by AP_Frsky_telem library
|
||||
break;
|
||||
case SerialProtocol_GPS:
|
||||
|
@ -485,14 +485,14 @@ void AP_SerialManager::init()
|
|||
break;
|
||||
case SerialProtocol_AlexMos:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_ALEXMOS_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_SToRM32:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_SToRM32_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(state[i].baudrate(),
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_TX);
|
||||
|
@ -502,7 +502,7 @@ void AP_SerialManager::init()
|
|||
break;
|
||||
case SerialProtocol_Volz:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud = AP_SERIALMANAGER_VOLZ_BAUD; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_VOLZ_BAUD); // update baud param in case user looks at it
|
||||
uart->begin(state[i].baudrate(),
|
||||
AP_SERIALMANAGER_VOLZ_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_VOLZ_BUFSIZE_TX);
|
||||
|
@ -510,7 +510,7 @@ void AP_SerialManager::init()
|
|||
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
break;
|
||||
case SerialProtocol_Sbus1:
|
||||
state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_SBUS1_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(state[i].baudrate(),
|
||||
AP_SERIALMANAGER_SBUS1_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_SBUS1_BUFSIZE_TX);
|
||||
|
@ -522,7 +522,7 @@ void AP_SerialManager::init()
|
|||
|
||||
case SerialProtocol_ESCTelemetry:
|
||||
// ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
|
||||
state[i].baud = 115200 / 1000;
|
||||
state[i].baud.set_and_default(115200 / 1000);
|
||||
uart->begin(state[i].baudrate(), 30, 30);
|
||||
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue