Browse Source

Rover: radio.cpp correct whitespace, remove tabs

mission-4.1.18
Pierre Kancir 8 years ago committed by Randy Mackay
parent
commit
25fbfeb5cf
  1. 9
      APMrover2/radio.cpp

9
APMrover2/radio.cpp

@ -20,7 +20,6 @@ void Rover::set_control_channels(void) @@ -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());
@ -32,7 +31,7 @@ void Rover::init_rc_in() @@ -32,7 +31,7 @@ void Rover::init_rc_in()
channel_steer->set_default_dead_zone(30);
channel_throttle->set_default_dead_zone(30);
//set auxiliary ranges
// set auxiliary ranges
update_aux();
}
@ -90,12 +89,11 @@ void Rover::rudder_arm_disarm_check() @@ -90,12 +89,11 @@ 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;
}
} else {
//time to arm!
// time to arm!
arm_motors(AP_Arming::RUDDER);
rudder_arm_timer = 0;
}
@ -116,7 +114,7 @@ void Rover::rudder_arm_disarm_check() @@ -116,7 +114,7 @@ void Rover::rudder_arm_disarm_check()
rudder_arm_timer = now;
}
} else {
//time to disarm!
// time to disarm!
disarm_motors();
rudder_arm_timer = 0;
}
@ -184,7 +182,6 @@ void Rover::read_radio() @@ -184,7 +182,6 @@ void Rover::read_radio()
}
rudder_arm_disarm_check();
}
void Rover::control_failsafe(uint16_t pwm)

Loading…
Cancel
Save