mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Copter: add and use FLIP_COMPLETE mode reason
No need to use the original reason we entered flip mode as the reason we are exiting flip. Instead we can use a new reason called FLIP_COMPLETE
This commit is contained in:
parent
ae3cb0557d
commit
390d06a400
@ -34,7 +34,6 @@
|
|||||||
|
|
||||||
FlipState flip_state; // current state of flip
|
FlipState flip_state; // current state of flip
|
||||||
control_mode_t flip_orig_control_mode; // flight mode when flip was initated
|
control_mode_t flip_orig_control_mode; // flight mode when flip was initated
|
||||||
mode_reason_t flip_orig_control_mode_reason;
|
|
||||||
uint32_t flip_start_time; // time since flip began
|
uint32_t flip_start_time; // time since flip began
|
||||||
int8_t flip_roll_dir; // roll direction (-1 = roll left, 1 = roll right)
|
int8_t flip_roll_dir; // roll direction (-1 = roll left, 1 = roll right)
|
||||||
int8_t flip_pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
|
int8_t flip_pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
|
||||||
@ -64,7 +63,6 @@ bool Copter::flip_init(bool ignore_checks)
|
|||||||
|
|
||||||
// capture original flight mode so that we can return to it after completion
|
// capture original flight mode so that we can return to it after completion
|
||||||
flip_orig_control_mode = control_mode;
|
flip_orig_control_mode = control_mode;
|
||||||
flip_orig_control_mode_reason = control_mode_reason;
|
|
||||||
|
|
||||||
// initialise state
|
// initialise state
|
||||||
flip_state = Flip_Start;
|
flip_state = Flip_Start;
|
||||||
@ -195,7 +193,7 @@ void Copter::flip_run()
|
|||||||
// check for successful recovery
|
// check for successful recovery
|
||||||
if (fabsf(recovery_angle) <= FLIP_RECOVERY_ANGLE) {
|
if (fabsf(recovery_angle) <= FLIP_RECOVERY_ANGLE) {
|
||||||
// restore original flight mode
|
// restore original flight mode
|
||||||
if (!set_mode(flip_orig_control_mode, flip_orig_control_mode_reason)) {
|
if (!set_mode(flip_orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
||||||
// this should never happen but just in case
|
// this should never happen but just in case
|
||||||
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
||||||
}
|
}
|
||||||
@ -206,7 +204,7 @@ void Copter::flip_run()
|
|||||||
|
|
||||||
case Flip_Abandon:
|
case Flip_Abandon:
|
||||||
// restore original flight mode
|
// restore original flight mode
|
||||||
if (!set_mode(flip_orig_control_mode, flip_orig_control_mode_reason)) {
|
if (!set_mode(flip_orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
||||||
// this should never happen but just in case
|
// this should never happen but just in case
|
||||||
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
||||||
}
|
}
|
||||||
|
@ -119,7 +119,8 @@ enum mode_reason_t {
|
|||||||
MODE_REASON_THROTTLE_LAND_ESCAPE,
|
MODE_REASON_THROTTLE_LAND_ESCAPE,
|
||||||
MODE_REASON_FENCE_BREACH,
|
MODE_REASON_FENCE_BREACH,
|
||||||
MODE_REASON_TERRAIN_FAILSAFE,
|
MODE_REASON_TERRAIN_FAILSAFE,
|
||||||
MODE_REASON_BRAKE_TIMEOUT
|
MODE_REASON_BRAKE_TIMEOUT,
|
||||||
|
MODE_REASON_FLIP_COMPLETE
|
||||||
};
|
};
|
||||||
|
|
||||||
// Tuning enumeration
|
// Tuning enumeration
|
||||||
|
Loading…
Reference in New Issue
Block a user