Rover: Steering.cpp correct whitespace, remove tabs
This commit is contained in:
parent
84f70f722d
commit
f32de5e21b
@ -12,7 +12,7 @@ void Rover::throttle_slew_limit(int16_t last_throttle) {
|
|||||||
if (temp < 1) {
|
if (temp < 1) {
|
||||||
temp = 1;
|
temp = 1;
|
||||||
}
|
}
|
||||||
channel_throttle->set_radio_out (constrain_int16(channel_throttle->get_radio_out(), last_throttle - temp, last_throttle + temp));
|
channel_throttle->set_radio_out(constrain_int16(channel_throttle->get_radio_out(), last_throttle - temp, last_throttle + temp));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -314,12 +314,12 @@ void Rover::set_servos(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (!arming.is_armed()) {
|
if (!arming.is_armed()) {
|
||||||
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
// Some ESCs get noisy (beep error msgs) if PWM == 0.
|
||||||
//This little segment aims to avoid this.
|
// This little segment aims to avoid this.
|
||||||
switch (arming.arming_required()) {
|
switch (arming.arming_required()) {
|
||||||
case AP_Arming::NO:
|
case AP_Arming::NO:
|
||||||
//keep existing behavior: do nothing to radio_out
|
// keep existing behavior: do nothing to radio_out
|
||||||
//(don't disarm throttle channel even if AP_Arming class is)
|
// (don't disarm throttle channel even if AP_Arming class is)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_Arming::YES_ZERO_PWM:
|
case AP_Arming::YES_ZERO_PWM:
|
||||||
|
Loading…
Reference in New Issue
Block a user