HAL_AVR: scheduler interrupt 500hz for APM2

This commit is contained in:
Randy Mackay 2013-10-11 16:35:08 +09:00
parent e9cefbafd1
commit f2f61af125
1 changed files with 7 additions and 2 deletions

View File

@ -14,8 +14,13 @@ using namespace AP_HAL_AVR;
extern const AP_HAL::HAL& hal;
/* AVRScheduler timer interrupt period is controlled by TCNT2.
* 256-62 gives a 1kHz period. */
#define RESET_TCNT2_VALUE (256 - 62)
* 256-124 gives a 500Hz period for APM2
* 256-62 gives a 1kHz period for APM1. */
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
# define RESET_TCNT2_VALUE (256 - 62)
#else
# define RESET_TCNT2_VALUE (256 - 124)
#endif
/* Static AVRScheduler variables: */
AVRTimer AVRScheduler::_timer;