Refactor A/D conversion in adc.c
Now the necessary settings are in adc.h. Refactored to allow repeated ADC reads without reinitialization. Arduino allows setting analogReference, this is now also implemented. ADC is now initialized to sane values in apps/arduino/arduino-process.c dev/arduino/arduino-compat.h now has all hardware independent settings for arduino (some moved from platform/osd-merkur/dev/hw-arduino.h). turnOffPWM re-implemented with hw_timer, removed from wiring_digital.c ADC-specific arduino stuff moved to arduino-compat.h Arduinos wiring_analog no longer necessary. arduino-sketch example now reads analog inputs 1 and 5 using analogRead.
This commit is contained in:
parent
6c06f43417
commit
77c02d58f8
12 changed files with 154 additions and 199 deletions
|
@ -51,6 +51,7 @@
|
|||
|
||||
#include "arduino-process.h"
|
||||
#include "hw_timer.h"
|
||||
#include "adc.h"
|
||||
#include "hw-arduino.h"
|
||||
|
||||
PROCESS(arduino_sketch, "Arduino Sketch Wrapper");
|
||||
|
@ -60,6 +61,7 @@ PROCESS_THREAD(arduino_sketch, ev, data)
|
|||
PROCESS_BEGIN();
|
||||
|
||||
arduino_pwm_timer_init ();
|
||||
adc_init ();
|
||||
setup ();
|
||||
while (1) {
|
||||
loop ();
|
||||
|
|
|
@ -84,6 +84,7 @@ extern "C" {
|
|||
|
||||
#include "contiki.h"
|
||||
#include "hw_timer.h"
|
||||
#include "adc.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
|
@ -145,6 +146,43 @@ static inline void analogWrite(uint8_t pin, int val)
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* turnOffPWM of arduino is implemented by hw_timer
|
||||
*/
|
||||
#define turnOffPWM(atimer) \
|
||||
( (atimer) == NOT_ON_TIMER \
|
||||
? (void)0 \
|
||||
: (void)hwtimer_pwm_disable \
|
||||
(atimer >> HW_TIMER_SHIFT, atimer & HWT_CHANNEL_MASK) \
|
||||
)
|
||||
|
||||
/*
|
||||
* micros on arduino takes timer overflows into account.
|
||||
* We put in the seconds counter. To get a consistent seconds / ticks
|
||||
* value we have to disable interrupts.
|
||||
*/
|
||||
static inline uint32_t micros (void)
|
||||
{
|
||||
uint32_t ticks;
|
||||
uint8_t sreg = SREG;
|
||||
cli ();
|
||||
ticks = clock_seconds () * 1000000L
|
||||
+ clock_time () * 1000L / CLOCK_SECOND;
|
||||
SREG = sreg;
|
||||
return ticks;
|
||||
}
|
||||
/*
|
||||
* millis counts only internal timer ticks since start, not trying to do
|
||||
* something about overflows. Note that we don't try to emulate overflow
|
||||
* behaviour of arduino implementation.
|
||||
*/
|
||||
#define millis() (((uint32_t)clock_time())*1000L/CLOCK_SECOND)
|
||||
#define micros() (clock_seconds()*1000L+
|
||||
#define delay(ms) clock_delay_msec(ms)
|
||||
#define delayMicroseconds(us) clock_delay_usec(us)
|
||||
|
||||
#define analogRead(analogpin) readADC(analogpin)
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
|
|
@ -21,10 +21,15 @@
|
|||
#include "erbium.h"
|
||||
#include "er-coap-13.h"
|
||||
|
||||
extern uint8_t pwm;
|
||||
extern uint8_t period_100ms;
|
||||
extern uint8_t pwm;
|
||||
extern uint8_t period_100ms;
|
||||
extern uint16_t analog1_voltage;
|
||||
extern uint16_t analog5_voltage;
|
||||
|
||||
extern resource_t resource_led_pwm;
|
||||
extern resource_t resource_led_period;
|
||||
extern resource_t resource_analog1_voltage;
|
||||
extern resource_t resource_analog5_voltage;
|
||||
|
||||
#endif // led_pwm_h
|
||||
/** @} */
|
||||
|
|
|
@ -69,6 +69,38 @@ GENERIC_RESOURCE \
|
|||
, period_to_string
|
||||
);
|
||||
|
||||
size_t
|
||||
analog1_v (const char *name, uint8_t is_json, char *buf, size_t bufsize)
|
||||
{
|
||||
return snprintf
|
||||
(buf, bufsize, "%d.%03d", analog1_voltage / 1000, analog1_voltage % 1000);
|
||||
}
|
||||
|
||||
GENERIC_RESOURCE \
|
||||
( analog1_voltage, METHOD_GET
|
||||
, "analog/1"
|
||||
, Analog 1 voltage
|
||||
, V
|
||||
, NULL
|
||||
, analog1_v
|
||||
);
|
||||
|
||||
size_t
|
||||
analog5_v (const char *name, uint8_t is_json, char *buf, size_t bufsize)
|
||||
{
|
||||
return snprintf
|
||||
(buf, bufsize, "%d.%03d", analog5_voltage / 1000, analog5_voltage % 1000);
|
||||
}
|
||||
|
||||
GENERIC_RESOURCE \
|
||||
( analog5_voltage, METHOD_GET
|
||||
, "analog/5"
|
||||
, Analog 5 voltage
|
||||
, V
|
||||
, NULL
|
||||
, analog5_v
|
||||
);
|
||||
|
||||
/*
|
||||
* VI settings, see coding style
|
||||
* ex:ts=8:et:sw=2
|
||||
|
|
|
@ -15,8 +15,10 @@ extern "C" {
|
|||
#include "led_pwm.h"
|
||||
#define LED_PIN 5
|
||||
|
||||
uint8_t pwm = 128;
|
||||
uint8_t period_100ms = 10; /* one second */
|
||||
uint8_t pwm = 128;
|
||||
uint8_t period_100ms = 10; /* one second */
|
||||
uint16_t analog1_voltage = 0;
|
||||
uint16_t analog5_voltage = 0;
|
||||
}
|
||||
|
||||
void setup (void)
|
||||
|
@ -24,12 +26,16 @@ void setup (void)
|
|||
rest_init_engine ();
|
||||
rest_activate_resource (&resource_led_pwm);
|
||||
rest_activate_resource (&resource_led_period);
|
||||
rest_activate_resource (&resource_analog1_voltage);
|
||||
rest_activate_resource (&resource_analog5_voltage);
|
||||
}
|
||||
|
||||
void loop (void)
|
||||
{
|
||||
/* Use 255 - pwm, LED on merkur-board is wired to +3.3V */
|
||||
analogWrite (LED_PIN, 255 - pwm);
|
||||
analog1_voltage = analogRead (1) * 1600L / 1023L;
|
||||
analog5_voltage = analogRead (5) * 1600L / 1023L;
|
||||
printf ("clock : %u\nmillis: %lu\n", clock_time (), millis ());
|
||||
delay (period_100ms * 100);
|
||||
analogWrite (LED_PIN, 255); /* OFF: LED on merkur-board is wired to +3.3V */
|
||||
|
|
|
@ -27,7 +27,7 @@ CONTIKI_TARGET_SOURCEFILES += servo.c servo-sensor.c
|
|||
#Needed for Relay 1 to 4
|
||||
CONTIKI_TARGET_SOURCEFILES += relay.c relay-sensor.c
|
||||
# Arduino
|
||||
CONTIKI_TARGET_SOURCEFILES += wiring_digital.c wiring_analog.c
|
||||
CONTIKI_TARGET_SOURCEFILES += wiring_digital.c
|
||||
|
||||
CONTIKIBOARD=.
|
||||
BOOTLOADER_START = 0x1F000
|
||||
|
|
|
@ -42,15 +42,8 @@ extern "C"{
|
|||
#define FALLING 2
|
||||
#define RISING 3
|
||||
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
#define INTERNAL1V1 2
|
||||
#define INTERNAL2V56 3
|
||||
#elif defined(__AVR_ATmega128RFA1__)
|
||||
#else
|
||||
#define INTERNAL 3
|
||||
#endif
|
||||
#define DEFAULT 1
|
||||
#define EXTERNAL 0
|
||||
#define DEFAULT ADC_DEFAULT
|
||||
#define EXTERNAL ADC_EXTERNAL
|
||||
|
||||
// undefine stdlib's abs if encountered
|
||||
#ifdef abs
|
||||
|
@ -85,18 +78,9 @@ typedef unsigned int word;
|
|||
typedef uint8_t boolean;
|
||||
typedef uint8_t byte;
|
||||
|
||||
/*
|
||||
* This has been renamed from init to arduino_init, the original
|
||||
* function name is way too generic. The arduino compatibility framework
|
||||
* makes sure the correct function is called.
|
||||
*/
|
||||
void arduino_init(void);
|
||||
|
||||
void pinMode(uint8_t, uint8_t);
|
||||
void digitalWrite(uint8_t, uint8_t);
|
||||
int digitalRead(uint8_t);
|
||||
int analogRead(uint8_t);
|
||||
void analogReference(uint8_t mode);
|
||||
|
||||
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout);
|
||||
|
||||
|
|
|
@ -36,33 +36,28 @@
|
|||
* Paulo Louro <paulolouro@binarylabs.dk>
|
||||
*/
|
||||
|
||||
#include <avr/io.h>
|
||||
#include "adc.h"
|
||||
|
||||
#ifndef cbi
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif
|
||||
#ifndef sbi
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
static uint8_t analog_reference = ADC_DEFAULT;
|
||||
|
||||
/*
|
||||
* For arduino interface for setting external reference voltage
|
||||
* Note that applying an external voltage *and* then setting the analog
|
||||
* reference to something internal will short the internal and the
|
||||
* external reference voltage and most likely destroy the processor.
|
||||
*/
|
||||
void analogReference(uint8_t mode)
|
||||
{
|
||||
analog_reference = mode;
|
||||
}
|
||||
|
||||
int readADC(uint8_t pin)
|
||||
{
|
||||
int result = 0;
|
||||
|
||||
if ( pin >= 14 )
|
||||
pin -= 14;
|
||||
|
||||
ADMUX = _BV(REFS1) | _BV(REFS0) | ( pin & 7 ) ;
|
||||
ADCSRA = _BV(ADEN) | _BV(ADPS0) | _BV(ADPS2) ;
|
||||
sbi(ADCSRA,ADSC);
|
||||
loop_until_bit_is_clear(ADCSRA,ADSC);
|
||||
|
||||
|
||||
result = ADC;
|
||||
|
||||
ADCSRA=0; //disable ADC
|
||||
ADMUX=0; //turn off internal vref
|
||||
|
||||
adc_setup (analog_reference, pin);
|
||||
result = adc_read ();
|
||||
adc_fin ();
|
||||
return result;
|
||||
}
|
||||
|
||||
|
@ -77,13 +72,13 @@ int readInternalTemp(void)
|
|||
ADMUX = _BV(REFS1) | _BV(REFS0) | 0b1001 ;
|
||||
ADCSRA = _BV(ADEN) | _BV(ADPS0) | _BV(ADPS2) ;
|
||||
|
||||
sbi(ADCSRA,ADSC);
|
||||
ADCSRA |= 1 << ADSC;
|
||||
loop_until_bit_is_clear(ADCSRA,ADSC);
|
||||
reading = ADC;
|
||||
|
||||
ADCSRB=0; //disable ADC, need to write B first for MUX5 bit
|
||||
ADCSRA=0; //disable ADC
|
||||
ADCSRB=0; //disable ADC
|
||||
ADMUX=0; //turn off internal vref
|
||||
|
||||
return reading * 113 - 27280;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,8 +1,52 @@
|
|||
#ifndef __ADC_ARCH_H__
|
||||
#define __ADC_ARCH_H__
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
/*
|
||||
* Reference voltage
|
||||
* The default is 1.6V reference voltage
|
||||
* The selected reference voltage is the maximum voltage that can be
|
||||
* measured.
|
||||
* Directly provide shifted variants so we don't need to shift.
|
||||
*/
|
||||
#define ADC_1_5 (2<<6)
|
||||
#define ADC_1_6 (3<<6)
|
||||
#define ADC_1_8 (1<<6)
|
||||
#define ADC_EXTERNAL (0<<6)
|
||||
#define ADC_DEFAULT ADC_1_6
|
||||
|
||||
/* sometimes it's desirable to decouple setup / finish from sampling */
|
||||
|
||||
static inline void adc_setup (uint8_t ref_volt, uint8_t pin)
|
||||
{
|
||||
ADMUX = ref_volt | (pin & 0x7);
|
||||
ADCSRA = _BV(ADEN) | _BV(ADPS0) | _BV(ADPS2);
|
||||
}
|
||||
|
||||
static inline int adc_read (void)
|
||||
{
|
||||
ADCSRA |= (1 << ADSC);
|
||||
loop_until_bit_is_clear (ADCSRA, ADSC);
|
||||
return ADC;
|
||||
}
|
||||
|
||||
static inline void adc_fin (void)
|
||||
{
|
||||
ADCSRA = 0;
|
||||
ADMUX = 0;
|
||||
}
|
||||
|
||||
static inline void adc_init (void)
|
||||
{
|
||||
ADCSRC = 0;
|
||||
ADCSRB = 0;
|
||||
adc_fin ();
|
||||
}
|
||||
|
||||
int readADC(uint8_t pin);
|
||||
long readVcc();
|
||||
int readInternalTemp(void);
|
||||
void analogReference(uint8_t mode);
|
||||
|
||||
#endif /* __ADC_ARCH_H__ */
|
||||
#endif /* __ADC_ARCH_H__ */
|
||||
|
|
|
@ -71,32 +71,6 @@ extern "C"{
|
|||
#define arduino_pwm_timer_init() \
|
||||
(hwtimer_ini (3, HWT_WGM_PWM_PHASE_8_BIT, HWT_CLOCK_PRESCALER_64, 0))
|
||||
|
||||
/*
|
||||
* micros on arduino takes timer overflows into account.
|
||||
* We put in the seconds counter. To get a consistent seconds / ticks
|
||||
* value we have to disable interrupts.
|
||||
*/
|
||||
static inline uint32_t micros (void)
|
||||
{
|
||||
uint32_t ticks;
|
||||
uint8_t sreg = SREG;
|
||||
cli ();
|
||||
ticks = clock_seconds () * 1000000L
|
||||
+ clock_time () * 1000L / CLOCK_SECOND;
|
||||
SREG = sreg;
|
||||
return ticks;
|
||||
}
|
||||
/*
|
||||
* millis counts only internal timer ticks since start, not trying to do
|
||||
* something about overflows. Note that we don't try to emulate overflow
|
||||
* behaviour of arduino implementation.
|
||||
*/
|
||||
#define millis() (((uint32_t)clock_time())*1000L/CLOCK_SECOND)
|
||||
#define micros() (clock_seconds()*1000L+
|
||||
#define delay(ms) clock_delay_msec(ms)
|
||||
#define delayMicroseconds(us) clock_delay_usec(us)
|
||||
|
||||
|
||||
/*
|
||||
* VI settings, see coding style
|
||||
* ex:ts=8:et:sw=2
|
||||
|
|
|
@ -1,48 +0,0 @@
|
|||
/*
|
||||
wiring_analog.c - analog input and output
|
||||
Part of Arduino - http://www.arduino.cc/
|
||||
|
||||
Copyright (c) 2005-2006 David A. Mellis
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General
|
||||
Public License along with this library; if not, write to the
|
||||
Free Software Foundation, Inc., 59 Temple Place, Suite 330,
|
||||
Boston, MA 02111-1307 USA
|
||||
|
||||
Modified 28 September 2010 by Mark Sproul
|
||||
|
||||
$Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
|
||||
*/
|
||||
|
||||
#include "wiring_private.h"
|
||||
#include "pins_arduino.h"
|
||||
#include "adc.h"
|
||||
|
||||
uint8_t analog_reference = DEFAULT;
|
||||
|
||||
void analogReference(uint8_t mode)
|
||||
{
|
||||
// can't actually set the register here because the default setting
|
||||
// will connect AVCC and the AREF pin, which would cause a short if
|
||||
// there's something connected to AREF.
|
||||
analog_reference = mode;
|
||||
}
|
||||
|
||||
int analogRead(uint8_t pin)
|
||||
{
|
||||
return readADC(pin);
|
||||
}
|
||||
|
||||
/*
|
||||
* analogWrite is now implemented in dev/arduino/arduino-compat.h
|
||||
*/
|
|
@ -60,83 +60,6 @@ void pinMode(uint8_t pin, uint8_t mode)
|
|||
}
|
||||
}
|
||||
|
||||
// Forcing this inline keeps the callers from having to push their own stuff
|
||||
// on the stack. It is a good performance win and only takes 1 more byte per
|
||||
// user than calling. (It will take more bytes on the 168.)
|
||||
//
|
||||
// But shouldn't this be moved into pinMode? Seems silly to check and do on
|
||||
// each digitalread or write.
|
||||
//
|
||||
// Mark Sproul:
|
||||
// - Removed inline. Save 170 bytes on atmega1280
|
||||
// - changed to a switch statment; added 32 bytes but much easier to read and maintain.
|
||||
// - Added more #ifdefs, now compiles for atmega645
|
||||
//
|
||||
//static inline void turnOffPWM(uint8_t timer) __attribute__ ((always_inline));
|
||||
//static inline void turnOffPWM(uint8_t timer)
|
||||
static void turnOffPWM(uint8_t timer)
|
||||
{
|
||||
switch (timer)
|
||||
{
|
||||
#if defined(TCCR1A) && defined(COM1A1)
|
||||
case TIMER1A: cbi(TCCR1A, COM1A1); break;
|
||||
#endif
|
||||
#if defined(TCCR1A) && defined(COM1B1)
|
||||
case TIMER1B: cbi(TCCR1A, COM1B1); break;
|
||||
#endif
|
||||
#if defined(TCCR1A) && defined(COM1B1)
|
||||
case TIMER1C: cbi(TCCR1A, COM1C1); break;
|
||||
#endif
|
||||
|
||||
#if defined(TCCR2) && defined(COM21)
|
||||
case TIMER2: cbi(TCCR2, COM21); break;
|
||||
#endif
|
||||
|
||||
#if defined(TCCR0A) && defined(COM0A1)
|
||||
case TIMER0A: cbi(TCCR0A, COM0A1); break;
|
||||
#endif
|
||||
|
||||
#if defined(TIMER0B) && defined(COM0B1)
|
||||
case TIMER0B: cbi(TCCR0A, COM0B1); break;
|
||||
#endif
|
||||
#if defined(TCCR2A) && defined(COM2A1)
|
||||
case TIMER2A: cbi(TCCR2A, COM2A1); break;
|
||||
#endif
|
||||
#if defined(TCCR2A) && defined(COM2B1)
|
||||
case TIMER2B: cbi(TCCR2A, COM2B1); break;
|
||||
#endif
|
||||
|
||||
#if defined(TCCR3A) && defined(COM3A1)
|
||||
case TIMER3A: cbi(TCCR3A, COM3A1); break;
|
||||
#endif
|
||||
#if defined(TCCR3A) && defined(COM3B1)
|
||||
case TIMER3B: cbi(TCCR3A, COM3B1); break;
|
||||
#endif
|
||||
#if defined(TCCR3A) && defined(COM3C1)
|
||||
case TIMER3C: cbi(TCCR3A, COM3C1); break;
|
||||
#endif
|
||||
|
||||
#if defined(TCCR4A) && defined(COM4A1)
|
||||
case TIMER4A: cbi(TCCR4A, COM4A1); break;
|
||||
#endif
|
||||
#if defined(TCCR4A) && defined(COM4B1)
|
||||
case TIMER4B: cbi(TCCR4A, COM4B1); break;
|
||||
#endif
|
||||
#if defined(TCCR4A) && defined(COM4C1)
|
||||
case TIMER4C: cbi(TCCR4A, COM4C1); break;
|
||||
#endif
|
||||
#if defined(TCCR4C) && defined(COM4D1)
|
||||
case TIMER4D: cbi(TCCR4C, COM4D1); break;
|
||||
#endif
|
||||
|
||||
#if defined(TCCR5A)
|
||||
case TIMER5A: cbi(TCCR5A, COM5A1); break;
|
||||
case TIMER5B: cbi(TCCR5A, COM5B1); break;
|
||||
case TIMER5C: cbi(TCCR5A, COM5C1); break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void digitalWrite(uint8_t pin, uint8_t val)
|
||||
{
|
||||
uint8_t timer = digitalPinToTimer(pin);
|
||||
|
|
Loading…
Reference in a new issue