Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/FreeRTOS/FreeRTOS-Kernel-Partner-Supported-Ports.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGaurav-Aggarwal-AWS <33462878+aggarg@users.noreply.github.com>2021-09-14 01:24:43 +0300
committerGitHub <noreply@github.com>2021-09-14 01:24:43 +0300
commit3f9c99a682c5c796bb7eb89fd9c4385688fce27a (patch)
treed08027e3c2f07fe81b51ce7e50798053a90f1270
parente62955bc44e5ad8c831cfdfcb67944d547df59e4 (diff)
Update portables for Microchip AVR Dx and Mega0 (#3)
- Update AVR GCC port files (now the port.c and portmacro.h files are identical for AVR_Mega0 and AVR_Dx families). - Add support for low-power tickless mode in portable files for AVR_Dx and AVR_Mega0. This change was originally contributed by alexmchp@ in the following PR: https://github.com/FreeRTOS/FreeRTOS-Kernel/pull/373
-rw-r--r--GCC/AVR_AVRDx/port.c277
-rw-r--r--GCC/AVR_AVRDx/porthardware.h110
-rw-r--r--GCC/AVR_AVRDx/portmacro.h156
-rw-r--r--GCC/AVR_Mega0/port.c273
-rw-r--r--GCC/AVR_Mega0/porthardware.h59
-rw-r--r--GCC/AVR_Mega0/portmacro.h168
6 files changed, 799 insertions, 244 deletions
diff --git a/GCC/AVR_AVRDx/port.c b/GCC/AVR_AVRDx/port.c
index f81af94..fd3e293 100644
--- a/GCC/AVR_AVRDx/port.c
+++ b/GCC/AVR_AVRDx/port.c
@@ -50,119 +50,6 @@ extern volatile RTOS_TCB_t * volatile pxCurrentTCB;
/*-----------------------------------------------------------*/
/*
- * Macro to save all the general purpose registers, the save the stack pointer
- * into the TCB.
- *
- * The first thing we do is save the flags then disable interrupts. This is to
- * guard our stack against having a context switch interrupt after we have already
- * pushed the registers onto the stack - causing the 32 registers to be on the
- * stack twice.
- *
- * r1 is set to zero as the compiler expects it to be thus, however some
- * of the math routines make use of R1.
- *
- * The interrupts will have been disabled during the call to portSAVE_CONTEXT()
- * so we need not worry about reading/writing to the stack pointer.
- */
-
-#define portSAVE_CONTEXT() \
- asm volatile ( "push r0 \n\t" \
- "in r0, __SREG__ \n\t" \
- "cli \n\t" \
- "push r0 \n\t" \
- "in r0, __RAMPZ__ \n\t" \
- "push r0 \n\t" \
- "push r1 \n\t" \
- "clr r1 \n\t" \
- "push r2 \n\t" \
- "push r3 \n\t" \
- "push r4 \n\t" \
- "push r5 \n\t" \
- "push r6 \n\t" \
- "push r7 \n\t" \
- "push r8 \n\t" \
- "push r9 \n\t" \
- "push r10 \n\t" \
- "push r11 \n\t" \
- "push r12 \n\t" \
- "push r13 \n\t" \
- "push r14 \n\t" \
- "push r15 \n\t" \
- "push r16 \n\t" \
- "push r17 \n\t" \
- "push r18 \n\t" \
- "push r19 \n\t" \
- "push r20 \n\t" \
- "push r21 \n\t" \
- "push r22 \n\t" \
- "push r23 \n\t" \
- "push r24 \n\t" \
- "push r25 \n\t" \
- "push r26 \n\t" \
- "push r27 \n\t" \
- "push r28 \n\t" \
- "push r29 \n\t" \
- "push r30 \n\t" \
- "push r31 \n\t" \
- "lds r26, pxCurrentTCB \n\t" \
- "lds r27, pxCurrentTCB + 1 \n\t" \
- "in r0, __SP_L__ \n\t" \
- "st x+, r0 \n\t" \
- "in r0, __SP_H__ \n\t" \
- "st x+, r0 \n\t" );
-
-/*
- * Opposite to portSAVE_CONTEXT(). Interrupts will have been disabled during
- * the context save so we can write to the stack pointer.
- */
-
-#define portRESTORE_CONTEXT() \
- asm volatile ( "lds r26, pxCurrentTCB \n\t" \
- "lds r27, pxCurrentTCB + 1 \n\t" \
- "ld r28, x+ \n\t" \
- "out __SP_L__, r28 \n\t" \
- "ld r29, x+ \n\t" \
- "out __SP_H__, r29 \n\t" \
- "pop r31 \n\t" \
- "pop r30 \n\t" \
- "pop r29 \n\t" \
- "pop r28 \n\t" \
- "pop r27 \n\t" \
- "pop r26 \n\t" \
- "pop r25 \n\t" \
- "pop r24 \n\t" \
- "pop r23 \n\t" \
- "pop r22 \n\t" \
- "pop r21 \n\t" \
- "pop r20 \n\t" \
- "pop r19 \n\t" \
- "pop r18 \n\t" \
- "pop r17 \n\t" \
- "pop r16 \n\t" \
- "pop r15 \n\t" \
- "pop r14 \n\t" \
- "pop r13 \n\t" \
- "pop r12 \n\t" \
- "pop r11 \n\t" \
- "pop r10 \n\t" \
- "pop r9 \n\t" \
- "pop r8 \n\t" \
- "pop r7 \n\t" \
- "pop r6 \n\t" \
- "pop r5 \n\t" \
- "pop r4 \n\t" \
- "pop r3 \n\t" \
- "pop r2 \n\t" \
- "pop r1 \n\t" \
- "pop r0 \n\t" \
- "out __RAMPZ__, r0 \n\t" \
- "pop r0 \n\t" \
- "out __SREG__, r0 \n\t" \
- "pop r0 \n\t" );
-
-/*-----------------------------------------------------------*/
-
-/*
* Perform hardware setup to enable ticks from timer.
*/
static void prvSetupTimerInterrupt( void );
@@ -206,8 +93,10 @@ StackType_t * pxPortInitialiseStack( StackType_t * pxTopOfStack,
pxTopOfStack--;
*pxTopOfStack = portFLAGS_INT_ENABLED;
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) 0x00; /* RAMPZ */
+#if defined(__AVR_HAVE_RAMPZ__)
+ *pxTopOfStack = (StackType_t)0x00; /* RAMPZ */
pxTopOfStack--;
+#endif
/* Now the remaining registers. The compiler expects R1 to be 0. */
*pxTopOfStack = ( StackType_t ) 0x00; /* R1 */
@@ -310,11 +199,15 @@ void vPortYieldFromTick( void )
*/
static void prvSetupTimerInterrupt( void )
{
+ /* Configure low-power timer used in tickless mode */
+#if (configUSE_TICKLESS_IDLE == 1)
+ RTC_INIT();
+#endif
TICK_init();
}
/*-----------------------------------------------------------*/
-#if configUSE_PREEMPTION == 1
+#if (configUSE_PREEMPTION == 1)
/*
* Tick ISR for preemptive scheduler. We can use a naked attribute as
@@ -344,3 +237,157 @@ static void prvSetupTimerInterrupt( void )
xTaskIncrementTick();
}
#endif /* if configUSE_PREEMPTION == 1 */
+
+#if (configUSE_TICKLESS_IDLE == 1)
+
+volatile uint32_t RTC_OVF_Count = 0;
+
+ISR(RTC_CNT_vect)
+{
+ if (RTC.INTFLAGS & RTC_OVF_bm )
+ {
+ RTC_OVF_Count += 0x00010000;
+ RTC.INTFLAGS = (RTC_OVF_bm);
+ }
+
+ if (RTC.INTFLAGS & RTC_CMP_bm )
+ {
+ RTC.INTFLAGS = (RTC_CMP_bm);
+ //Disable compare interrupt
+ RTC.INTCTRL &= (0xFF ^ RTC_CMP_bm);
+ }
+
+}
+
+static uint32_t ulGetExternalTime(void)
+{
+ uint32_t time_rtc;
+
+ while (RTC.STATUS & RTC_CNTBUSY_bm)
+ {
+ ;
+ }
+ time_rtc = RTC.CNT;
+ time_rtc += RTC_OVF_Count;
+ return time_rtc;
+}
+
+static void vSetWakeTimeInterrupt(uint16_t xExpectedIdleTime)
+{
+ uint32_t rtc_cnt_time;
+
+ /* compute the required */
+ rtc_cnt_time = RTC_TICKS_TO_COUNTS(xExpectedIdleTime);
+ rtc_cnt_time += ulGetExternalTime();
+
+ while (RTC.STATUS & RTC_CMPBUSY_bm)
+ {
+ ;
+ }
+ RTC.CMP = (rtc_cnt_time & 0xFFFF);
+
+ //Enable compare interrupt
+ RTC.INTCTRL |= RTC_CMP_bm;
+}
+
+/* Define the function that is called by portSUPPRESS_TICKS_AND_SLEEP(). */
+__attribute__((weak)) void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime)
+{
+ eSleepModeStatus eSleepStatus;
+ uint32_t ulLowPowerTimeBeforeSleep, ulLowPowerTimeAfterSleep;
+
+ /* Read the current time from a time source that will remain operational
+ while the microcontroller is in a low power state. */
+ ulLowPowerTimeBeforeSleep = ulGetExternalTime();
+
+ /* Stop the timer that is generating the tick interrupt. */
+ TICK_TMR_STOP();
+
+ /* Enter a critical section that will not effect interrupts bringing the MCU
+ out of sleep mode. */
+ portDISABLE_INTERRUPTS();
+
+ /* Ensure it is still ok to enter the sleep mode. */
+ eSleepStatus = eTaskConfirmSleepModeStatus();
+
+ if (eSleepStatus == eAbortSleep)
+ {
+ /* A task has been moved out of the Blocked state since this macro was
+ * executed, or a context switch is being held pending. Do not enter a
+ * sleep state. Restart the tick and exit the critical section. */
+ TICK_TMR_START();
+ portENABLE_INTERRUPTS();
+ }
+ else
+ {
+ if (eSleepStatus == eNoTasksWaitingTimeout)
+ {
+ /* A user definable macro that allows application code to be inserted
+ * here. Such application code can be used to minimize power consumption
+ * further by turning off IO, peripheral clocks, the Flash, etc. */
+ configPRE_PWR_DOWN_PROCESSING();
+
+ /* There are no running state tasks and no tasks that are blocked with a
+ * time out. Assuming the application does not care if the tick time slips
+ * with respect to calendar time then enter a deep sleep that can only be
+ * woken by (in this demo case) the user button being pushed on the
+ * Curiosity Nano board. If the application does require the tick time
+ * to keep better track of the calender time then the PIT peripheral can be
+ * used to make rough adjustments. */
+ portSET_MODE_AND_SLEEP(SLEEP_MODE_PWR_DOWN);
+
+ /* A user definable macro that allows application code to be inserted
+ * here. Such application code can be used to reverse any actions taken
+ * by the configPRE_STOP_PROCESSING() */
+ configPOST_PWR_DOWN_PROCESSING();
+ }
+ else
+ {
+ /* Configure an interrupt to bring the microcontroller out of its low
+ * power state at the time the kernel next needs to execute. The
+ * interrupt must be generated from a source that remains operational
+ * when the microcontroller is in a low power state. */
+ vSetWakeTimeInterrupt(xExpectedIdleTime);
+
+ /* Allow the application to define some pre-sleep processing. This is
+ * the standard configPRE_SLEEP_PROCESSING() macro as described on the
+ * FreeRTOS.org website. */
+ configPRE_SLEEP_PROCESSING(xExpectedIdleTime);
+
+ /* Enter the low power state. */
+ portSET_MODE_AND_SLEEP(SLEEP_MODE_STANDBY);
+
+ /* Determine how long the microcontroller was actually in a low power
+ * state for, which will be less than xExpectedIdleTime if the
+ * microcontroller was brought out of low power mode by an interrupt
+ * other than that configured by the vSetWakeTimeInterrupt() call.
+ * Note that the scheduler is suspended before
+ * portSUPPRESS_TICKS_AND_SLEEP() is called, and resumed when
+ * portSUPPRESS_TICKS_AND_SLEEP() returns. Therefore no other tasks will
+ * execute until this function completes. */
+ ulLowPowerTimeAfterSleep = ulGetExternalTime();
+
+ /* Allow the application to define some post sleep processing. This is
+ * the standard configPOST_SLEEP_PROCESSING() macro, as described on the
+ * FreeRTOS.org website.
+ * It can be used to reverse the actions of configPRE_SLEEP_PROCESSING(),
+ * and in so doing, return the microcontroller back to its fully operational state */
+ configPOST_SLEEP_PROCESSING(xExpectedIdleTime);
+
+ /* Correct the kernels tick count to account for the time the
+ * microcontroller spent in its low power state. */
+ vTaskStepTick(RTC_COUNTS_TO_TICKS(ulLowPowerTimeAfterSleep - ulLowPowerTimeBeforeSleep));
+ // vTaskStepTick(xExpectedIdleTime);
+
+ }
+
+ /* Exit the critical section - it might be possible to do this immediately
+ * after the SET_MODE_AND_SLEEP calls. */
+ portENABLE_INTERRUPTS();
+
+ /* Restart the timer that is generating the tick interrupt. */
+ TICK_TMR_START();
+ }
+}
+
+#endif
diff --git a/GCC/AVR_AVRDx/porthardware.h b/GCC/AVR_AVRDx/porthardware.h
index ca0302e..52e3f12 100644
--- a/GCC/AVR_AVRDx/porthardware.h
+++ b/GCC/AVR_AVRDx/porthardware.h
@@ -55,6 +55,15 @@
TCB0.INTCTRL = TCB_CAPT_bm; \
TCB0.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB0.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB0.INTFLAGS = TCB_CAPT_bm; \
+ TCB0.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB0.CNT
+ #define TICK_INT_READY() (TCB0.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 1 )
@@ -68,6 +77,15 @@
TCB1.INTCTRL = TCB_CAPT_bm; \
TCB1.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB1.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB1.INTFLAGS = TCB_CAPT_bm; \
+ TCB1.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB1.CNT
+ #define TICK_INT_READY() (TCB1.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 2 )
@@ -81,6 +99,15 @@
TCB2.INTCTRL = TCB_CAPT_bm; \
TCB2.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB2.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB2.INTFLAGS = TCB_CAPT_bm; \
+ TCB2.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB2.CNT
+ #define TICK_INT_READY() (TCB2.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 3 )
@@ -94,6 +121,15 @@
TCB3.INTCTRL = TCB_CAPT_bm; \
TCB3.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB3.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB3.INTFLAGS = TCB_CAPT_bm; \
+ TCB3.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB3.CNT
+ #define TICK_INT_READY() (TCB3.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 4 )
@@ -107,31 +143,79 @@
TCB4.INTCTRL = TCB_CAPT_bm; \
TCB4.CTRLA = TCB_ENABLE_bm; \
}
+ #define TICK_TMR_STOP() TCB4.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB4.INTFLAGS = TCB_CAPT_bm; \
+ TCB4.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB4.CNT
+ #define TICK_INT_READY() (TCB4.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 5 )
- #define TICK_INT_vect RTC_CNT_vect
- #define INT_FLAGS RTC_INTFLAGS
- #define INT_MASK RTC_OVF_bm
-
-/* Hertz to period for RTC setup */
- #define RTC_PERIOD_HZ( x ) ( 32768 * ( ( 1.0 / x ) ) )
- #define TICK_init() \
- { \
- while( RTC.STATUS > 0 ) {; } \
- RTC.CTRLA = RTC_PRESCALER_DIV1_gc | 1 << RTC_RTCEN_bp; \
- RTC.PER = RTC_PERIOD_HZ( configTICK_RATE_HZ ); \
- RTC.INTCTRL |= 1 << RTC_OVF_bp; \
- }
+ #if ( configUSE_TICKLESS_IDLE == 1 )
+
+ /* RTC is not supported as tick timer when tickless mode is used */
+ #error Invalid timer setting.
+
+ #else
+
+ #define TICK_INT_vect RTC_CNT_vect
+ #define INT_FLAGS RTC_INTFLAGS
+ #define INT_MASK RTC_OVF_bm
+
+ /* Hertz to period for RTC setup */
+ #define RTC_PERIOD_HZ( x ) ( 32768 * ( ( 1.0 / x ) ) )
+ #define TICK_init() \
+ { \
+ while( RTC.STATUS > 0 ) {; } \
+ RTC.CTRLA = RTC_PRESCALER_DIV1_gc | 1 << RTC_RTCEN_bp; \
+ RTC.PER = RTC_PERIOD_HZ( configTICK_RATE_HZ ); \
+ RTC.INTCTRL |= 1 << RTC_OVF_bp; \
+ }
+ #undef TICK_TMR_STOP()
+ #undef TICK_TMR_START()
+ #undef TICK_TMR_READ()
+ #undef TICK_INT_READY()
+ #endif
#else /* if ( configUSE_TIMER_INSTANCE == 0 ) */
#undef TICK_INT_vect
#undef INT_FLAGS
#undef INT_MASK
#undef TICK_init()
+ #undef TICK_TMR_STOP()
+ #undef TICK_TMR_START()
+ #undef TICK_TMR_READ()
+ #undef TICK_INT_READY()
#error Invalid timer setting.
#endif /* if ( configUSE_TIMER_INSTANCE == 0 ) */
/*-----------------------------------------------------------*/
+
+#if ( configUSE_TICKLESS_IDLE == 1 )
+
+#define LOW_POWER_CLOCK (32768UL)
+
+#define RTC_TICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ )
+#define RTC_TICKS_TO_COUNTS(tick_cnt) (uint32_t)(((float)(tick_cnt * LOW_POWER_CLOCK)/configTICK_RATE_HZ) - 0.5)
+#define RTC_COUNTS_TO_TICKS(counts) (uint32_t)((float)((counts * 1.0) * configTICK_RATE_HZ)/LOW_POWER_CLOCK )
+
+
+#define RTC_INIT() \
+{ \
+ while( RTC.STATUS > 0 ) {; } \
+ RTC.PER = 0xFFFF; \
+ RTC.CMP = 0x3FFF; \
+ RTC.CNT = 0; \
+ RTC.INTFLAGS = RTC_OVF_bm | RTC_CMP_bm; \
+ RTC.CTRLA = RTC_RUNSTDBY_bm | RTC_PRESCALER_DIV1_gc | RTC_RTCEN_bm ; \
+ RTC.INTCTRL = RTC_OVF_bm | RTC_CMP_bm; \
+}
+
+#endif
+
+
#endif /* PORTHARDWARE_H */
diff --git a/GCC/AVR_AVRDx/portmacro.h b/GCC/AVR_AVRDx/portmacro.h
index f26acca..7879b64 100644
--- a/GCC/AVR_AVRDx/portmacro.h
+++ b/GCC/AVR_AVRDx/portmacro.h
@@ -35,6 +35,7 @@
#endif
/* *INDENT-ON* */
+#include <avr/sleep.h>
/*-----------------------------------------------------------
* Port specific definitions.
*
@@ -102,6 +103,161 @@ extern void vPortYieldFromISR( void ) __attribute__( ( naked ) );
#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void * pvParameters )
#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void * pvParameters )
+/* Macros for tickless idle/low power functionality. */
+#ifndef portSUPPRESS_TICKS_AND_SLEEP
+
+extern void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime);
+#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vPortSuppressTicksAndSleep(xExpectedIdleTime)
+#endif
+
+#ifndef configPRE_PWR_DOWN_PROCESSING
+#define configPRE_PWR_DOWN_PROCESSING()
+#endif
+
+#ifndef configPOST_PWR_DOWN_PROCESSING
+#define configPOST_PWR_DOWN_PROCESSING()
+#endif
+
+/*-----------------------------------------------------------*/
+
+/* Helper macros for portSAVE_CONTEXT/ portRESTORE_CONTEXT - common support for Mega-0 and AVR-Dx families */
+
+#if defined(__AVR_HAVE_RAMPZ__)
+
+#define portSAVE_RAMPZ() \
+ asm volatile("in r0, __RAMPZ__ \n\t" \
+ "push r0 \n\t");
+
+#define portRESTORE_RAMPZ() \
+ asm volatile("pop r0 \n\t" \
+ "out __RAMPZ__, r0 \n\t");
+
+#else
+
+#define portSAVE_RAMPZ()
+#define portRESTORE_RAMPZ()
+
+#endif
+
+/* Macro to save all the general purpose registers, the save the stack pointer
+ * into the TCB.
+
+ * The first thing we do is save the flags then disable interrupts. This is to
+ * guard our stack against having a context switch interrupt after we have already
+ * pushed the registers onto the stack - causing the 32 registers to be on the
+ * stack twice.
+
+ * r1 is set to zero as the compiler expects it to be thus, however some
+ * of the math routines make use of R1.
+
+ * The interrupts will have been disabled during the call to portSAVE_CONTEXT()
+ * so we need not worry about reading/writing to the stack pointer. */
+
+#define portSAVE_CONTEXT() \
+ { \
+ asm volatile("push r0 \n\t" \
+ "in r0, __SREG__ \n\t" \
+ "cli \n\t" \
+ "push r0 \n\t"); \
+ portSAVE_RAMPZ(); \
+ asm volatile("push r1 \n\t" \
+ "clr r1 \n\t" \
+ "push r2 \n\t" \
+ "push r3 \n\t" \
+ "push r4 \n\t" \
+ "push r5 \n\t" \
+ "push r6 \n\t" \
+ "push r7 \n\t" \
+ "push r8 \n\t" \
+ "push r9 \n\t" \
+ "push r10 \n\t" \
+ "push r11 \n\t" \
+ "push r12 \n\t" \
+ "push r13 \n\t" \
+ "push r14 \n\t" \
+ "push r15 \n\t" \
+ "push r16 \n\t" \
+ "push r17 \n\t" \
+ "push r18 \n\t" \
+ "push r19 \n\t" \
+ "push r20 \n\t" \
+ "push r21 \n\t" \
+ "push r22 \n\t" \
+ "push r23 \n\t" \
+ "push r24 \n\t" \
+ "push r25 \n\t" \
+ "push r26 \n\t" \
+ "push r27 \n\t" \
+ "push r28 \n\t" \
+ "push r29 \n\t" \
+ "push r30 \n\t" \
+ "push r31 \n\t" \
+ "lds r26, pxCurrentTCB \n\t" \
+ "lds r27, pxCurrentTCB + 1 \n\t" \
+ "in r0, __SP_L__ \n\t" \
+ "st x+, r0 \n\t" \
+ "in r0, __SP_H__ \n\t" \
+ "st x+, r0 \n\t"); \
+ }
+
+/* Opposite to portSAVE_CONTEXT(). Interrupts will have been disabled during
+ * the context save so we can write to the stack pointer. */
+#define portRESTORE_CONTEXT() \
+ { \
+ asm volatile("lds r26, pxCurrentTCB \n\t" \
+ "lds r27, pxCurrentTCB + 1 \n\t" \
+ "ld r28, x+ \n\t" \
+ "out __SP_L__, r28 \n\t" \
+ "ld r29, x+ \n\t" \
+ "out __SP_H__, r29 \n\t" \
+ "pop r31 \n\t" \
+ "pop r30 \n\t" \
+ "pop r29 \n\t" \
+ "pop r28 \n\t" \
+ "pop r27 \n\t" \
+ "pop r26 \n\t" \
+ "pop r25 \n\t" \
+ "pop r24 \n\t" \
+ "pop r23 \n\t" \
+ "pop r22 \n\t" \
+ "pop r21 \n\t" \
+ "pop r20 \n\t" \
+ "pop r19 \n\t" \
+ "pop r18 \n\t" \
+ "pop r17 \n\t" \
+ "pop r16 \n\t" \
+ "pop r15 \n\t" \
+ "pop r14 \n\t" \
+ "pop r13 \n\t" \
+ "pop r12 \n\t" \
+ "pop r11 \n\t" \
+ "pop r10 \n\t" \
+ "pop r9 \n\t" \
+ "pop r8 \n\t" \
+ "pop r7 \n\t" \
+ "pop r6 \n\t" \
+ "pop r5 \n\t" \
+ "pop r4 \n\t" \
+ "pop r3 \n\t" \
+ "pop r2 \n\t" \
+ "pop r1 \n\t"); \
+ portRESTORE_RAMPZ(); \
+ asm volatile("pop r0 \n\t" \
+ "out __SREG__, r0 \n\t" \
+ "pop r0 \n\t"); \
+ }
+/*-----------------------------------------------------------*/
+
+#define portSET_MODE_AND_SLEEP(mode) \
+ { \
+ set_sleep_mode(mode); \
+ sleep_enable(); \
+ portENABLE_INTERRUPTS(); \
+ sleep_cpu(); \
+ portDISABLE_INTERRUPTS(); \
+ sleep_disable(); \
+ }
+
/* *INDENT-OFF* */
#ifdef __cplusplus
}
diff --git a/GCC/AVR_Mega0/port.c b/GCC/AVR_Mega0/port.c
index 1e25d13..fd3e293 100644
--- a/GCC/AVR_Mega0/port.c
+++ b/GCC/AVR_Mega0/port.c
@@ -50,115 +50,6 @@ extern volatile RTOS_TCB_t * volatile pxCurrentTCB;
/*-----------------------------------------------------------*/
/*
- * Macro to save all the general purpose registers, the save the stack pointer
- * into the TCB.
- *
- * The first thing we do is save the flags then disable interrupts. This is to
- * guard our stack against having a context switch interrupt after we have already
- * pushed the registers onto the stack - causing the 32 registers to be on the
- * stack twice.
- *
- * r1 is set to zero as the compiler expects it to be thus, however some
- * of the math routines make use of R1.
- *
- * The interrupts will have been disabled during the call to portSAVE_CONTEXT()
- * so we need not worry about reading/writing to the stack pointer.
- */
-
-#define portSAVE_CONTEXT() \
- asm volatile ( "push r0 \n\t" \
- "in r0, __SREG__ \n\t" \
- "cli \n\t" \
- "push r0 \n\t" \
- "push r1 \n\t" \
- "clr r1 \n\t" \
- "push r2 \n\t" \
- "push r3 \n\t" \
- "push r4 \n\t" \
- "push r5 \n\t" \
- "push r6 \n\t" \
- "push r7 \n\t" \
- "push r8 \n\t" \
- "push r9 \n\t" \
- "push r10 \n\t" \
- "push r11 \n\t" \
- "push r12 \n\t" \
- "push r13 \n\t" \
- "push r14 \n\t" \
- "push r15 \n\t" \
- "push r16 \n\t" \
- "push r17 \n\t" \
- "push r18 \n\t" \
- "push r19 \n\t" \
- "push r20 \n\t" \
- "push r21 \n\t" \
- "push r22 \n\t" \
- "push r23 \n\t" \
- "push r24 \n\t" \
- "push r25 \n\t" \
- "push r26 \n\t" \
- "push r27 \n\t" \
- "push r28 \n\t" \
- "push r29 \n\t" \
- "push r30 \n\t" \
- "push r31 \n\t" \
- "lds r26, pxCurrentTCB \n\t" \
- "lds r27, pxCurrentTCB + 1 \n\t" \
- "in r0, __SP_L__ \n\t" \
- "st x+, r0 \n\t" \
- "in r0, __SP_H__ \n\t" \
- "st x+, r0 \n\t" );
-
-/*
- * Opposite to portSAVE_CONTEXT(). Interrupts will have been disabled during
- * the context save so we can write to the stack pointer.
- */
-
-#define portRESTORE_CONTEXT() \
- asm volatile ( "lds r26, pxCurrentTCB \n\t" \
- "lds r27, pxCurrentTCB + 1 \n\t" \
- "ld r28, x+ \n\t" \
- "out __SP_L__, r28 \n\t" \
- "ld r29, x+ \n\t" \
- "out __SP_H__, r29 \n\t" \
- "pop r31 \n\t" \
- "pop r30 \n\t" \
- "pop r29 \n\t" \
- "pop r28 \n\t" \
- "pop r27 \n\t" \
- "pop r26 \n\t" \
- "pop r25 \n\t" \
- "pop r24 \n\t" \
- "pop r23 \n\t" \
- "pop r22 \n\t" \
- "pop r21 \n\t" \
- "pop r20 \n\t" \
- "pop r19 \n\t" \
- "pop r18 \n\t" \
- "pop r17 \n\t" \
- "pop r16 \n\t" \
- "pop r15 \n\t" \
- "pop r14 \n\t" \
- "pop r13 \n\t" \
- "pop r12 \n\t" \
- "pop r11 \n\t" \
- "pop r10 \n\t" \
- "pop r9 \n\t" \
- "pop r8 \n\t" \
- "pop r7 \n\t" \
- "pop r6 \n\t" \
- "pop r5 \n\t" \
- "pop r4 \n\t" \
- "pop r3 \n\t" \
- "pop r2 \n\t" \
- "pop r1 \n\t" \
- "pop r0 \n\t" \
- "out __SREG__, r0 \n\t" \
- "pop r0 \n\t" );
-
-/*-----------------------------------------------------------*/
-
-/*
* Perform hardware setup to enable ticks from timer.
*/
static void prvSetupTimerInterrupt( void );
@@ -202,6 +93,10 @@ StackType_t * pxPortInitialiseStack( StackType_t * pxTopOfStack,
pxTopOfStack--;
*pxTopOfStack = portFLAGS_INT_ENABLED;
pxTopOfStack--;
+#if defined(__AVR_HAVE_RAMPZ__)
+ *pxTopOfStack = (StackType_t)0x00; /* RAMPZ */
+ pxTopOfStack--;
+#endif
/* Now the remaining registers. The compiler expects R1 to be 0. */
*pxTopOfStack = ( StackType_t ) 0x00; /* R1 */
@@ -304,11 +199,15 @@ void vPortYieldFromTick( void )
*/
static void prvSetupTimerInterrupt( void )
{
+ /* Configure low-power timer used in tickless mode */
+#if (configUSE_TICKLESS_IDLE == 1)
+ RTC_INIT();
+#endif
TICK_init();
}
/*-----------------------------------------------------------*/
-#if configUSE_PREEMPTION == 1
+#if (configUSE_PREEMPTION == 1)
/*
* Tick ISR for preemptive scheduler. We can use a naked attribute as
@@ -338,3 +237,157 @@ static void prvSetupTimerInterrupt( void )
xTaskIncrementTick();
}
#endif /* if configUSE_PREEMPTION == 1 */
+
+#if (configUSE_TICKLESS_IDLE == 1)
+
+volatile uint32_t RTC_OVF_Count = 0;
+
+ISR(RTC_CNT_vect)
+{
+ if (RTC.INTFLAGS & RTC_OVF_bm )
+ {
+ RTC_OVF_Count += 0x00010000;
+ RTC.INTFLAGS = (RTC_OVF_bm);
+ }
+
+ if (RTC.INTFLAGS & RTC_CMP_bm )
+ {
+ RTC.INTFLAGS = (RTC_CMP_bm);
+ //Disable compare interrupt
+ RTC.INTCTRL &= (0xFF ^ RTC_CMP_bm);
+ }
+
+}
+
+static uint32_t ulGetExternalTime(void)
+{
+ uint32_t time_rtc;
+
+ while (RTC.STATUS & RTC_CNTBUSY_bm)
+ {
+ ;
+ }
+ time_rtc = RTC.CNT;
+ time_rtc += RTC_OVF_Count;
+ return time_rtc;
+}
+
+static void vSetWakeTimeInterrupt(uint16_t xExpectedIdleTime)
+{
+ uint32_t rtc_cnt_time;
+
+ /* compute the required */
+ rtc_cnt_time = RTC_TICKS_TO_COUNTS(xExpectedIdleTime);
+ rtc_cnt_time += ulGetExternalTime();
+
+ while (RTC.STATUS & RTC_CMPBUSY_bm)
+ {
+ ;
+ }
+ RTC.CMP = (rtc_cnt_time & 0xFFFF);
+
+ //Enable compare interrupt
+ RTC.INTCTRL |= RTC_CMP_bm;
+}
+
+/* Define the function that is called by portSUPPRESS_TICKS_AND_SLEEP(). */
+__attribute__((weak)) void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime)
+{
+ eSleepModeStatus eSleepStatus;
+ uint32_t ulLowPowerTimeBeforeSleep, ulLowPowerTimeAfterSleep;
+
+ /* Read the current time from a time source that will remain operational
+ while the microcontroller is in a low power state. */
+ ulLowPowerTimeBeforeSleep = ulGetExternalTime();
+
+ /* Stop the timer that is generating the tick interrupt. */
+ TICK_TMR_STOP();
+
+ /* Enter a critical section that will not effect interrupts bringing the MCU
+ out of sleep mode. */
+ portDISABLE_INTERRUPTS();
+
+ /* Ensure it is still ok to enter the sleep mode. */
+ eSleepStatus = eTaskConfirmSleepModeStatus();
+
+ if (eSleepStatus == eAbortSleep)
+ {
+ /* A task has been moved out of the Blocked state since this macro was
+ * executed, or a context switch is being held pending. Do not enter a
+ * sleep state. Restart the tick and exit the critical section. */
+ TICK_TMR_START();
+ portENABLE_INTERRUPTS();
+ }
+ else
+ {
+ if (eSleepStatus == eNoTasksWaitingTimeout)
+ {
+ /* A user definable macro that allows application code to be inserted
+ * here. Such application code can be used to minimize power consumption
+ * further by turning off IO, peripheral clocks, the Flash, etc. */
+ configPRE_PWR_DOWN_PROCESSING();
+
+ /* There are no running state tasks and no tasks that are blocked with a
+ * time out. Assuming the application does not care if the tick time slips
+ * with respect to calendar time then enter a deep sleep that can only be
+ * woken by (in this demo case) the user button being pushed on the
+ * Curiosity Nano board. If the application does require the tick time
+ * to keep better track of the calender time then the PIT peripheral can be
+ * used to make rough adjustments. */
+ portSET_MODE_AND_SLEEP(SLEEP_MODE_PWR_DOWN);
+
+ /* A user definable macro that allows application code to be inserted
+ * here. Such application code can be used to reverse any actions taken
+ * by the configPRE_STOP_PROCESSING() */
+ configPOST_PWR_DOWN_PROCESSING();
+ }
+ else
+ {
+ /* Configure an interrupt to bring the microcontroller out of its low
+ * power state at the time the kernel next needs to execute. The
+ * interrupt must be generated from a source that remains operational
+ * when the microcontroller is in a low power state. */
+ vSetWakeTimeInterrupt(xExpectedIdleTime);
+
+ /* Allow the application to define some pre-sleep processing. This is
+ * the standard configPRE_SLEEP_PROCESSING() macro as described on the
+ * FreeRTOS.org website. */
+ configPRE_SLEEP_PROCESSING(xExpectedIdleTime);
+
+ /* Enter the low power state. */
+ portSET_MODE_AND_SLEEP(SLEEP_MODE_STANDBY);
+
+ /* Determine how long the microcontroller was actually in a low power
+ * state for, which will be less than xExpectedIdleTime if the
+ * microcontroller was brought out of low power mode by an interrupt
+ * other than that configured by the vSetWakeTimeInterrupt() call.
+ * Note that the scheduler is suspended before
+ * portSUPPRESS_TICKS_AND_SLEEP() is called, and resumed when
+ * portSUPPRESS_TICKS_AND_SLEEP() returns. Therefore no other tasks will
+ * execute until this function completes. */
+ ulLowPowerTimeAfterSleep = ulGetExternalTime();
+
+ /* Allow the application to define some post sleep processing. This is
+ * the standard configPOST_SLEEP_PROCESSING() macro, as described on the
+ * FreeRTOS.org website.
+ * It can be used to reverse the actions of configPRE_SLEEP_PROCESSING(),
+ * and in so doing, return the microcontroller back to its fully operational state */
+ configPOST_SLEEP_PROCESSING(xExpectedIdleTime);
+
+ /* Correct the kernels tick count to account for the time the
+ * microcontroller spent in its low power state. */
+ vTaskStepTick(RTC_COUNTS_TO_TICKS(ulLowPowerTimeAfterSleep - ulLowPowerTimeBeforeSleep));
+ // vTaskStepTick(xExpectedIdleTime);
+
+ }
+
+ /* Exit the critical section - it might be possible to do this immediately
+ * after the SET_MODE_AND_SLEEP calls. */
+ portENABLE_INTERRUPTS();
+
+ /* Restart the timer that is generating the tick interrupt. */
+ TICK_TMR_START();
+ }
+}
+
+#endif
diff --git a/GCC/AVR_Mega0/porthardware.h b/GCC/AVR_Mega0/porthardware.h
index 758d949..05a04ae 100644
--- a/GCC/AVR_Mega0/porthardware.h
+++ b/GCC/AVR_Mega0/porthardware.h
@@ -55,6 +55,15 @@
TCB0.INTCTRL = TCB_CAPT_bm; \
TCB0.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB0.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB0.INTFLAGS = TCB_CAPT_bm; \
+ TCB0.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB0.CNT
+ #define TICK_INT_READY() (TCB0.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 1 )
@@ -68,6 +77,15 @@
TCB1.INTCTRL = TCB_CAPT_bm; \
TCB1.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB1.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB1.INTFLAGS = TCB_CAPT_bm; \
+ TCB1.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB1.CNT
+ #define TICK_INT_READY() (TCB1.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 2 )
@@ -81,6 +99,15 @@
TCB2.INTCTRL = TCB_CAPT_bm; \
TCB2.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB2.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB2.INTFLAGS = TCB_CAPT_bm; \
+ TCB2.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB2.CNT
+ #define TICK_INT_READY() (TCB2.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 3 )
@@ -94,6 +121,15 @@
TCB3.INTCTRL = TCB_CAPT_bm; \
TCB3.CTRLA = TCB_ENABLE_bm; \
}
+
+ #define TICK_TMR_STOP() TCB3.CTRLA = 0x00;
+ #define TICK_TMR_START() \
+ { \
+ TCB3.INTFLAGS = TCB_CAPT_bm; \
+ TCB3.CTRLA = TCB_ENABLE_bm; \
+ }
+ #define TICK_TMR_READ() TCB3.CNT
+ #define TICK_INT_READY() (TCB3.INTCTRL & TCB_CAPT_bm)
#elif ( configUSE_TIMER_INSTANCE == 4 )
@@ -119,6 +155,29 @@
#error Invalid timer setting.
#endif /* if ( configUSE_TIMER_INSTANCE == 0 ) */
+
+#if ( configUSE_TICKLESS_IDLE == 1 )
+
+#define LOW_POWER_CLOCK (32768UL)
+
+#define RTC_TICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ )
+#define RTC_TICKS_TO_COUNTS(tick_cnt) (uint32_t)(((float)(tick_cnt * LOW_POWER_CLOCK)/configTICK_RATE_HZ) - 0.5)
+#define RTC_COUNTS_TO_TICKS(counts) (uint32_t)((float)((counts * 1.0) * configTICK_RATE_HZ)/LOW_POWER_CLOCK )
+
+
+#define RTC_INIT() \
+{ \
+ while( RTC.STATUS > 0 ) {; } \
+ RTC.PER = 0xFFFF; \
+ RTC.CMP = 0x3FFF; \
+ RTC.CNT = 0; \
+ RTC.INTFLAGS = RTC_OVF_bm | RTC_CMP_bm; \
+ RTC.CTRLA = RTC_RUNSTDBY_bm | RTC_PRESCALER_DIV1_gc | RTC_RTCEN_bm ; \
+ RTC.INTCTRL = RTC_OVF_bm | RTC_CMP_bm; \
+}
+
+#endif
+
/*-----------------------------------------------------------*/
#endif /* PORTHARDWARE_H */
diff --git a/GCC/AVR_Mega0/portmacro.h b/GCC/AVR_Mega0/portmacro.h
index 7d66a73..7879b64 100644
--- a/GCC/AVR_Mega0/portmacro.h
+++ b/GCC/AVR_Mega0/portmacro.h
@@ -30,11 +30,12 @@
#define PORTMACRO_H
/* *INDENT-OFF* */
-#ifdef __cplusplus
- extern "C" {
-#endif
+ #ifdef __cplusplus
+ extern "C" {
+ #endif
/* *INDENT-ON* */
+#include <avr/sleep.h>
/*-----------------------------------------------------------
* Port specific definitions.
*
@@ -102,10 +103,165 @@ extern void vPortYieldFromISR( void ) __attribute__( ( naked ) );
#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void * pvParameters )
#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void * pvParameters )
-/* *INDENT-OFF* */
-#ifdef __cplusplus
- }
+/* Macros for tickless idle/low power functionality. */
+#ifndef portSUPPRESS_TICKS_AND_SLEEP
+
+extern void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime);
+#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vPortSuppressTicksAndSleep(xExpectedIdleTime)
+#endif
+
+#ifndef configPRE_PWR_DOWN_PROCESSING
+#define configPRE_PWR_DOWN_PROCESSING()
+#endif
+
+#ifndef configPOST_PWR_DOWN_PROCESSING
+#define configPOST_PWR_DOWN_PROCESSING()
+#endif
+
+/*-----------------------------------------------------------*/
+
+/* Helper macros for portSAVE_CONTEXT/ portRESTORE_CONTEXT - common support for Mega-0 and AVR-Dx families */
+
+#if defined(__AVR_HAVE_RAMPZ__)
+
+#define portSAVE_RAMPZ() \
+ asm volatile("in r0, __RAMPZ__ \n\t" \
+ "push r0 \n\t");
+
+#define portRESTORE_RAMPZ() \
+ asm volatile("pop r0 \n\t" \
+ "out __RAMPZ__, r0 \n\t");
+
+#else
+
+#define portSAVE_RAMPZ()
+#define portRESTORE_RAMPZ()
+
#endif
+
+/* Macro to save all the general purpose registers, the save the stack pointer
+ * into the TCB.
+
+ * The first thing we do is save the flags then disable interrupts. This is to
+ * guard our stack against having a context switch interrupt after we have already
+ * pushed the registers onto the stack - causing the 32 registers to be on the
+ * stack twice.
+
+ * r1 is set to zero as the compiler expects it to be thus, however some
+ * of the math routines make use of R1.
+
+ * The interrupts will have been disabled during the call to portSAVE_CONTEXT()
+ * so we need not worry about reading/writing to the stack pointer. */
+
+#define portSAVE_CONTEXT() \
+ { \
+ asm volatile("push r0 \n\t" \
+ "in r0, __SREG__ \n\t" \
+ "cli \n\t" \
+ "push r0 \n\t"); \
+ portSAVE_RAMPZ(); \
+ asm volatile("push r1 \n\t" \
+ "clr r1 \n\t" \
+ "push r2 \n\t" \
+ "push r3 \n\t" \
+ "push r4 \n\t" \
+ "push r5 \n\t" \
+ "push r6 \n\t" \
+ "push r7 \n\t" \
+ "push r8 \n\t" \
+ "push r9 \n\t" \
+ "push r10 \n\t" \
+ "push r11 \n\t" \
+ "push r12 \n\t" \
+ "push r13 \n\t" \
+ "push r14 \n\t" \
+ "push r15 \n\t" \
+ "push r16 \n\t" \
+ "push r17 \n\t" \
+ "push r18 \n\t" \
+ "push r19 \n\t" \
+ "push r20 \n\t" \
+ "push r21 \n\t" \
+ "push r22 \n\t" \
+ "push r23 \n\t" \
+ "push r24 \n\t" \
+ "push r25 \n\t" \
+ "push r26 \n\t" \
+ "push r27 \n\t" \
+ "push r28 \n\t" \
+ "push r29 \n\t" \
+ "push r30 \n\t" \
+ "push r31 \n\t" \
+ "lds r26, pxCurrentTCB \n\t" \
+ "lds r27, pxCurrentTCB + 1 \n\t" \
+ "in r0, __SP_L__ \n\t" \
+ "st x+, r0 \n\t" \
+ "in r0, __SP_H__ \n\t" \
+ "st x+, r0 \n\t"); \
+ }
+
+/* Opposite to portSAVE_CONTEXT(). Interrupts will have been disabled during
+ * the context save so we can write to the stack pointer. */
+#define portRESTORE_CONTEXT() \
+ { \
+ asm volatile("lds r26, pxCurrentTCB \n\t" \
+ "lds r27, pxCurrentTCB + 1 \n\t" \
+ "ld r28, x+ \n\t" \
+ "out __SP_L__, r28 \n\t" \
+ "ld r29, x+ \n\t" \
+ "out __SP_H__, r29 \n\t" \
+ "pop r31 \n\t" \
+ "pop r30 \n\t" \
+ "pop r29 \n\t" \
+ "pop r28 \n\t" \
+ "pop r27 \n\t" \
+ "pop r26 \n\t" \
+ "pop r25 \n\t" \
+ "pop r24 \n\t" \
+ "pop r23 \n\t" \
+ "pop r22 \n\t" \
+ "pop r21 \n\t" \
+ "pop r20 \n\t" \
+ "pop r19 \n\t" \
+ "pop r18 \n\t" \
+ "pop r17 \n\t" \
+ "pop r16 \n\t" \
+ "pop r15 \n\t" \
+ "pop r14 \n\t" \
+ "pop r13 \n\t" \
+ "pop r12 \n\t" \
+ "pop r11 \n\t" \
+ "pop r10 \n\t" \
+ "pop r9 \n\t" \
+ "pop r8 \n\t" \
+ "pop r7 \n\t" \
+ "pop r6 \n\t" \
+ "pop r5 \n\t" \
+ "pop r4 \n\t" \
+ "pop r3 \n\t" \
+ "pop r2 \n\t" \
+ "pop r1 \n\t"); \
+ portRESTORE_RAMPZ(); \
+ asm volatile("pop r0 \n\t" \
+ "out __SREG__, r0 \n\t" \
+ "pop r0 \n\t"); \
+ }
+/*-----------------------------------------------------------*/
+
+#define portSET_MODE_AND_SLEEP(mode) \
+ { \
+ set_sleep_mode(mode); \
+ sleep_enable(); \
+ portENABLE_INTERRUPTS(); \
+ sleep_cpu(); \
+ portDISABLE_INTERRUPTS(); \
+ sleep_disable(); \
+ }
+
+/* *INDENT-OFF* */
+ #ifdef __cplusplus
+ }
+ #endif
/* *INDENT-ON* */
#endif /* PORTMACRO_H */