jaspreeth / ardupilot-mega

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

default parameters for Failsafe cause endless CIRCLE #400

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
The default parameters for ArduPilotMega short and long failsafe are 

#ifndef SHORT_FAILSAFE_ACTION
# define SHORT_FAILSAFE_ACTION          0
#endif
#ifndef LONG_FAILSAFE_ACTION
# define LONG_FAILSAFE_ACTION           0
#endif

The default parameter for throttle failsafe is

#ifndef THROTTLE_FAILSAFE
# define THROTTLE_FAILSAFE              ENABLED
#endif

These defaults are also in the example Skywalker Config file, and the current 
hex file from APM

In the case of a "throttle failsafe", first the failsafe_short_on_event() is 
called

        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;

Thus, the plane goes into CIRCLE mode (LOITER would be better)

Then after a longer pause, the failsafe_long_on_event() is called

        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;

As per this code, since the mode of the plane is already CIRCLE, the mode does 
not go to RTL, because g.long_fs_action is 0 (the default).

Therefore the plane circles and continues to circle until failsafe mode is 
dis-engaged.

This is not desirable if the failsafe is real (not just a test by the user).

In addition, CIRCLE would not be a desirable mode for a short failsafe if 
LOITER is possible.

Original issue reported on code.google.com by justinbe...@gmail.com on 5 Sep 2011 at 2:09

GoogleCodeExporter commented 8 years ago
corrected

Original comment by dewei...@gmail.com on 12 Sep 2011 at 4:00