mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APMrover2: fix indentation leading to compiler warning
GCC 6 has a new warning about misleading indentation: ../../APMrover2/system.cpp: In member function ‘void Rover::set_mode(mode)’: ../../APMrover2/system.cpp:272:5: warning: this ‘if’ clause does not guard... [-Wmisleading-indentation] if (control_mode == AUTO) ^~ ../../APMrover2/system.cpp:275:2: note: ...this statement, but the^Bn latter is misleadingly indented as if it is guarded by the ‘if’ control_mode = mode; ^~~~~~~~~~~~ The issue here is that we are mixing tabs and spaces. Remove tabs and re-indent the code.
This commit is contained in:
parent
7af888633d
commit
368a72044c
@ -263,14 +263,15 @@ void Rover::set_reverse(bool reverse)
|
||||
void Rover::set_mode(enum mode mode)
|
||||
{
|
||||
|
||||
if(control_mode == mode){
|
||||
if (control_mode == mode){
|
||||
// don't switch modes if we are already in the correct mode.
|
||||
return;
|
||||
}
|
||||
|
||||
// If we are changing out of AUTO mode reset the loiter timer
|
||||
if (control_mode == AUTO)
|
||||
if (control_mode == AUTO) {
|
||||
loiter_time = 0;
|
||||
}
|
||||
|
||||
control_mode = mode;
|
||||
throttle_last = 0;
|
||||
@ -282,8 +283,7 @@ void Rover::set_mode(enum mode mode)
|
||||
auto_triggered = false;
|
||||
}
|
||||
|
||||
switch(control_mode)
|
||||
{
|
||||
switch(control_mode) {
|
||||
case MANUAL:
|
||||
case HOLD:
|
||||
case LEARNING:
|
||||
|
Loading…
Reference in New Issue
Block a user