Feed on
Posts
Comments

Today we’ll be modifying the ATtiny85_Blink WinAVR example to convert the Standalone Temperature Logger from using the Arduino software to WinAVR so that we can easily integrate it in with V-USB. Download here: Standalone_Temperature_Logger_v2.0_Beta_1

Changes to setup.c

Let’s begin with the setup.c file, to make things easier we will put all of our commonly used functions in this file too.

// Used from http://www.arduino.cc/playground/ComponentLib/Thermistor2
double Thermistor(int RawADC) {
  double Temp;
  Temp = log(((10240000/RawADC) - 10000));
  Temp = 1 / (0.001129148 + (0.000234125 * Temp) + (0.0000000876741 * Temp * Temp * Temp));
  Temp = Temp - 273.15; // Convert Kelvin to Celcius
  return Temp;
}

First we put in the Thermistor function without any changes made.

// Used from http://interface.khm.de/index.php/lab/experiments/sleep_watchdog_battery/
void system_sleep(void) {
  DDRB &= ~((1<<ledPin) | (1<<dataPin)); // Set outputs to inputs to save some power
  cbi(ADCSRA,ADEN); // Switch Analog to Digital converter OFF
  set_sleep_mode(SLEEP_MODE_PWR_DOWN); // Set sleep mode
  sleep_mode(); // System sleeps here
  sbi(ADCSRA,ADEN);  // Switch Analog to Digital converter ON
  DDRB |= ((1<<ledPin) | (1<<dataPin)); // Set those outputs back to outputs
}

Next we insert the system_sleep function, other than the switching between outputs and inputs which is done using DDRB. Notice that we have referenced ledPin and dataPin, we will define those ports in the main.c file.

// Watchdog timeout values
// 0=16ms, 1=32ms, 2=64ms, 3=128ms, 4=250ms, 5=500ms, 6=1sec, 7=2sec, 8=4sec, 9=8sec
// Used from http://interface.khm.de/index.php/lab/experiments/sleep_watchdog_battery
void setup_watchdog(int ii) {
  byte bb;
  int ww;
  if (ii > 9 ) ii=9;
  bb=ii & 7;
  if (ii > 7) bb|= (1<<5);
  bb|= (1<<WDCE);
  ww=bb;

  MCUSR &= ~(1<<WDRF);
  // Start timed sequence
  WDTCR |= (1<<WDCE) | (1<<WDE);
  // Set new watchdog timeout value
  WDTCR = bb;
  WDTCR |= _BV(WDIE);
}

The setup_watchdog function is also placed here and once again no change is needed.

// Used from Arduino wiring_analog.c
int analogRead(uint8_t pin) {
  uint8_t low, high;

  // set the analog reference (high two bits of ADMUX) and select the
  // channel (low 4 bits).  this also sets ADLAR (left-adjust result)
  // to 0 (the default).
  //    ADMUX = (analog_reference << 6) | (pin & 0x3f); // more MUX
  // sapo per tiny45
  ADMUX = pin & 0x3f;

  // without a delay, we seem to read from the wrong channel
  //delay(1);

  // start the conversion
  sbi(ADCSRA, ADSC);

  // ADSC is cleared when the conversion finishes
  while (bit_is_set(ADCSRA, ADSC));

  // we have to read ADCL first; doing so locks both ADCL
  // and ADCH until ADCH is read.  reading ADCL second would
  // cause the results of each conversion to be discarded,
  // as ADCL and ADCH would be locked when it completed.
  low = ADCL;
  high = ADCH;

  // combine the two bytes
  return (high << 8) | low;
}

The only other thing that’s missing form the setup.c file is the analog reading, we can actually use the analogRead function from the Arduino’s wiring.c file because it does everything like we would if we were to code it ourselves.

Changes to main.c
//                  +-\/-+
// Ain0 (D 5) PB5  1|    |8  Vcc
// Ain3 (D 3) PB3  2|    |7  PB2 (D 2)  Ain1
// Ain2 (D 4) PB4  3|    |6  PB1 (D 1) pwm1
//            GND  4|    |5  PB0 (D 0) pwm0
//                  +----+

int thermistorPin = 1; // Analog input 1
int clockPin = 3; // Analog input 3
#define ledPin PB0 // Output
#define buttonPin PB4 // Input
#define dataPin PB1 // Output

#define F_CPU 1000000 // 1 MHz
#include <avr/io.h>
#include <avr/wdt.h>
#include <math.h>
#include <avr/eeprom.h>
#include <avr/interrupt.h>
#include <avr/sleep.h>
#include <util/delay.h>
#include "setup.c"

volatile boolean f_pin = 0; // Pin change variable

int functionSelect = 0;
int dataCount = 1;
int delayTime = -1;

We set our analog inputs as variables because the analogRead function doesn’t use the PBx mapping and then we use defines to map the led, button and data pins to the corresponding PBx ports.

int main(void) {

  setup();

  DDRB |= ((1<<ledPin) | (1<<dataPin)); // Set Outputs
  DDRB &= ~(1<<buttonPin); // Set Inputs

  // Pin interrupt setup
  sbi(GIMSK,PCIE); // Enable pin change interrupt
  sbi(PCMSK,PCINT4); // Apply to pin D4 (button)

We being main and just set our outputs/inputs and copy the pin interrupt setup we had before.

Now I’m going to only show the parts that we change, really there isn’t much to change.

while(1) {
  // Wait for input
  if (functionSelect == 0) {

  // Read delay time
  if (delayTime == -1) {
    delayTime = eeprom_read_byte((uint8_t*)0);
  ...

Instead of using EEPROM.read(0) we now use eeprom_read_byte.

// Always reset variables just in case
PORTB &= ~((1<<ledPin) | (1<<dataPin));

system_sleep();
...

Once again whenever we see anything like digitalWrite(ledPin, LOW) we can just write it like PORTB &= ~((1<<ledPin).

// First test we are connected to the Arduino
int clockState = analogRead(clockPin);
if (clockState >= 160) {
  int clockhighCount = 0;
  // Delay for 10 x 25ms = 250ms, check CLK is always high
  for (int x = 0; x < 10; x++) {
    _delay_ms(25);
    clockState = analogRead(clockPin);
    if (clockState >= 160) {
      clockhighCount++;
    }
    else {
      clockhighCount = 0;
    }
  }
  // CLK is high, now give the 250ms HIGH as an ok
  if (clockhighCount >= 10) {
    functionSelect = 3;
    PORTB |= (1<<dataPin); // ON
    _delay_ms(250);
    PORTB &= ~(1<<dataPin); // OFF
  }
...

Instead of using delay(25) we just use _delay_ms(25).

...
while (millis() < resetTimer + 1500) {
  buttonState = PINB & (1<<buttonPin);
  if (buttonState) {
    buttonCount++;
    while (buttonState && (millis() < resetTimer + 1500)) {
      buttonState = PINB & (1<<buttonPin);
      buttonPressed++;
      _delay_ms(50);
...

Instead of using digitalRead we use AND to check if the value of buttonPin is indeed set to 1 in PINB. For example, PINB could be 10101010 and buttonPin as 1000. We check if bit 3 is on and if it is then the result would be 1000, if it’s not on then we just get 0.

Now instead of using if (buttonState == HIGH) we can just use if (buttonState) because if it has anything other than 0 we know the button was pressed.

// Log Temperature
if (functionSelect == 1) {
  PORTB |= (1<<dataPin); // ON
  int tempValue = (int) Thermistor(analogRead(thermistorPin));
  PORTB &= ~(1<<dataPin); // OFF
...

We changed the int(Thermistor….) part to be in brackets before the call to Thermistor.

// Write to EEPROM
if (dataCount < 512) {
  eeprom_write_byte((uint8_t*)dataCount, tempStore);
  dataCount++;
  if (dataCount < 512) {
    eeprom_write_byte((uint8_t*)dataCount, 0); // So we know where to stop when extracting data
  }
...

Now to write to the EEPROM, we use eeprom_write_byte instead of EEPROM.write.

// Wait until CLK is low
long resetTimer = millis();
...
// Output the bit
boolean dataBit = dataByte & (1<<x);
if (dataBit) {
  PORTB |= (1<<dataPin);
}
else {
  PORTB &= ~(1<<dataPin);
}

We now use byte dataBit = dataByte & 1<<x instead of bitRead(dataByte, x) to read each bit from the dataByte variable. It’s the same thing that we were doing before when we were checking if the button was pressed.

Summary of the changes

There were other changes but it would be too long to list them and they were same things we were doing above. In short the things that we changed were:

  • pinMode(x, OUTPUT) became DDRB |= (1<<x)
  • pinMode(x, INPUT) became DDRB &= ~(1<<x)
  • EEPROM.read(x) became eeprom_read_byte((uint8_t*)x)
  • EEPROM.write(x, y) became eeprom_write_byte((uint8_t*)x, y);
  • delay(x) became _delay_ms(x)
  • digitalWrite(x, LOW) became PORTB &= ~(1<<x)
  • digitalWrite(x, HIGH) became PORTB |= (1<<x)
  • digitalRead(x) became PINB & (1<<x)
  • if (x == HIGH) became if (x)
  • bitRead(x, y) became x & 1<<y

We have changed the Standalone Temperature Logger from using the Arduino software to WinAVR and it was pretty simple to do too. We’ve also saved 542 bytes when it’s compiled which brings us down to 3,678 bytes so the code is now able to fit in the ATtiny45 although you’d only have 256bytes of EEPROM vs 512bytes.

4 Responses to “Convert Standalone Temperature Logger code to WinAVR”

  1. ptichki_pichuzhki says:

    Just met an article (sorry, it’s in Russian) discussing the quality of internal reference voltage in AVR chips (as far as I got your project relies upon this voltage as it measures the resistance (voltage) of a thermal resistor). So, basically, the article says you definitely need a stabilized power source. By the way, according to specs, tiny85 also has a built in thermosensor. However, people say, it needs to be calibrated, and even then it offers +/-10! degrees accuracy – so it is better to say it’s useless.
    So, why not converting the whole project to DS1820 family? They are digital, they are calibrated, and the can be powered from 2.8v, although in this case their accuracy will be less than 0.5degrees…

    • Alex says:

      I just checked the price of the DS1820… about the cost of 2-3 ATtiny85s in Australia, wow.

      Here are the reasons I won’t use them:
      – Price (this project should be cheap to build, thermistor only costs 0.46 cents AU)
      – Don’t need the accuracy supplied by them, the thermistor I used is about -/+ 1 to 2 degrees (from my testing) which is good enough for this small project.

      I do agree that the internal reference voltages can vary however in this project we don’t use them, we just use the VCC of the battery as the reference. The ATtiny85 has two internal voltage references 1.1V and 2.56V, you have to be very careful when using them. The voltage reference means that is the maximum voltage that analogRead can take, so exceeding it would cause damage.

      For example:
      VCC is 3V and internal reference is set to 2.56V. We have a 10K thermistor connected from pin 6 to pin 7 and then a 10K resistor to ground, a typical voltage divider using the thermistor (we use this in our project). If you are at 25C degrees, the thermistor is 10K. We do an analogRead and it gives us the result as 1.5V.

      Now if the temperature rose to 70C degrees the value of the thermistor changes to 1.5K which would give us 2.6V with the voltage divider. When you do the analogRead that’s when you would damage the AVR because 2.56V reference is the maximum voltage that the port can accept when doing ADC.

      Using the voltage reference is good to use if you need more resolution to the ADC. For example, if you have a voltage of 0.538 applied to a analog pin and you want to see when it rises to 0.539 using 1.1V reference gives the most resolution.
      2.56V / 1024 = 0.0025 per division, you would only see 0.538 or 0.540
      1.1V / 1024 = 0.00107 per division, you would see both 0.538 and 0.539

  2. ptichki_pichuzhki says:

    By the way, it’s amazing to see such reduction in compiled code size! Is it just the difference between arduion’s compiler and that of winavr?

    • Alex says:

      Arduino actually uses WinAVR however it probably uses a different makefile than the WinAVR one. I think most of the size saving comes from not using all the extra things that the Arduino code adds on, an example is digitalWrite which does a lot more than just turn the pin on.

Leave a Reply to ptichki_pichuzhki