mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
ArduCopter: allow GUIDED mode roll-pitch, yaw and throttle control modes to be overridden
This commit is contained in:
parent
31fd9a22a3
commit
8d75022d58
@ -561,6 +561,19 @@
|
||||
# define AUTO_THR THROTTLE_AUTO
|
||||
#endif
|
||||
|
||||
// Guided Mode
|
||||
#ifndef GUIDED_YAW
|
||||
# define GUIDED_YAW YAW_LOOK_AT_NEXT_WP
|
||||
#endif
|
||||
|
||||
#ifndef GUIDED_RP
|
||||
# define GUIDED_RP ROLL_PITCH_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef GUIDED_THR
|
||||
# define GUIDED_THR THROTTLE_AUTO
|
||||
#endif
|
||||
|
||||
// CIRCLE Mode
|
||||
#ifndef CIRCLE_YAW
|
||||
# define CIRCLE_YAW YAW_LOOK_AT_NEXT_WP
|
||||
|
@ -506,9 +506,9 @@ static void set_mode(byte mode)
|
||||
case GUIDED:
|
||||
ap.manual_throttle = false;
|
||||
ap.manual_attitude = false;
|
||||
set_yaw_mode(YAW_LOOK_AT_NEXT_WP);
|
||||
set_roll_pitch_mode(ROLL_PITCH_AUTO);
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
set_yaw_mode(GUIDED_YAW);
|
||||
set_roll_pitch_mode(GUIDED_RP);
|
||||
set_throttle_mode(GUIDED_THR);
|
||||
next_WP = current_loc;
|
||||
set_next_WP(&guided_WP);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user