mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: removed calls to set motor's max throttle
This commit is contained in:
parent
62cb5c172b
commit
36bbed8fdd
@ -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);
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user