Copter: removed calls to set motor's max throttle

This commit is contained in:
Randy Mackay 2013-09-12 22:28:38 +09:00
parent 62cb5c172b
commit 36bbed8fdd
2 changed files with 0 additions and 2 deletions

View File

@ -57,7 +57,6 @@ static void init_rc_out()
motors.set_frame_orientation(g.frame_orientation);
motors.Init(); // motor initialisation
motors.set_min_throttle(g.throttle_min);
motors.set_max_throttle(g.throttle_max);
for(uint8_t i = 0; i < 5; i++) {
delay(20);

View File

@ -347,7 +347,6 @@ test_motors(uint8_t argc, const Menu::arg *argv)
motors.set_frame_orientation(g.frame_orientation);
motors.set_min_throttle(g.throttle_min);
motors.set_mid_throttle(g.throttle_mid);
motors.set_max_throttle(g.throttle_max);
// enable motors
init_rc_out();