HAL_AVR: added Scheduler.set_timer_speed() support

This commit is contained in:
Andrew Tridgell 2013-10-12 18:23:27 +11:00 committed by Randy Mackay
parent 7ef187fcfd
commit a5788dde8f
2 changed files with 22 additions and 8 deletions

View File

@ -14,13 +14,9 @@ using namespace AP_HAL_AVR;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
/* AVRScheduler timer interrupt period is controlled by TCNT2. /* AVRScheduler timer interrupt period is controlled by TCNT2.
* 256-124 gives a 500Hz period for APM2 * 256-124 gives a 500Hz period
* 256-62 gives a 1kHz period for APM1. */ * 256-62 gives a 1kHz period. */
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 volatile uint8_t AVRScheduler::_timer2_reset_value = (256 - 62);
# define RESET_TCNT2_VALUE (256 - 62)
#else
# define RESET_TCNT2_VALUE (256 - 124)
#endif
/* Static AVRScheduler variables: */ /* Static AVRScheduler variables: */
AVRTimer AVRScheduler::_timer; AVRTimer AVRScheduler::_timer;
@ -151,7 +147,7 @@ void AVRScheduler::_timer_isr_event() {
// This approach also gives us a nice uniform spacing between // This approach also gives us a nice uniform spacing between
// timer calls // timer calls
TCNT2 = RESET_TCNT2_VALUE; TCNT2 = _timer2_reset_value;
sei(); sei();
_run_timer_procs(true); _run_timer_procs(true);
} }
@ -242,4 +238,19 @@ void AVRScheduler::reboot(bool hold_in_bootloader) {
} }
/**
set timer speed in Hz. Used by ArduCopter on APM2 to reduce the
cost of timer interrupts
*/
void AVRScheduler::set_timer_speed(uint16_t timer_hz)
{
if (timer_hz > 1000) {
timer_hz = 1000;
}
if (timer_hz < 250) {
timer_hz = 250;
}
_timer2_reset_value = 256 - (62 * (1000 / timer_hz));
}
#endif #endif

View File

@ -46,6 +46,8 @@ public:
void panic(const prog_char_t *errormsg); void panic(const prog_char_t *errormsg);
void reboot(bool hold_in_bootloader); void reboot(bool hold_in_bootloader);
void set_timer_speed(uint16_t timer_hz);
private: private:
static AVRTimer _timer; static AVRTimer _timer;
@ -66,6 +68,7 @@ private:
static volatile bool _timer_event_missed; static volatile bool _timer_event_missed;
static AP_HAL::MemberProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS]; static AP_HAL::MemberProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS];
static uint8_t _num_timer_procs; static uint8_t _num_timer_procs;
static volatile uint8_t _timer2_reset_value;
}; };
#endif // __AP_HAL_AVR_SCHEDULER_H__ #endif // __AP_HAL_AVR_SCHEDULER_H__