mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: implement reboot in scheduler
* still need to fix system io register inits to do it like bootloader would
This commit is contained in:
parent
592d32ba47
commit
6e45ce12b2
|
@ -1,14 +1,16 @@
|
|||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include "HAL_AVR.h"
|
||||
#include "Scheduler.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
static volatile uint32_t timer0_overflow_count = 0;
|
||||
static volatile uint32_t timer0_millis = 0;
|
||||
static uint8_t timer0_fract = 0;
|
||||
|
@ -335,3 +337,19 @@ void AVRScheduler::end_atomic() {
|
|||
sei();
|
||||
}
|
||||
}
|
||||
|
||||
void AVRScheduler::reboot() {
|
||||
hal.uartA->println_P(PSTR("GOING DOWN FOR A REBOOT\r\n"));
|
||||
hal.scheduler->delay(100);
|
||||
|
||||
cli();
|
||||
/* Making a null pointer call will cause all AVRs to reboot
|
||||
* but they may not come back alive properly - we need to setup
|
||||
* the IO the way the bootloader would.
|
||||
* pch will go back and fix this.
|
||||
*/
|
||||
void (*fn)(void) = NULL;
|
||||
fn();
|
||||
|
||||
for(;;);
|
||||
}
|
||||
|
|
|
@ -27,6 +27,7 @@ public:
|
|||
void resume_timer_procs();
|
||||
void begin_atomic();
|
||||
void end_atomic();
|
||||
void reboot();
|
||||
|
||||
private:
|
||||
/* Implementation specific methods: */
|
||||
|
|
Loading…
Reference in New Issue