mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Rover: radio.cpp correct whitespace, remove tabs
This commit is contained in:
parent
fb8446ffd5
commit
25fbfeb5cf
@ -20,7 +20,6 @@ void Rover::set_control_channels(void)
|
||||
hal.rcout->set_safety_pwm(1UL<<(rcmap.roll()-1), channel_steer->get_radio_trim());
|
||||
}
|
||||
}
|
||||
|
||||
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
||||
// take a proportion of speed.
|
||||
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
@ -90,7 +89,6 @@ void Rover::rudder_arm_disarm_check()
|
||||
|
||||
if (rudder_arm_timer == 0 ||
|
||||
now - rudder_arm_timer < 3000) {
|
||||
|
||||
if (rudder_arm_timer == 0) {
|
||||
rudder_arm_timer = now;
|
||||
}
|
||||
@ -184,7 +182,6 @@ void Rover::read_radio()
|
||||
}
|
||||
|
||||
rudder_arm_disarm_check();
|
||||
|
||||
}
|
||||
|
||||
void Rover::control_failsafe(uint16_t pwm)
|
||||
|
Loading…
Reference in New Issue
Block a user