mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed a build warning
This commit is contained in:
parent
23803df038
commit
e002fbdb8d
|
@ -664,14 +664,14 @@ void UARTDriver::_timer_tick(void)
|
||||||
/*
|
/*
|
||||||
change flow control mode for port
|
change flow control mode for port
|
||||||
*/
|
*/
|
||||||
void UARTDriver::set_flow_control(enum flow_control flow_control)
|
void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
||||||
{
|
{
|
||||||
if (sdef.rts_line == 0 || sdef.is_usb) {
|
if (sdef.rts_line == 0 || sdef.is_usb) {
|
||||||
// no hw flow control available
|
// no hw flow control available
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
_flow_control = flow_control;
|
_flow_control = flowcontrol;
|
||||||
if (!_initialised) {
|
if (!_initialised) {
|
||||||
// not ready yet, we just set variable for when we call begin
|
// not ready yet, we just set variable for when we call begin
|
||||||
return;
|
return;
|
||||||
|
|
Loading…
Reference in New Issue