mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ArduCopter: change TOY_M throttle mode to THROTTLE_HOLD
This commit is contained in:
parent
e780bfd4c1
commit
2e6625b82c
@ -549,7 +549,7 @@ static void set_mode(byte mode)
|
|||||||
yaw_mode = YAW_TOY;
|
yaw_mode = YAW_TOY;
|
||||||
roll_pitch_mode = ROLL_PITCH_TOY;
|
roll_pitch_mode = ROLL_PITCH_TOY;
|
||||||
wp_control = NO_NAV_MODE;
|
wp_control = NO_NAV_MODE;
|
||||||
throttle_mode = THROTTLE_MANUAL;
|
throttle_mode = THROTTLE_HOLD;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user