mrAyaz / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

Throttle Failsafe wrong behaviour and fix #429

Open GoogleCodeExporter opened 8 years ago

GoogleCodeExporter commented 8 years ago
APM 2.24

I used following settings (default except THROTTLE_FS_VALUE):
#define THROTTLE_FAILSAFE   ENABLED
#define THROTTLE_FS_VALUE   940

#define GCS_HEARTBEAT_FAILSAFE  DISABLED
#define SHORT_FAILSAFE_ACTION   0
#define LONG_FAILSAFE_ACTION        0

I spent a bit of time wondering why the APM did not do what the wiki said:

when on MANUAL mode, I switch off the RC (to simulate an out of range issue), 
the APM goes to CIRCLE mode after 1.5 second. That s normal as the short 
failsafe event is triggered.

But then nothing happens. The long failsafe event never switch to RTL mode 
after 20 seconds as it should.

If you take a close look to the code (in events.pde), it seems the long 
failsafe event uses the mode newly set by the short failsafe event as a 
criteria to take action. So in my case the CIRCLE mode. The resulting action, 
with my settings is: do nothing.

I did the following corrections (only the 2 lines containing 
"before_failsafe_control_mode") to my code to get the proper behaviour (at 
least what I expect to be the right behaviour!!):

static void failsafe_short_on_event()
{
    // This is how to handle a short loss of control signal failsafe.
    failsafe = FAILSAFE_SHORT;
    ch3_failsafe_timer = millis();
    SendDebug_P("Failsafe - Short event on");
    before_failsafe_control_mode = control_mode;
        switch(control_mode)
    {
        case MANUAL:
        case STABILIZE:
        case FLY_BY_WIRE_A: // middle position
        case FLY_BY_WIRE_B: // middle position
            set_mode(CIRCLE);
            break;

        case AUTO:
        case LOITER:
            if(g.short_fs_action == 1) {
                set_mode(RTL);
            }
            break;

        case CIRCLE:
        case RTL:
        default:
            break;
    }
                SendDebug_P("flight mode = ");
                SendDebugln(control_mode, DEC);
}

static void failsafe_long_on_event()
{
    // This is how to handle a long loss of control signal failsafe.
    SendDebug_P("Failsafe - Long event on");
    APM_RC.clearOverride();        //  If the GCS is locked up we allow control to revert to RC
    switch(before_failsafe_control_mode)
    {
        case MANUAL:
        case STABILIZE:
        case FLY_BY_WIRE_A: // middle position
        case FLY_BY_WIRE_B: // middle position
            set_mode(RTL);
            break;

        case AUTO:
        case LOITER:
        case CIRCLE:
            if(g.long_fs_action == 1) {
                set_mode(RTL);
            }
            break;

        case RTL:
        default:
            break;
    }
}

Original issue reported on code.google.com by eric.lar...@gmail.com on 5 Oct 2011 at 9:18

GoogleCodeExporter commented 8 years ago
This was fixed once before.

Thanks for the report.  I'll take a look.

Original comment by dewei...@gmail.com on 31 Oct 2011 at 3:57

GoogleCodeExporter commented 8 years ago
Eric - this bug was fixed previously and the current trunk still contains the 
fix.  The Circle case was moved up in the long failsafe switch block so that it 
was handled the same as Manual, Stabilize, etc.

What code are you using?

Original comment by dewei...@gmail.com on 31 Oct 2011 at 4:44

GoogleCodeExporter commented 8 years ago
Dewei,
I am using 2.24. It seems to me Circle is not handled the same as Manual or 
Stabilize... Here is the original 2.24 code:

static void failsafe_long_on_event()
{
    // This is how to handle a long loss of control signal failsafe.
    SendDebug_P("Failsafe - Long event on");
    APM_RC.clearOverride();     //  If the GCS is locked up we allow control to revert to RC
    switch(control_mode)
    {
        case MANUAL: 
        case STABILIZE:
        case FLY_BY_WIRE_A: // middle position
        case FLY_BY_WIRE_B: // middle position
            set_mode(RTL);
            break;

        case AUTO: 
        case LOITER: 
        case CIRCLE: 
            if(g.long_fs_action == 1) {
                set_mode(RTL);
            }
            break;

        case RTL: 
        default:
            break;
    }
}

also (if I understand right the reference), whatever are the values of 
SHORT_FAILSAFE_ACTION and LONG_FAILSAFE_ACTION, we should go from:
-Manual to Circle when SHORT_FAILSAFE occurs
-Circle to RTL when LONG_FAILSAFE occurs

Here is what the reference says:
"Note that for Manual, Stabilize, and Fly-By-Wire (A and B) modes the aircraft 
will always enter a circling mode for short failsafe conditions and will be 
switched to RTL for long failsafe conditions.  RTL mode is unaffected by 
failsafe conditions."

Thanks for your help.

Original comment by eric.lar...@gmail.com on 31 Oct 2011 at 8:28