Quantcast
Channel: Emlid Community Forum - Latest topics
Viewing all articles
Browse latest Browse all 12782

Issue with Navio2 with a potential flyaway condition

$
0
0

@i-copter wrote:

I am letting the community know of a potential serious issue with the Navio2 that can result in a fly away condition. I have discussed with the developers over the course of several weeks now and have refrained from posting this specific issue until they could come up with a fix.

I have come up with a temporary fix, but this requires modification and compiling of the ArduPilot code, which I will post below.

I have uploaded the modified files here ArduPilot Modified Code

The files above are based on a 10 second (.1hz) update instead of the 1 second (1hz) update described below.


The Issue

The specific issue I have found is specific to the Navio 2 boards, with the additional MCU co-processor. The issue can arise if for any reason the ArduPilot program running on the raspberry pi experiences a crash or no longer responds. The MCU will hold the last state of the PWM outputs that were sent by ArduPilot, which can result in a fly away condition.


How to Test this Issue

Before doing this test, please remove all props from your airframe!!
This issue can be tested fairly easily. First launch the ArduPilot (ArduCopter, ArduPlane, etc) from the Raspberry pi shell (./ArduCopter -A udp:0.0.0.0:14550) without the & sign, this will run it in the shell and keep the process in the foreground.

Remove your props!!!

Next arm your airframe and go full or partial throttle. You are going to go back to the raspberry pi shell and hit Control-C. This will essentially kill the ArduPilot application running on your raspberry pi.

You will now be in the situation where there is no flight software running however the throttle is still wide open. This is the issue and will result in a fly away condition that you have no control over... wave your aircraft goodbye!!

Remove power from the raspberry pi or issue the sudo shutdown -h now command to disable the PWM outputs.


The Temporary Fix

The fix is not perfect and a proper fix will be to modify the MCU to add a fail safe if the ArduPilot program dies. There is currently a fail safe implemented in the MCU co-processor if the raspberry pi dies (powers off) or if the Kernel panics, but not if the ArduPilot program dies.

The temporary fix essentially enables the watchdog timer in the raspberry pi and the ArduPilot application "pats the dog" or resets the watchdog timer from timing out and re-booting the raspberry pi. This will reboot the raspberry pi in the event that the ArduPilot application dies. I have included a paramter that can be enabled or disabled from Mission Planner in the event you need to frequently stop or start the applicaiton for testing purposes. The default paramter is set to disable the watchdog timer (ie. disabled = 0)

First you will load the watchdog kernel module by issuing the following command:

$ sudo modprobe bcm2708_wdog

This loads the watchdog kernel module, but doesn't start the timer... I'll explain how that happens in a bit.

lsmod

This should list all the kernel modules that are loaded, you should see the following:

bcm2708_wdog 3537 0

The watchdog kernel module should now be loaded, however you will have to make this permanent if a re-boot happens. To do this you will have to modify the /etc/modules file (using nano or vim) and include the following:

bcm2708_wdog

Close and save the file.

Next you will be modifying the following three files in the ArudPilot source tree.

APM_Config.h
Parameters.h
UserCode.cpp


The watchdog timer will only start when you open the /dev/watchdog file. When it's opened for read/write, the timer is started automatically and begins its countdown. At this point, if you fail to write any character (except the special "V" character) to the device file, the timer will timeout and reboot the Rpi. Writing a value to the file will reset the counter, this is known as "patting the dog" as you are constantly resetting the timer to stop it from timing out and resetting the Rpi. Writing the special character "V" will disable the watchdog timer.


APM_Config.h

Uncomment the define USERHOOK_VARIABLES, USERHOOK_INIT, and USERHOOK_SUPERSLOWLOOP by removing the "//"

#define USERHOOK_VARIABLES "UserVariables.h"
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz

This essentially enables the user code which we will modify below. I created a loop that runs at .1 Hz or once every 10 seconds, however to simplify the fix you can use the SuperSlowLoop which runs at 1Hz or once a second to reset the watchdog timer

Parameters.cpp

Add the following code just above the AP_VAREND statement:


// @Param: WDT_ENABLED
// @DisplayName: WDT Enable
// @Description: This enables the Kernel WatchDog Timer
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(wdt_enabled, "WDT_ENABLED", 0),

AP_VAREND

This adds the parameter type, range, and description.


Parameters.h

Add the parameter k_param_wdt_enabled, into the parameter.h file, be careful where you put this as all the parameters are indexed and could result in the EEPROM image being messed up. I added it in the layout section as shown below:


enum {
// Layout version number, always key zero.
//
k_param_format_version = 0,
k_param_software_type,
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
k_param_ins, // libraries/AP_InertialSensor variables
k_param_NavEKF2,
k_param_wdt_enabled,

// simulation
k_param_sitl = 10,
...

Also in this file we will add the variable type and name AP_Int8 wdt_enabled; at the end of the variable declarations.


AP_Int8 land_repositioning;
AP_Int8 fs_ekf_action;
AP_Int8 fs_crash_check;
AP_Float fs_ekf_thresh;
AP_Int16 gcs_pid_mask;

AP_Int8 wdt_enabled;


UserCode.cpp

This is where we will add the watchdog "patting" or reset code. The code is below:

#include "Copter.h"

#include < stdio.h>
#include < fcntl.h>
#include < sys/ioctl.h>
#include < linux/watchdog.h>
#include < unistd.h>

static void _wdtOpen(int *fd); // local file open wrapper
static void _wdtClose(int *fd); // local file close wrapper

int _deviceHandle; // Device file handler
bool _watchdogPreRun = false; // First run, previously run

#ifdef USERHOOK_INIT
void Copter::userhook_init()
{
// put your initialisation code here
// this will be called once at start-up

}
#endif

#ifdef USERHOOK_FASTLOOP
void Copter::userhook_FastLoop()
{
// put your 100Hz code here
}
#endif

#ifdef USERHOOK_50HZLOOP
void Copter::userhook_50Hz()
{
// put your 50Hz code here
}
#endif

#ifdef USERHOOK_MEDIUMLOOP
void Copter::userhook_MediumLoop()
{
// put your 10Hz code here
}
#endif

#ifdef USERHOOK_SLOWLOOP
void Copter::userhook_SlowLoop()
{
// put your 3.3Hz code here

}
#endif

#ifdef USERHOOK_SUPERSLOWLOOP
void Copter::userhook_SuperSlowLoop()
{
// put your 1Hz code here

// WatchDog Timer parameter Enabled
if (g.wdt_enabled){

wdtOpen(&deviceHandle);
ioctl(deviceHandle, WDIOCKEEPALIVE, 0); // Reset the watchdog timer
wdtClose(&deviceHandle);
if (_watchdogPreRun == false)
_watchdogPreRun = true; // Watchdog timer enabled first time

}else if (_watchdogPreRun){

wdtOpen(&deviceHandle);

if (write(_deviceHandle,"V",1) < 0) // Disable Watchdog timer
hal.console->println("Faile to stop watchdog Device");

_watchdogPreRun = false;
wdtClose(&deviceHandle);
}
}

// Static file open, pass device handler as pointer
static void _wdtOpen(int *fd)
{
if ((*fd = open("/dev/watchdog",O_RDWR | O_NOCTTY)) < 0) //watchdog is automatically started when opened
{
hal.console->println("Failed to open watchdog Device");

}
}

// Static file close, pass device handler as pointer
static void _wdtClose(int *fd)
{
if (close(*fd) < 0) // Close the handle
hal.console->println("Failed to close watchdog device");
}
#endif

Please note that there are no spaces after the "<" in #include < xxxx


Compile and download to your raspberry pi... Please note that I have not fully tested this on a running machine, but I have bench tested it.

To enable the watchdog timer, list the full parameter list and look for the parameter WDT_enable. Setting this to 1 will enable the watchdog timer while a 0 will disable the functionality.

Dale

Posts: 5

Participants: 3

Read full topic


Viewing all articles
Browse latest Browse all 12782

Trending Articles