Rover: radio.cpp correct whitespace, remove tabs

This commit is contained in:
Pierre Kancir 2016-12-20 14:33:36 +01:00 committed by Randy Mackay
parent fb8446ffd5
commit 25fbfeb5cf

View File

@ -20,7 +20,6 @@ void Rover::set_control_channels(void)
hal.rcout->set_safety_pwm(1UL<<(rcmap.roll()-1), channel_steer->get_radio_trim()); hal.rcout->set_safety_pwm(1UL<<(rcmap.roll()-1), channel_steer->get_radio_trim());
} }
} }
// setup correct scaling for ESCs like the UAVCAN PX4ESC which // setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed. // take a proportion of speed.
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); 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 || if (rudder_arm_timer == 0 ||
now - rudder_arm_timer < 3000) { now - rudder_arm_timer < 3000) {
if (rudder_arm_timer == 0) { if (rudder_arm_timer == 0) {
rudder_arm_timer = now; rudder_arm_timer = now;
} }
@ -184,7 +182,6 @@ void Rover::read_radio()
} }
rudder_arm_disarm_check(); rudder_arm_disarm_check();
} }
void Rover::control_failsafe(uint16_t pwm) void Rover::control_failsafe(uint16_t pwm)