mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM: Toy mode updates
This commit is contained in:
parent
b27c1ce396
commit
1e0ab8768e
@ -420,7 +420,7 @@ static void set_mode(byte mode)
|
|||||||
if(home_is_set == false){
|
if(home_is_set == false){
|
||||||
// THOR
|
// THOR
|
||||||
// We don't care about Home if we don't have lock yet in Toy mode
|
// We don't care about Home if we don't have lock yet in Toy mode
|
||||||
if(mode == TOY || mode == OF_LOITER){
|
if(mode == TOY_A || mode == TOY_M || mode == OF_LOITER){
|
||||||
// nothing
|
// nothing
|
||||||
}else if (mode > ALT_HOLD){
|
}else if (mode > ALT_HOLD){
|
||||||
mode = STABILIZE;
|
mode = STABILIZE;
|
||||||
@ -551,18 +551,26 @@ static void set_mode(byte mode)
|
|||||||
// THOR
|
// THOR
|
||||||
// These are the flight modes for Toy mode
|
// These are the flight modes for Toy mode
|
||||||
// See the defines for the enumerated values
|
// See the defines for the enumerated values
|
||||||
case TOY:
|
case TOY_A:
|
||||||
yaw_mode = YAW_TOY;
|
yaw_mode = YAW_TOY;
|
||||||
roll_pitch_mode = ROLL_PITCH_TOY;
|
roll_pitch_mode = ROLL_PITCH_TOY;
|
||||||
|
throttle_mode = THROTTLE_AUTO;
|
||||||
wp_control = NO_NAV_MODE;
|
wp_control = NO_NAV_MODE;
|
||||||
|
|
||||||
// init throttle
|
// save throttle for fast exit of Alt hold
|
||||||
update_toy_throttle();
|
saved_toy_throttle = g.rc_3.control_in;
|
||||||
|
|
||||||
// hold the current altitude
|
// hold the current altitude
|
||||||
set_new_altitude(current_loc.alt);
|
set_new_altitude(current_loc.alt);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case TOY_M:
|
||||||
|
yaw_mode = YAW_TOY;
|
||||||
|
roll_pitch_mode = ROLL_PITCH_TOY;
|
||||||
|
wp_control = NO_NAV_MODE;
|
||||||
|
throttle_mode = THROTTLE_MANUAL;
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user