Timer2 asynchronous clocking problem (ATmega328P)

Hello,

I'm playing around with Timer2 in asynchronous mode on a custom board. External clock source is a DS3231 32kHz output (with 4k7 pull-up resistor) connected to TOSC1 pin. The sketch is only a test program at this point, so it doesn't do anything specific, just trying to flash a led with sleep mode and wake up by Timer2 interrupt. I've tried to set related registers cautiously (e.g. waiting for ASSR busy bits to be cleared if necessary) and also added comments based on the datasheet.

My problem is that the uC doesn't wake up, not even once, unless I add a little delay before goToSleep() function (leds stay in HIGH state).

I simply don't get it. The only thing that would explain this, is Timer2 interrupt happening somewhere between enableTimer2Interrupt() and goToSleep() (and related Timer2 interrupt is disabled by the related routine), but why does delay(1) help?
(32kHz is enabled in every case, I've checked it with a scope)

/******************************************************************************/
/* INCLUDE, DEFINE */
/******************************************************************************/
#include <avr/sleep.h>
#include <avr/wdt.h>
#include <DS3232RTC.h>
#include <Wire.h>

/******************************************************************************/
/* CONSTANTS */
/******************************************************************************/
const uint8_t BLUE_LED_PIN = 6;
const uint8_t RED_LED_PIN = 7;

/*RTC Status Register bits*/
/*********************************************|
| OSF | X | X | X | EN32kHz | BSY | A2F | A1F |
|*********************************************/
const uint8_t RTC_EN32KHZ = 3;

const uint8_t RTC_CONTROL_ADDRESS = 0x0E;
const uint8_t RTC_STATUS_ADDRESS = 0x0F;

/******************************************************************************/
/* VARIABLES, OBJECTS */
/******************************************************************************/
DS3232RTC myRTC;

/******************************************************************************/
/* SETUP */
/******************************************************************************/
void setup()
{
  setPinModes();

  /*set default for RTC*/
  initRTC();
    
  /*set asynchronous operation of Timer2 and do a basic*/
  /* timer, sleep function check with led flashing*/
  setAsynchronousTimer2();
}

/******************************************************************************/
/* LOOP */
/******************************************************************************/
void loop()
{
  digitalWrite(BLUE_LED_PIN, HIGH);
  digitalWrite(RED_LED_PIN, HIGH);
  enable32kHz();

  // (3 + 1) * 31.25ms = 125ms
  setTimer2TopValue(3);
  resetTimer2();
  enableTimer2Interrupt();

  // this delay helps
  // delay(1ul);
  goToSleep();
    
  disable32kHz();
  digitalWrite(BLUE_LED_PIN, LOW);
  digitalWrite(RED_LED_PIN, LOW);
  delay(125ul);

}

/******************************************************************************/
/* RTC */
/******************************************************************************/
void initRTC()
{
  Wire.begin();
  myRTC.writeRTC(RTC_STATUS_ADDRESS, 0x00);
  myRTC.writeRTC(RTC_CONTROL_ADDRESS, 0x00);
}

void enable32kHz()
{
  myRTC.writeRTC(RTC_STATUS_ADDRESS, bit(RTC_EN32KHZ));

  /*make sure that square-wave is stabilized*/
  delay(2ul);
}

void disable32kHz()
{
  /*uC can be right after sleep, wait a little*/
  delay(1ul);
  myRTC.writeRTC(RTC_STATUS_ADDRESS, 0x00);
}

/******************************************************************************/
/* SLEEP */
/******************************************************************************/
void goToSleep()
{
  uint8_t old_ADCSRA = 0;

  /*turn off I2C (twi_disable)*/
  Wire.end();

  /*disable ADC*/
  old_ADCSRA = ADCSRA;
  ADCSRA = 0;

  /*do not interrupt before going to sleep or the ISR will detach*/
  /*interrupts and wake by interrupt will be disabled*/
  noInterrupts();

  /*disable watchdog*/
  wdt_disable();

  /*clear various "reset" flags*/
  MCUSR = 0;

  /*full power-down doesn't respond to Timer2, use Power-save mode*/
  set_sleep_mode(SLEEP_MODE_PWR_SAVE);

  sleep_enable();

  /*clear interrupt flags by writing logical one*/
  EIFR = bit(INTF0);
  EIFR = bit(INTF1);

  /*turn off brown-out enable in software*/
  /*to disable BOD in relevant sleep modes, both BODS and BODSE must first be set to 1*/
  /*then, to set the BODS bit, BODS must be set to 1 and BODSE must be set to 0 within 4 clock cycles*/
  MCUCR = bit(BODS) | bit(BODSE);
  MCUCR = bit(BODS);

  /*it is guaranteed that the sleep_cpu call will be done as the processor*/
  /*executes the next instruction after interrupts are turned on*/
  /*one cycle*/
  interrupts();
  /*one cycle*/
  sleep_cpu();

  /*AFTER ISR execution, running is continue from here*/
  ADCSRA = old_ADCSRA;

  /*i2c is needed every time after wakeup*/
  Wire.begin();
}

/******************************************************************************/
/* INTERRUPT ROUTINES */
/******************************************************************************/
ISR(TIMER2_COMPA_vect)
{
  /*disable Timer2 interrupt*/
  TIMSK2 = 0;
}

/******************************************************************************/
/* TIMER2 RELATED */
/******************************************************************************/
void setAsynchronousTimer2()
{
  /*!! Warning: When switching between asynchronous and synchronous clocking           !!*/
  /*!! of Timer/Counter2, the Timer Registers TCNT2, OCR2x, and TCCR2x might           !!*/
  /*!! be corrupted. A safe procedure for switching clock source is:                   !!*/
  /*!! a. Disable the Timer/Counter2 interrupts by clearing OCIE2x and TOIE2.          !!*/
  /*!! b. Select clock source by setting AS2 as appropriate.                           !!*/
  /*!! c. Write new values to TCNT2, OCR2x, and TCCR2x.                                !!*/
  /*!! d. To switch to asynchronous operation: Wait for TCN2xUB, OCR2xUB, and TCR2xUB. !!*/
  /*!! e. Clear the Timer/Counter2 interrupt flags.                                    !!*/
  /*!! f. Enable interrupts, if needed.                                                !!*/

  /*disable interrupts (by clearing OCIE2x and TOIE2)*/
  TIMSK2 = 0;

  /*clean start for control registers, stop and reset Timer2*/
  TCCR2A = 0;
  TCCR2B = 0;
  TCNT2 = 0;

  /*Writing to EXCLK should be done before asynchronous operation is selected*/
  ASSR = bit(EXCLK);

  /*select asynchronous operation of Timer2*/
  ASSR |= bit(AS2);

  /*!! When (after) the value of AS2 is changed, the contents of TCNT2, OCR2A, !!*/
  /*!! OCR2B, TCCR2A and TCCR2B might be corrupted. Each of the five mentioned !!*/
  /*!! registers have their individual temporary register, which means that    !!*/
  /*!! e.g. writing to TCNT2 does not disturb an OCR2x write in progress       !!*/

  /*!! If a write is performed to any of the five Timer/Counter2    !!*/
  /*!! while its update busy flag is set, the updated value might   !!*/
  /*!! get corrupted and cause an unintentional interrupt to occur. !!*/

  /*wait until TCCR2A and TCCR2B are ready to be updated with a new value*/
  /*(related busy bits are cleared by hardware)*/
  while ((ASSR & (bit(TCR2AUB) | bit(TCR2BUB))) == 1) continue;

  /*set CTC mode and prescaler to 1024 (1024*(1/32768) = 31,25ms)*/
  TCCR2A = bit(WGM21);
  TCCR2B = bit(CS22) | bit(CS21) | bit(CS20);

  /*wait until TCCR2A and TCCR2B is updated from their temporary*/
  /*storage register (related busy bits are cleared by hardware)*/
  while ((ASSR & (bit(TCR2AUB) | bit(TCR2BUB))) == 1) continue;
}

void setTimer2TopValue(uint8_t topValue)
{
  /*wait until OCR2A is ready to be updated with a new value*/
  while ((ASSR & bit(OCR2AUB)) == 1) continue;

  /*e.g. 5000ms / 31,25ms = 160 --> count to 159 (zero-relative)*/
  OCR2A = topValue;

  /*wait until OCR2A is updated from temporary storage register*/
  while ((ASSR & bit(OCR2AUB)) == 1) continue;
}

void resetTimer2()
{
  /*!! If the user is in doubt whether the time before re-entering power-save or ADC !!*/
  /*!! noise reduction mode is sufficient, the following algorithm can be used       !!*/
  /*!! to ensure that one TOSC1 cycle has elapsed:                                   !!*/
  /*!! a. Write a value to TCCR2x, TCNT2, or OCR2x.                                  !!*/
  /*!! b. Wait until the corresponding update busy flag in ASSR returns to zero.     !!*/
  /*!! c. Enter power-save or ADC noise reduction mode                               !!*/

  /*reset timer*/
  TCNT2 = 0;

  /*wait until TCNT2 is updated from temporary storage register*/
  while ((ASSR & bit(TCN2UB)) == 1) continue;
}

void enableTimer2Interrupt()
{
  noInterrupts();

  /*enable Timer2 compare match A interrupt*/
  TIMSK2 = bit(OCIE2A);

  /*clear (pending) interrupt-flags (flags are cleared by writing a logic one)*/
  TIFR2 = bit(OCF2B) | bit(OCF2A) | bit(TOV2);

  interrupts();
}

void setPinModes()
{
  analogReference(DEFAULT);

  pinMode(BLUE_LED_PIN, OUTPUT);
  digitalWrite(BLUE_LED_PIN, LOW);

  pinMode(RED_LED_PIN, OUTPUT);
  digitalWrite(RED_LED_PIN, LOW);
}

Anyone have any ideas?
Thanks in advance.

Here's some code I was playing around with a few years ago. I still haven't got around to completing that project, but the parts that used timer2 worked ok. I was using a 32KHz external crystal and wanted timer2 to interrupt every second, waking the atmega from sleep mode.

Take a look at the parts that deal with timer2 and compare them to your code to see if anything is missing.

#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
#include <avr/sleep.h>

#define BATT_PIN A3
#define ANEMOMETER_PIN 2
#define RAIN_SENSOR_PIN 3
#define WIND_DIR_SENSOR_PIN A2
#define WIND_DIR_SENSOR_ENABLE_PIN 4
#define SERVER_UPDATE_PERIOD 900UL
#define WIND_GUST_PERIOD 6UL
#define COMPASS_DIRECTIONS 16

//Variables used in interrupt code
volatile unsigned long elapsedSeconds = 0;
volatile unsigned int anemometerCount = 0;
volatile unsigned int rainSensorCount = 0;
volatile unsigned int windGustCount = 0;
volatile unsigned int gustPeriodStartSeconds = 0;
volatile unsigned int gustPeriodStartCount = 0;
volatile unsigned int windDirReading = 0;
volatile long windDirTot[COMPASS_DIRECTIONS];

//Arrays to convert readings from wind direction sensor into compass directions
const int reading[COMPASS_DIRECTIONS] = {147, 172, 208, 281, 368, 437, 531, 624, 710, 780, 817, 870, 909, 938, 970, 1023};
const int compass[COMPASS_DIRECTIONS] = {112,  67,  90, 157, 135, 202, 180,  22,  45, 247, 225, 337,   0, 292, 315,  270};

volatile byte TCNT2Before = 0;

ISR(TIMER2_OVF_vect) {
  elapsedSeconds++;
}

void anemometerISR() {
  //  if (TCNT2 - TCNT2Before >= 1) {
  anemometerCount++;
  //    TCNT2Before = TCNT2;
  //  }
  
  //Is the wind gust period up?
  if (elapsedSeconds - gustPeriodStartSeconds > WIND_GUST_PERIOD) {
    //Do we have a new highest gust count?
    if (anemometerCount - gustPeriodStartCount > windGustCount) {
      //Record a new highest wind gust count
      windGustCount = anemometerCount - gustPeriodStartCount;
    }
    //Start a new gust period
    gustPeriodStartSeconds = elapsedSeconds;
    gustPeriodStartCount = anemometerCount;
  }

  //Read the wind direction sensor
  bitSet(ADCSRA, ADEN); // Enable ADC
  pinMode(WIND_DIR_SENSOR_ENABLE_PIN, OUTPUT);
  digitalWrite(WIND_DIR_SENSOR_ENABLE_PIN, HIGH);
  windDirReading = analogRead(WIND_DIR_SENSOR_PIN);
  pinMode(WIND_DIR_SENSOR_ENABLE_PIN, INPUT);
  // Translate analog reading into compass direction
  // Can be one of 16 values, but there could be some
  // analog noise, so the reading[] array contains values
  // mid-way between the expected readings.
  byte i;
  for (i = 0; i < COMPASS_DIRECTIONS && windDirReading >= reading[i]; i++);
  windDirTot[i]++;
  bitClear(ADCSRA, ADEN); // Disable ADC

}

void rainSensorISR() {
  //  if (TCNT2 - TCNT2Before >= 1) {
  rainSensorCount++;
  //    TCNT2Before = TCNT2;
  //  }
}


void initTimer2() {

  //Set up timer 2 to use external 32.768KHz crystal
  TIMSK2 = 0; //Disable timer2 interrupts
  ASSR   = _BV(AS2); //enable asynchronous mode for timer2, so it uses the external crystal
  TCNT2  = 0; //Reset timer2
  TCCR2A = 0;
  TCCR2B = _BV(CS22) | _BV(CS20); //Start the timer (128 pre-scale)
  while (ASSR != _BV(AS2)); //Wait for TCN2xUB, OCR2xUB, and TCR2xUB.
  TIFR2  = 0; //Clear the interrupt flag
  TIMSK2 = _BV(TOIE2); //Enable the overflow interrupt
}

void deep_sleep(unsigned int sleepSeconds) {

  bitClear(ADCSRA, ADEN); // Disable ADC
  set_sleep_mode(SLEEP_MODE_PWR_SAVE);

  unsigned int elapsedSecondsBefore = elapsedSeconds;
  while (elapsedSeconds - elapsedSecondsBefore < sleepSeconds) {
    TCCR2B = _BV(CS22) | _BV(CS20); //Start the timer (128 pre-scale)
    while (ASSR != _BV(AS2)); //Wait for TCN2xUB, OCR2xUB, and TCR2xUB.
    sleep_enable();
    cli(); //time critical steps follow
    MCUCR = _BV(BODS) | _BV(BODSE); // turn on brown-out enable select
    MCUCR = _BV(BODS);       //Brown out off. This must be done within 4 clock cycles of above
    sei();
    sleep_cpu();
    sleep_disable();
  }

  bitSet(ADCSRA, ADEN); // Enable ADC

}

// LoRaWAN NwkSKey, network session key
static const PROGMEM u1_t NWKSKEY[16] = { xxxx };

// LoRaWAN AppSKey, application session key
static const u1_t PROGMEM APPSKEY[16] = { xxxx };

// LoRaWAN end-device address (DevAddr)
static const u4_t DEVADDR = xxxx; // <-- Change this address for every node!

// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in config.h, otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }

static osjob_t sendjob;

// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 0; //Set to zero because do_send() delays for a suitable period

// Pin mapping
const lmic_pinmap lmic_pins = {
  .nss = 10,
  .rxtx = LMIC_UNUSED_PIN,
  .rst = 9,
  .dio = {8, 7, 6},
};

void onEvent (ev_t ev) {
  Serial.print(os_getTime());
  Serial.print(": ");
  switch (ev) {
    case EV_SCAN_TIMEOUT:
      Serial.println(F("EV_SCAN_TIMEOUT"));
      break;
    case EV_BEACON_FOUND:
      Serial.println(F("EV_BEACON_FOUND"));
      break;
    case EV_BEACON_MISSED:
      Serial.println(F("EV_BEACON_MISSED"));
      break;
    case EV_BEACON_TRACKED:
      Serial.println(F("EV_BEACON_TRACKED"));
      break;
    case EV_JOINING:
      Serial.println(F("EV_JOINING"));
      break;
    case EV_JOINED:
      Serial.println(F("EV_JOINED"));
      break;
    case EV_JOIN_FAILED:
      Serial.println(F("EV_JOIN_FAILED"));
      break;
    case EV_REJOIN_FAILED:
      Serial.println(F("EV_REJOIN_FAILED"));
      break;
    case EV_TXCOMPLETE:
      Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
      if (LMIC.txrxFlags & TXRX_ACK)
        Serial.println(F("Received ack"));
      if (LMIC.dataLen) {
        Serial.println(F("Received "));
        Serial.println(LMIC.dataLen);
        Serial.println(F(" bytes of payload"));
      }
      // Schedule next transmission
      os_setTimedCallback(&sendjob, os_getTime() + sec2osticks(TX_INTERVAL), do_send);
      break;
    case EV_LOST_TSYNC:
      Serial.println(F("EV_LOST_TSYNC"));
      break;
    case EV_RESET:
      Serial.println(F("EV_RESET"));
      break;
    case EV_RXCOMPLETE:
      // data received in ping slot
      Serial.println(F("EV_RXCOMPLETE"));
      break;
    case EV_LINK_DEAD:
      Serial.println(F("EV_LINK_DEAD"));
      break;
    case EV_LINK_ALIVE:
      Serial.println(F("EV_LINK_ALIVE"));
      break;
    case EV_TXSTART:
      Serial.println(F("EV_TXSTART"));
      break;
    case EV_TXCANCELED:
      Serial.println(F("EV_TXCANCELED"));
      break;
    case EV_RXSTART:
      /* do not print anything -- it wrecks timing */
      break;
    case EV_JOIN_TXCOMPLETE:
      Serial.println(F("EV_JOIN_TXCOMPLETE: no JoinAccept"));
      break;
    default:
      Serial.print(F("Unknown event: "));
      Serial.println((unsigned) ev);
      break;
  }
}

void do_send(osjob_t* j) {
  // Check if there is not a current TX/RX job running
  if (LMIC.opmode & OP_TXRXPEND) {
    Serial.println(F("OP_TXRXPEND, not sending"));
  } else {
    char batt[10], payload[64];

    Serial.print(F("Sleeping, timer2="));
    Serial.println(elapsedSeconds);
    Serial.flush();

    deep_sleep(60);

    Serial.print(F("Waking, timer2="));
    Serial.println(elapsedSeconds);

    Serial.print(F("anemometer="));
    Serial.println(anemometerCount);

    delay(10); // wait for ADC to stabilise
    float b = analogRead(BATT_PIN) * 1.1 / 256; // Voltage divider: 180K & 60K
    dtostrf(b, 1, 2, batt);

    // Calcualate average wind speed, in Km/hr, over reporting period
    // Note: 1 rotation per second = 2.4 Km/hr
    // 2 changes per rotation, so 1 change per second = 1.2 Km/hr
    double windSpeed = 1.2 * anemometerCount / SERVER_UPDATE_PERIOD;
    Serial.print("windSpeed=");
    Serial.print(windSpeed);
  
    // Calculate wind gust speed, in Km/hr, over period of 6s
    // Note: 1 rotation per second = 2.4 Km/hr
    // 2 changes per rotation, so 1 change per second = 1.2 Km/hr
    double windGustSpeed = 1.2 * windGustCount / WIND_GUST_PERIOD;
    Serial.print(" maxWindGust=");
    Serial.print(windGustSpeed);
    //Reset wind gust count for next period
    windGustCount = 0;
  
    // Report rainfall rate in mm/hr
    // One counts = 0.011" of rain
    // One count per second = 0.011 * 25.4 * 60 * 60 = 1005.84mm/hr
    double rainRate = 1005.84 * rainSensorCount / SERVER_UPDATE_PERIOD;
    Serial.print(" rainRate=");
    Serial.print(rainRate);
    //Reset rain sensor count for next period
    rainSensorCount = 0;

    // Find most common wind direction over the reporting period
    long maxWindDirTot = 0;
    byte maxWindDirIndex = 0;
    for (byte i = 0; i < COMPASS_DIRECTIONS; i++) {
      if (windDirTot[i] > maxWindDirTot) {
        maxWindDirTot = windDirTot[i];
        maxWindDirIndex = i;
      }
      //Reset for next reporting period
      windDirTot[i] = 0;
    }
    int windDir = compass[maxWindDirIndex];


    sprintf(payload, "BV=%s", batt); //To add: WV, GV, DV, RV
    Serial.print(F("payload = "));
    Serial.println(payload);

    // Prepare upstream data transmission at the next possible time.
    LMIC_setTxData2(1, (uint8_t *)payload, strlen(payload), 0);
    Serial.println(F("Packet queued"));
  }
  // Next TX is scheduled after TX_COMPLETE event.
}


void setup() {
  Serial.begin(115200);
  Serial.println(F("Starting"));
  analogReference(INTERNAL);
  initTimer2();
  pinMode(ANEMOMETER_PIN, INPUT_PULLUP);
  attachInterrupt(digitalPinToInterrupt(ANEMOMETER_PIN), anemometerISR, FALLING);
  pinMode(RAIN_SENSOR_PIN, INPUT_PULLUP);
  attachInterrupt(digitalPinToInterrupt(RAIN_SENSOR_PIN), rainSensorISR, FALLING);

  // LMIC init
  os_init();
  // Reset the MAC state. Session and pending data transfers will be discarded.
  LMIC_reset();

  // Set static session parameters. Instead of dynamically establishing a session
  // by joining the network, precomputed session parameters are be provided.
#ifdef PROGMEM
  // On AVR, these values are stored in flash and only copied to RAM
  // once. Copy them to a temporary buffer here, LMIC_setSession will
  // copy them into a buffer of its own again.
  uint8_t appskey[sizeof(APPSKEY)];
  uint8_t nwkskey[sizeof(NWKSKEY)];
  memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
  memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
  LMIC_setSession (0x1, DEVADDR, nwkskey, appskey);
#else
  // If not running an AVR with PROGMEM, just use the arrays directly
  LMIC_setSession (0x1, DEVADDR, NWKSKEY, APPSKEY);
#endif

  // Set up the channels used by the Things Network
  LMIC_setupChannel(0, 868100000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(1, 868300000, DR_RANGE_MAP(DR_SF12, DR_SF7B), BAND_CENTI);      // g-band
  LMIC_setupChannel(2, 868500000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(3, 867100000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(4, 867300000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(5, 867500000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(6, 867700000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band
  LMIC_setupChannel(7, 867900000, DR_RANGE_MAP(DR_SF12, DR_SF7),  BAND_CENTI);      // g-band

  // Disable link check validation
  LMIC_setLinkCheckMode(0);

  // Set data rate and transmit power (note: txpow seems to be ignored by the library)
  LMIC_setDrTxpow(DR_SF7, 14);

  // Start job
  do_send(&sendjob);
}

void loop() {
  os_runloop_once();
}

This code creates an RTC using Timer2, with a 32 kHz crystal + 2x22 pF caps on the oscillator pins. The fuses must be set for 8 MHz internal oscillator for the waking activity. It calibrates the 8 MHz clock using the 32 kHz crystal as a time base and on waking, reads and prints the battery voltage and time. I use it as the starting point for remote sensors, some still working 10 years later.

Maybe it will give you some ideas.

// low power RTC using bare bones ATMega328p, no regulator, 3-5V
// not complete yet, needs UART routines!

// This code incorporates an RTC formed by Timer2 and a 32768 xtal+2x30pF caps on OSC pins
// The internal RC oscillator is calibrated by comparison with the 32768 Hz standard.

// SET FUSES: 8 MHz internal clock, LP xtal (32768 Hz) on OSC pins
// sjr 3/2013

// Timer0 is disabled by this code

//uses 8 MHz internal RC for the processor
#define F_CPU 8000000UL

#include <util/delay.h>
#include <stdio.h>
#include <stdlib.h>
#include <avr/interrupt.h>
#include <avr/io.h>
#include <avr/sleep.h>
#include <string.h>

// Global variables for RTC

volatile unsigned char RTC_buf[] = {0, 0, 0, 0, 0, 0}; //binary hh:mm:ss
volatile unsigned int dayno = 0; //days since startup

#define BUF_LEN 30

char buf[BUF_LEN]

void OSCCAL_calibrate(void);
void timer2_init(void);
unsigned int readVcc(void);

/*
** MAIN
*/
int main(void)
{

  char t, zero = 0;
  unsigned int batt, h, m, s;
  
// we do our own printing and formatting.

  static FILE uart_stream;
  fdev_setup_stream(&uart_stream, uart_putchar, uart_getchar, _FDEV_SETUP_RW);
  stdout = &uart_stream;

  uart_init(9600); //Baud rate

  //PRR Power Reduction Register (set PRADC after ADCSRA=0)
  //Bit 7 - PRTWI: Power Reduction TWI
  //Bit 6 - PRTIM2: Power Reduction Timer/Counter2
  //Bit 5 - PRTIM0: Power Reduction Timer/Counter0
  //Bit 3 - PRTIM1: Power Reduction Timer/Counter1
  //Bit 2 - PRSPI: Power Reduction Serial Peripheral Interface
  //Bit 1 - PRUSART0: Power Reduction USART0
  //Bit 0 - PRADC: Power Reduction ADC

  ADCSRA = 0; //disable ADC
  PRR |= (1 << PRTWI) | (1 << PRTIM0) | (1 << PRSPI) | (1 << PRUSART0) | (1 << PRADC); //need timers 1 and 2

  OSCCAL_calibrate();  //calibrate the RC osc using the 32 kHz crystal

  // reprogram timers for this application

  timer2_init();


  //	vw_setup(2000);	 // VirtualWire bits per sec

  sei();  //enable interrupts (Timer 2 ticks)

  t = 99; //initialize loop timer, here based on RTC 10 minutes digit

  while (1) {

    // wake up on Timer2 overflow (1/sec)
    // output day, time and cpu voltage on uart every 10 minutes

    if (t != RTC_buf[3]) { //did 10 minute digit change?

      t = RTC_buf[3]; //save digit
      s = 10 * RTC_buf[4] + RTC_buf[5]; //format time
      m = 10 * RTC_buf[2] + RTC_buf[3];
      h = 10 * RTC_buf[0] + RTC_buf[1];

      PRR &= ~((1 << PRADC) | (1 << PRUSART0)); //turn ADC and UART back on
      ADCSRA = (1 << ADEN);
      ADCSRA |= (1 << ADPS0) | (1 << ADPS1) | (1 << ADPS2); // Prescaler 128

      delay1ms(2); //let ADC and UART stabilize

      batt = readVcc();  //get battery voltage in mV

      sprintf(buf, "%0u,%0d,%0d,%0d,%0u\r\n%c", dayno, h, m, s, batt, zero); //max ~16 characters
      uart_puts(buf);
      delay1ms(3); //let uart finish

      ADCSRA = 0; //ADC off
      PRR |= (1 << PRADC) | (1 << PRUSART0);  //and USART off

    } //end if (t ...

    set_sleep_mode(SLEEP_MODE_PWR_SAVE);
    sleep_enable();
    cli(); //time critical steps follow
    MCUCR = (1 << BODS) | (1 << BODSE);	// turn on brown-out enable select
    MCUCR = (1 << BODS);        		//Brown out off. This must be done within 4 clock cycles of above
    sei();
    sleep_cpu();

  } //end while(1)
}

//******************************************************************
//  Timer2 Interrupt Service
//  32 kKz / 256 = 1 Hz with prescaler 128
//  provides global tick timer and binary RTC
//  no check for illegal values of RTC_buffer upon startup!

ISR (TIMER2_OVF_vect) {

  // RTC function

  RTC_buf[5]++;		// increment second

  if (RTC_buf[5] > 9)
  {
    RTC_buf[5] = 0;	// increment ten seconds
    RTC_buf[4]++;
    if ( RTC_buf[4] > 5)
    {
      RTC_buf[4] = 0;
      RTC_buf[3]++;			// increment minutes
      if (RTC_buf[3] > 9)
      {
        RTC_buf[3] = 0;
        RTC_buf[2]++;		// increment ten minutes

        if (RTC_buf[2] > 5)
        {
          RTC_buf[2] = 0;
          RTC_buf[1]++;			// increment hours
          char b = RTC_buf[0]; // tens of hours, handle rollover at 19 or 23
          if ( ((b < 2) && (RTC_buf[1] > 9)) || ((b == 2) && (RTC_buf[1] > 3)) )
          {
            RTC_buf[1] = 0;
            RTC_buf[0]++;		// increment ten hours and day number, if midnight rollover
            if (RTC_buf[0] > 2) {
              RTC_buf[0] = 0;
              dayno++;
            }
          }
        }
      }
    }
  }
}


/*
  // initialize Timer2 as asynchronous 32768 Hz timing source
*/

void timer2_init(void) {

  TCCR2B = 0;  //stop Timer 2
  TIMSK2 = 0;	// disable Timer 2 interrupts
  ASSR = (1 << AS2);	// select asynchronous operation of Timer2
  TCNT2 = 0;			// clear Timer 2 counter
  TCCR2A = 0; 		//normal count up mode, no port output
  TCCR2B = (1 << CS22) | (1 << CS20);		// select prescaler 128 => 1 sec between each overflow

 while (ASSR & ((1<<TCN2UB)|(1<<TCR2BUB)|(1<<TCR2AUB))); // wait for TCN2UB and TCR2A/BUB to be cleared


  TIFR2 = (1 << TOV2);			// clear interrupt-flag
  TIMSK2 = (1 << TOIE2);	// enable Timer2 overflow interrupt
}

// Read 1.1V reference against AVcc

unsigned int readVcc(void) {

  unsigned int result;

  // set the reference to Vcc and the measurement to the internal 1.1V reference

  ADMUX = (1 << REFS0) | (1 << MUX3) | (1 << MUX2) | (1 << MUX1);
  delay1ms(2); // Wait for Vref to settle

  ADCSRA |= (1 << ADSC); // Start conversion
  while (bit_is_set(ADCSRA, ADSC)); // wait until done
  result = ADC;

  // two is better than one

  ADCSRA |= (1 << ADSC); // Start conversion
  while (bit_is_set(ADCSRA, ADSC)); // wait until done
  result = ADC;

  // calibrated for Miniduino
  result = 1195700UL / (unsigned long)result; //1126400 = 1.1*1024*1000
  return result; // Vcc in millivolts
}

//
// Calibrate the internal OSCCAL byte, using the external 32768 Hz crystal as reference.
//

void OSCCAL_calibrate(void)  //This version specific to ATmegaXX8 (tested with ATmega328)

{
  unsigned char calibrate = 0; //FALSE;
  unsigned int temp;

  TIMSK1 = 0; //disable Timer1,2 interrupts
  TIMSK2 = 0;

  ASSR = (1 << AS2);      //select asynchronous operation of timer2 (32,768kHz)
  OCR2A = 200;            // set timer2 compare value
  TCCR1A = 0;
  TCCR1B = (1 << CS11);   // start timer1 with prescaler 8
  TCCR2A = 0;
  TCCR2B = (1 << CS20);   // start timer2 with no prescaling (ATmega169 use TCCR2A!)

  while (ASSR & ((1 << TCN2UB) | (1 << TCR2BUB))); //wait for TCN2UB and TCR2BUB to be cleared
  delay1ms(2000); //allow xtal osc to stabilize

  while (!calibrate)
  {
    cli(); // disable global interrupt

    TIFR1 = 0xFF;   // clear TIFR1 flags
    TIFR2 = 0xFF;   // clear TIFR2 flags

    TCNT1 = 0;      // clear timer1 counter
    TCNT2 = 0;      // clear timer2 counter

    while ( !(TIFR2 & (1 << OCF2A)) ); // wait for timer2 compareflag

    TCCR1B = 0; // stop timer1

    sei();			// enable global interrupts

    if ( (TIFR1 & (1 << TOV1)) ) temp = 0xFFFF; //overflow, load max
    else   temp = TCNT1;

    if (temp > 6140)  //expect about (1e6/32768)*201 = 6134 ticks
    {
      OSCCAL--;   //RC oscillator runs too fast, decrease OSCCAL
    }
    else if (temp < 6130)
    {
      OSCCAL++;   //RC oscillator runs too slow, increase OSCCAL
    }
    else calibrate = 1; //done

    TCCR1B = (1 << CS11); // (re)start timer1

  } //end while(!calibrate)
} //return

Thanks for the quick replies.

@PaulRB's slightly different approach for checking busy bits gave an idea to double check ASSR before enabling Timer2 interrupt.

So changing this:

void enableTimer2Interrupt()
{
  noInterrupts();

  /*enable Timer2 compare match A interrupt*/
  TIMSK2 = bit(OCIE2A);

  /*clear (pending) interrupt flags (cleared by writing a logic one)*/
  TIFR2 = bit(OCF2B) | bit(OCF2A) | bit(TOV2);

  interrupts();
}

to this:

void enableTimer2Interrupt()
{
  /*make sure every busy bit is cleared*/
  while (ASSR != (bit(AS2) | bit(EXCLK))) continue;

  noInterrupts();

  /*enable Timer2 compare match A interrupt*/
  TIMSK2 = bit(OCIE2A);

  /*clear (pending) interrupt flags (cleared by writing a logic one)*/
  TIFR2 = bit(OCF2B) | bit(OCF2A) | bit(TOV2);

  interrupts();
}

solved the problem without a need for delay.

works-doesnt-work

I still don't get it. Every "special" register write was already protected by checking related, individual busy bits.

That reminds me that I did run into trouble with one application, and discovered that in that particular case, three busy bits needed to be checked. I don't know what led to the difference in behavior. It was certainly not clear from the data sheet.

while (ASSR & ((1<<TCN2UB)|(1<<TCR2BUB)|(1<<TCR2AUB))); // wait for TCN2UB and TCR2A/BUB to be cleared

The datasheet states:

18.9 Asynchronous Operation of Timer/Counter2

...
When writing to one of the registers TCNT2, OCR2x, or TCCR2x, the value is transferred to a temporary
register, and latched after two positive edges on TOSC1. The user should not write a new value before the
contents of the temporary register have been transferred to its destination. Each of the five mentioned registers have their individual temporary register, which means that e.g. writing to TCNT2 does not disturb an OCR2x write in progress. To detect that a transfer to the destination register has taken place, the Asynchronous Status Register – ASSR has been implemented
...

So in my interpretetation, individial checking should also work.

I can't claim to have invented that myself, took a lot of help from the forum, probably including @jremington.

Glad you got it working.

And it works of course, significant user error was made.
I just needed to relearn how bitwise AND works.

This doesn't wait until busy bit (except LSB) is cleared:

while ((ASSR & bit(OCR2AUB)) == 1) continue;

But this one is:

while ((ASSR & bit(OCR2AUB)) != 0) continue;

This topic was automatically closed 180 days after the last reply. New replies are no longer allowed.