aboutsummaryrefslogtreecommitdiffstats
path: root/os
diff options
context:
space:
mode:
authorefti <efti@35acf78f-673a-0410-8e92-d51de3d6d3f4>2013-06-27 11:28:02 +0000
committerefti <efti@35acf78f-673a-0410-8e92-d51de3d6d3f4>2013-06-27 11:28:02 +0000
commit7880778f170553a2bbb5222d121bc95c6548eb51 (patch)
tree96256076cec60899dea63e229702b143eb8aae05 /os
parent848d54b242558cbbfe0e0d2e7b5de405cd203bae (diff)
downloadChibiOS-7880778f170553a2bbb5222d121bc95c6548eb51.tar.gz
ChibiOS-7880778f170553a2bbb5222d121bc95c6548eb51.tar.bz2
ChibiOS-7880778f170553a2bbb5222d121bc95c6548eb51.zip
AVR: improvements and fixes
- HAL prescaler selection logic - Added ADC support - SPI improvements git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@5893 35acf78f-673a-0410-8e92-d51de3d6d3f4
Diffstat (limited to 'os')
-rw-r--r--os/hal/platforms/AVR/adc_lld.c192
-rw-r--r--os/hal/platforms/AVR/adc_lld.h205
-rw-r--r--os/hal/platforms/AVR/atmega_pins.h45
-rw-r--r--os/hal/platforms/AVR/hal_lld.c39
-rw-r--r--os/hal/platforms/AVR/hal_lld.h47
-rw-r--r--os/hal/platforms/AVR/pal_lld.h17
-rw-r--r--os/hal/platforms/AVR/platform.dox16
-rw-r--r--os/hal/platforms/AVR/platform.mk1
-rw-r--r--os/hal/platforms/AVR/serial_lld.c63
-rw-r--r--os/hal/platforms/AVR/serial_lld.h12
-rw-r--r--os/hal/platforms/AVR/spi_lld.c141
-rw-r--r--os/hal/platforms/AVR/spi_lld.h25
12 files changed, 717 insertions, 86 deletions
diff --git a/os/hal/platforms/AVR/adc_lld.c b/os/hal/platforms/AVR/adc_lld.c
new file mode 100644
index 000000000..ee4c8a173
--- /dev/null
+++ b/os/hal/platforms/AVR/adc_lld.c
@@ -0,0 +1,192 @@
+/*
+ ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
+ 2011,2012 Giovanni Di Sirio.
+
+ This file is part of ChibiOS/RT.
+
+ ChibiOS/RT is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 3 of the License, or
+ (at your option) any later version.
+
+ ChibiOS/RT 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 General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/**
+ * @file templates/adc_lld.c
+ * @brief ADC Driver subsystem low level driver source template.
+ *
+ * @addtogroup ADC
+ * @{
+ */
+
+#include "ch.h"
+#include "hal.h"
+
+#if HAL_USE_ADC || defined(__DOXYGEN__)
+
+/*===========================================================================*/
+/* Driver local definitions. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Driver exported variables. */
+/*===========================================================================*/
+/** @brief ADC1 driver identifier.*/
+#if AVR_ADC_USE_ADC1 || defined(__DOXYGEN__)
+ADCDriver ADCD1;
+#endif
+/*===========================================================================*/
+/* Driver local variables. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Driver local functions. */
+/*===========================================================================*/
+
+static size_t getAdcChannelNumberFromMask(uint8_t mask, uint8_t currentChannel)
+{
+ for(uint8_t i = 0; mask>0; i++)
+ {
+ if(mask & 0x01)
+ {
+ if(!currentChannel)
+ return i;
+ currentChannel--;
+ }
+ mask >>= 1;
+ }
+
+ /* error, should never reach this line */
+}
+
+static void setAdcChannel(uint8_t channelNum)
+{
+ ADMUX = (ADMUX & 0xf8) | (channelNum & 0x07);
+}
+/*===========================================================================*/
+/* Driver interrupt handlers. */
+/*===========================================================================*/
+
+#include <util/delay.h>
+
+CH_IRQ_HANDLER(ADC_vect) {
+
+ CH_IRQ_PROLOGUE();
+ uint8_t low = ADCL;
+ uint8_t high = ADCH;
+ uint16_t result = (high << 8) | low;
+
+ ADCD1.samples[ADCD1.currentBufferPosition] = result;
+ ADCD1.currentBufferPosition++;
+
+ size_t bufferSize = ADCD1.depth * ADCD1.grpp->num_channels;
+ size_t currentChannel = ADCD1.currentBufferPosition % ADCD1.grpp->num_channels;
+ size_t currentIteration = ADCD1.currentBufferPosition / ADCD1.grpp->num_channels;
+ if(ADCD1.grpp-> circular && currentChannel == 0 && currentIteration == ADCD1.depth/2)
+ {
+ _adc_isr_half_code(&ADCD1);
+
+ }
+
+ if(ADCD1.currentBufferPosition == bufferSize)
+ {
+ _adc_isr_full_code(&ADCD1);
+ }
+ else
+ {
+
+ setAdcChannel(getAdcChannelNumberFromMask(ADCD1.grpp->channelsMask,currentChannel));
+ ADCSRA |= 1<<ADSC;
+ }
+
+ CH_IRQ_EPILOGUE();
+}
+
+/*===========================================================================*/
+/* Driver exported functions. */
+/*===========================================================================*/
+
+/**
+ * @brief Low level ADC driver initialization.
+ *
+ * @notapi
+ */
+void adc_lld_init(void) {
+ adcObjectInit(&ADCD1);
+ ADCSRA =(1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0) | //prescaler 128, unico valore possibile a 20Mhz
+ (1<<ADIE) ; //interrupt
+
+ ADCSRB=0; //single shot
+ ADMUX=(0<<REFS1)| (0<<REFS0); //uso aref, vale solo per arduino. arduino ha aref collegato
+}
+
+/**
+ * @brief Configures and activates the ADC peripheral.
+ *
+ * @param[in] adcp pointer to the @p ADCDriver object
+ *
+ * @notapi
+ */
+void adc_lld_start(ADCDriver *adcp) {
+
+ if (adcp->state == ADC_STOP) {
+ /* Clock activation.*/
+ ADCSRA |= (1<<ADEN);
+ }
+
+ if (adcp->config != NULL)
+ {
+ ADMUX = (adcp->config->analog_reference << REFS0);
+ }
+}
+
+/**
+ * @brief Deactivates the ADC peripheral.
+ *
+ * @param[in] adcp pointer to the @p ADCDriver object
+ *
+ * @notapi
+ */
+void adc_lld_stop(ADCDriver *adcp) {
+
+ if (adcp->state == ADC_READY) {
+ /* Clock de-activation.*/
+ ADCSRA &= ~(1<<ADEN);
+ }
+}
+
+/**
+ * @brief Starts an ADC conversion.
+ *
+ * @param[in] adcp pointer to the @p ADCDriver object
+ *
+ * @notapi
+ */
+void adc_lld_start_conversion(ADCDriver *adcp) {
+ adcp->currentBufferPosition=0;
+
+ setAdcChannel(getAdcChannelNumberFromMask(adcp->grpp->channelsMask,0));
+ ADCSRA |= 1<<ADSC;
+}
+
+/**
+ * @brief Stops an ongoing conversion.
+ *
+ * @param[in] adcp pointer to the @p ADCDriver object
+ *
+ * @notapi
+ */
+void adc_lld_stop_conversion(ADCDriver *adcp) {
+ ADCSRA &= ~(1<<ADSC);
+}
+
+#endif /* HAL_USE_ADC */
+
+/** @} */
diff --git a/os/hal/platforms/AVR/adc_lld.h b/os/hal/platforms/AVR/adc_lld.h
new file mode 100644
index 000000000..76e5fbe31
--- /dev/null
+++ b/os/hal/platforms/AVR/adc_lld.h
@@ -0,0 +1,205 @@
+/*
+ ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
+ 2011,2012 Giovanni Di Sirio.
+
+ This file is part of ChibiOS/RT.
+
+ ChibiOS/RT is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 3 of the License, or
+ (at your option) any later version.
+
+ ChibiOS/RT 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 General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/**
+ * @file templates/adc_lld.h
+ * @brief ADC Driver subsystem low level driver header template.
+ *
+ * @addtogroup ADC
+ * @{
+ */
+
+#ifndef _ADC_LLD_H_
+#define _ADC_LLD_H_
+
+#if HAL_USE_ADC || defined(__DOXYGEN__)
+
+/*===========================================================================*/
+/* Driver constants. */
+/*===========================================================================*/
+
+#define ANALOG_REFERENCE_AREF 0
+#define ANALOG_REFERENCE_AVCC 1
+#define ANALOG_REFERENCE_1V1 2
+#define ANALOG_REFERENCE_2V56 3
+
+
+
+/*===========================================================================*/
+/* Driver pre-compile time settings. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Derived constants and error checks. */
+/*===========================================================================*/
+
+#if !CH_USE_SEMAPHORES
+#error "the ADC driver requires CH_USE_SEMAPHORES"
+#endif
+
+/*===========================================================================*/
+/* Driver data structures and types. */
+/*===========================================================================*/
+
+/**
+ * @brief ADC sample data type.
+ */
+typedef uint16_t adcsample_t;
+
+/**
+ * @brief Channels number in a conversion group.
+ */
+typedef uint16_t adc_channels_num_t;
+
+/**
+ * @brief Type of a structure representing an ADC driver.
+ */
+typedef struct ADCDriver ADCDriver;
+
+/**
+ * @brief ADC notification callback type.
+ *
+ * @param[in] adcp pointer to the @p ADCDriver object triggering the
+ * callback
+ * @param[in] buffer pointer to the most recent samples data
+ * @param[in] n number of buffer rows available starting from @p buffer
+ */
+typedef void (*adccallback_t)(ADCDriver *adcp, adcsample_t *buffer, size_t n);
+
+/**
+ * @brief Conversion group configuration structure.
+ * @details This implementation-dependent structure describes a conversion
+ * operation.
+ * @note Implementations may extend this structure to contain more,
+ * architecture dependent, fields.
+ */
+typedef struct {
+ /**
+ * @brief Enables the circular buffer mode for the group.
+ */
+ bool_t circular;
+ /**
+ * @brief Number of the analog channels belonging to the conversion group.
+ */
+ adc_channels_num_t num_channels;
+ /**
+ * @brief Callback function associated to the group or @p NULL.
+ */
+ adccallback_t end_cb;
+ /* End of the mandatory fields.*/
+
+ uint8_t channelsMask;
+
+} ADCConversionGroup;
+
+/**
+ * @brief Driver configuration structure.
+ * @note Implementations may extend this structure to contain more,
+ * architecture dependent, fields.
+ * @note It could be empty on some architectures.
+ */
+typedef struct {
+ uint8_t analog_reference;
+} ADCConfig;
+
+/**
+ * @brief Structure representing an ADC driver.
+ * @note Implementations may extend this structure to contain more,
+ * architecture dependent, fields.
+ */
+struct ADCDriver {
+ /**
+ * @brief Driver state.
+ */
+ adcstate_t state;
+ /**
+ * @brief Current configuration data.
+ */
+ const ADCConfig *config;
+ /**
+ * @brief Current samples buffer pointer or @p NULL.
+ */
+ adcsample_t *samples;
+ /**
+ * @brief Current samples buffer depth or @p 0.
+ */
+ size_t depth;
+ /**
+ * @brief Current conversion group pointer or @p NULL.
+ */
+ const ADCConversionGroup *grpp;
+#if ADC_USE_WAIT || defined(__DOXYGEN__)
+ /**
+ * @brief Waiting thread.
+ */
+ Thread *thread;
+#endif /* ADC_USE_WAIT */
+#if ADC_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__)
+#if CH_USE_MUTEXES || defined(__DOXYGEN__)
+ /**
+ * @brief Mutex protecting the peripheral.
+ */
+ Mutex mutex;
+#elif CH_USE_SEMAPHORES
+ Semaphore semaphore;
+#endif
+#endif /* ADC_USE_MUTUAL_EXCLUSION */
+#if defined(ADC_DRIVER_EXT_FIELDS)
+ ADC_DRIVER_EXT_FIELDS
+#endif
+ /* End of the mandatory fields.*/
+ /**
+ * @brief Current position in the buffer.
+ */
+ size_t currentBufferPosition;
+};
+
+/*===========================================================================*/
+/* Driver macros. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* External declarations. */
+/*===========================================================================*/
+
+#if AVR_ADC_USE_ADC1 && !defined(__DOXYGEN__)
+extern ADCDriver ADCD1;
+#endif
+
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+ void adc_lld_init(void);
+ void adc_lld_start(ADCDriver *adcp);
+ void adc_lld_stop(ADCDriver *adcp);
+ void adc_lld_start_conversion(ADCDriver *adcp);
+ void adc_lld_stop_conversion(ADCDriver *adcp);
+#ifdef __cplusplus
+}
+#endif
+
+
+
+#endif /* HAL_USE_ADC */
+
+#endif /* _ADC_LLD_H_ */
+
+/** @} */
diff --git a/os/hal/platforms/AVR/atmega_pins.h b/os/hal/platforms/AVR/atmega_pins.h
new file mode 100644
index 000000000..bf2479b34
--- /dev/null
+++ b/os/hal/platforms/AVR/atmega_pins.h
@@ -0,0 +1,45 @@
+
+#include <avr/io.h>
+#ifndef ATMEGA_PINS_H
+#define ATMEGA_PINS_H
+
+ #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__)
+ #define PINADC PINA
+ #define PORTADC PORTA
+ #define DDRADC DDRA
+ #define PIN_SPI1 PINB
+ #define PORT_SPI1 PORTB
+ #define DDR_SPI1 DDRB
+ #define SPI1_SS 4
+ #define SPI1_SCK 7
+ #define SPI1_MOSI 5
+ #define SPI1_MISO 6
+
+ #elif defined(__AVR_ATmega328P__)
+ #define PINADC PINC
+ #define PORTADC PORTC
+ #define DDRADC DDRC
+ #define PIN_SPI1 PINB
+ #define PORT_SPI1 PORTB
+ #define DDR_SPI1 DDRB
+ #define SPI1_SS 2
+ #define SPI1_SCK 5
+ #define SPI1_MOSI 3
+ #define SPI1_MISO 4
+
+ #elif defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega128__)
+ #define PINADC PINF
+ #define PORTADC PORTF
+ #define DDRADC DDRF
+ #define PIN_SPI1 PINB
+ #define PORT_SPI1 PORTB
+ #define DDR_SPI1 DDRB
+ #define SPI1_SS 0
+ #define SPI1_SCK 1
+ #define SPI1_MOSI 2
+ #define SPI1_MISO 3
+ #else
+ #warning "Device not supported by ADC or SPI driver"
+ #endif
+
+#endif
diff --git a/os/hal/platforms/AVR/hal_lld.c b/os/hal/platforms/AVR/hal_lld.c
index e01e291d9..dbe870534 100644
--- a/os/hal/platforms/AVR/hal_lld.c
+++ b/os/hal/platforms/AVR/hal_lld.c
@@ -41,6 +41,21 @@
/* Driver interrupt handlers. */
/*===========================================================================*/
+/**
+ * @brief Timer0 interrupt handler.
+ */
+CH_IRQ_HANDLER(AVR_TIMER_VECT) {
+
+ CH_IRQ_PROLOGUE();
+
+ chSysLockFromIsr();
+ chSysTimerHandlerI();
+ chSysUnlockFromIsr();
+
+ CH_IRQ_EPILOGUE();
+}
+
+
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
@@ -52,6 +67,30 @@
*/
void hal_lld_init(void) {
+ /*
+ * Timer 0 setup.
+ */
+#ifdef TCCR0A /* Timer has multiple output comparators */
+ TCCR0A = (1 << WGM01) | (0 << WGM00) | /* CTC mode. */
+ (0 << COM0A1) | (0 << COM0A0) | /* OC0A disabled. */
+ (0 << COM0B1) | (0 << COM0B0); /* OC0B disabled. */
+ TCCR0B = (0 << WGM02) | AVR_TIMER_PRESCALER_BITS; /* CTC mode. */
+ OCR0A = AVR_TIMER_COUNTER - 1;
+ TCNT0 = 0; /* Reset counter. */
+ TIFR0 = (1 << OCF0A); /* Reset pending. */
+ TIMSK0 = (1 << OCIE0A); /* IRQ on compare. */
+
+#elif defined(TCCR0) /* Timer has single output comparator */
+ TCCR0 = (1 << WGM01) | (0 << WGM00) | /* CTC mode. */
+ (0 << COM01) | (0 << COM00) | /* OC0A disabled. */
+ AVR_TIMER_PRESCALER_BITS;
+ OCR0 = AVR_TIMER_COUNTER - 1;
+ TCNT0 = 0; /* Reset counter. */
+ TIFR = (1 << OCF0); /* Reset pending. */
+ TIMSK = (1 << OCIE0); /* IRQ on compare. */
+#else
+ #error "Neither TCCR0A nor TCCRO registers are defined"
+#endif
}
/** @} */
diff --git a/os/hal/platforms/AVR/hal_lld.h b/os/hal/platforms/AVR/hal_lld.h
index fd99a70aa..d2dae48bd 100644
--- a/os/hal/platforms/AVR/hal_lld.h
+++ b/os/hal/platforms/AVR/hal_lld.h
@@ -37,16 +37,61 @@
/**
* @brief Platform name.
*/
-#define PLATFORM_NAME "ATmega128"
+#define PLATFORM_NAME "AVR"
+
+/**
+ * @brief Timer maximum value
+ */
+#define AVR_TIMER_COUNTER_MAX 255
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
+/* Work out what the timer interrupt is called on this MCU */
+#ifdef TIMER0_COMPA_vect
+ #define AVR_TIMER_VECT TIMER0_COMPA_vect
+#elif defined(TIMER_COMPA_vect)
+ #define AVR_TIMER_VECT TIMER_COMPA_vect
+#elif defined(TIMER0_COMP_vect)
+ #define AVR_TIMER_VECT TIMER0_COMP_vect
+#else
+ #error "Cannot find interrupt vector name for timer"
+#endif
+
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
+/* Find the most suitable prescaler setting for the desired CH_FREQUENCY */
+#if ((F_CPU / CH_FREQUENCY) <= AVR_TIMER_COUNTER_MAX)
+ #define AVR_TIMER_PRESCALER 1
+ #define AVR_TIMER_PRESCALER_BITS (0 << CS02) | (0 << CS01) | (1 << CS00); /* CLK */
+#elif ((F_CPU / CH_FREQUENCY / 8) <= AVR_TIMER_COUNTER_MAX)
+ #define AVR_TIMER_PRESCALER 8
+ #define AVR_TIMER_PRESCALER_BITS (0 << CS02) | (1 << CS01) | (0 << CS00); /* CLK/8 */
+#elif ((F_CPU / CH_FREQUENCY / 64) <= AVR_TIMER_COUNTER_MAX)
+ #define AVR_TIMER_PRESCALER 64
+ #define AVR_TIMER_PRESCALER_BITS (0 << CS02) | (1 << CS01) | (1 << CS00); /* CLK/64 */
+#elif ((F_CPU / CH_FREQUENCY / 256) <= AVR_TIMER_COUNTER_MAX)
+ #define AVR_TIMER_PRESCALER 256
+ #define AVR_TIMER_PRESCALER_BITS (1 << CS02) | (0 << CS01) | (0 << CS00); /* CLK/256 */
+#elif ((F_CPU / CH_FREQUENCY / 1024) <= AVR_TIMER_COUNTER_MAX)
+ #define AVR_TIMER_PRESCALER 1024
+ #define AVR_TIMER_PRESCALER_BITS (1 << CS02) | (0 << CS01) | (1 << CS00); /* CLK/1024 */
+#else
+ #error "Frequency too low for timer, please set CH_FREQUENCY to a higher value"
+#endif
+
+#define AVR_TIMER_COUNTER F_CPU / CH_FREQUENCY / AVR_TIMER_PRESCALER
+
+/* Test if CH_FREQUENCY can be matched exactly using this timer */
+#define F_CPU_ (AVR_TIMER_COUNTER * AVR_TIMER_PRESCALER * CH_FREQUENCY)
+#if (F_CPU_ != F_CPU)
+ #warning "CH_FREQUENCY cannot be generated exactly using timer"
+#endif
+#undef F_CPU_
+
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
diff --git a/os/hal/platforms/AVR/pal_lld.h b/os/hal/platforms/AVR/pal_lld.h
index f48b51ec3..247d9dfb9 100644
--- a/os/hal/platforms/AVR/pal_lld.h
+++ b/os/hal/platforms/AVR/pal_lld.h
@@ -25,6 +25,8 @@
#ifndef _PAL_LLD_H_
#define _PAL_LLD_H_
+#include "atmega_pins.h"
+
#if HAL_USE_PAL || defined(__DOXYGEN__)
/*===========================================================================*/
@@ -211,6 +213,21 @@ typedef avr_gpio_registers_t *ioportid_t;
#define IOPORT11 ((volatile avr_gpio_registers_t *)&PINL)
#endif
+#if defined(PORTADC) || defined(__DOXYGEN__)
+/**
+ * @brief GPIO port ADC identifier.
+ */
+#define IOPORTADC ((volatile avr_gpio_registers_t *)&PINADC)
+#endif
+
+#if defined(PORT_SPI1) || defined(__DOXYGEN__)
+/**
+ * @brief GPIO port SPI1 identifier.
+ */
+#define IOPORTSPI1 ((volatile avr_gpio_registers_t *)&PIN_SPI1)
+#endif
+
+
/*===========================================================================*/
/* Implementation, some of the following macros could be implemented as */
/* functions, if so please put them in pal_lld.c. */
diff --git a/os/hal/platforms/AVR/platform.dox b/os/hal/platforms/AVR/platform.dox
index f012d6f66..c7d636fd8 100644
--- a/os/hal/platforms/AVR/platform.dox
+++ b/os/hal/platforms/AVR/platform.dox
@@ -98,6 +98,18 @@
*/
/**
+ * @defgroup AVR_ADC AVR ADC Support
+ * @details The AVR ADC driver uses the ADC and ADCMUX peripherals
+ * in an interrupt driven, one-shot or multiple shot implementation.
+ *
+ * @section avr_adc Supported HW resources
+ * The i2c driver can support the following hardware resource:
+ * - ADC.
+ * .
+ * @ingroup AVR_DRIVERS
+ */
+
+/**
* @defgroup AVR_I2C AVR I2C Support
* @details The AVR I2C driver uses the TWI peripheral in an interrupt
* driven, implementation.
@@ -112,7 +124,9 @@
/**
* @defgroup AVR_SPI AVR SPI Support
* @details The AVR SPI driver uses the SPI peripheral (USART in SPI mode
- * is not supported). It is an interrupt driven implementation.
+ * is not supported). It works as an interrupt driven implementation but
+ * a polled mode is available for 8 bit or 16 bit messages. Both master
+ * and slave mode are supported.
*
* @section avr_spi Supported HW resources
* The spi driver can support the following hardware resource:
diff --git a/os/hal/platforms/AVR/platform.mk b/os/hal/platforms/AVR/platform.mk
index 79e2235f0..42505fea2 100644
--- a/os/hal/platforms/AVR/platform.mk
+++ b/os/hal/platforms/AVR/platform.mk
@@ -2,6 +2,7 @@
PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/AVR/hal_lld.c \
${CHIBIOS}/os/hal/platforms/AVR/pal_lld.c \
${CHIBIOS}/os/hal/platforms/AVR/serial_lld.c \
+ ${CHIBIOS}/os/hal/platforms/AVR/adc_lld.c \
${CHIBIOS}/os/hal/platforms/AVR/i2c_lld.c \
${CHIBIOS}/os/hal/platforms/AVR/spi_lld.c
diff --git a/os/hal/platforms/AVR/serial_lld.c b/os/hal/platforms/AVR/serial_lld.c
index 0b6127bb6..a60074252 100644
--- a/os/hal/platforms/AVR/serial_lld.c
+++ b/os/hal/platforms/AVR/serial_lld.c
@@ -36,18 +36,37 @@
* @note The name does not follow the convention used in the other ports
* (COMn) because a name conflict with the AVR headers.
*/
-#if USE_AVR_USART0 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART0 || defined(__DOXYGEN__)
SerialDriver SD1;
-#endif
+
+ /* USARTs are not consistently named across the AVR range */
+ #ifdef USART0_RX_vect
+ #define AVR_SD1_RX_VECT USART0_RX_vect
+ #define AVR_SD1_TX_VECT USART0_UDRE_vect
+ #elif defined(USART_RX_vect)
+ #define AVR_SD1_RX_VECT USART_RX_vect
+ #define AVR_SD1_TX_VECT USART_UDRE_vect
+ #else
+ #error "Cannot find USART to use for SD1"
+ #endif
+#endif /* AVR_SERIAL_USE_USART0 */
/**
* @brief USART1 serial driver identifier.
* @note The name does not follow the convention used in the other ports
* (COMn) because a name conflict with the AVR headers.
*/
-#if USE_AVR_USART1 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART1 || defined(__DOXYGEN__)
SerialDriver SD2;
-#endif
+
+ /* Check if USART1 exists for this MCU */
+ #ifdef USART1_RX_vect
+ #define AVR_SD2_RX_VECT USART1_RX_vect
+ #define AVR_SD2_TX_VECT USART1_UDRE_vect
+ #else
+ #error "Cannot find USART to use for SD2"
+ #endif
+#endif /* AVR_SERIAL_USE_USART1 */
/*===========================================================================*/
/* Driver local variables and types. */
@@ -71,7 +90,7 @@ static void set_error(uint8_t sra, SerialDriver *sdp) {
uint8_t upe = 0;
uint8_t fe = 0;
-#if USE_AVR_USART0
+#if AVR_SERIAL_USE_USART0
if (&SD1 == sdp) {
dor = (1 << DOR0);
upe = (1 << UPE0);
@@ -79,7 +98,7 @@ static void set_error(uint8_t sra, SerialDriver *sdp) {
}
#endif
-#if USE_AVR_USART1
+#if AVR_SERIAL_USE_USART1
if (&SD2 == sdp) {
dor = (1 << DOR1);
upe = (1 << UPE1);
@@ -98,7 +117,7 @@ static void set_error(uint8_t sra, SerialDriver *sdp) {
chSysUnlockFromIsr();
}
-#if USE_AVR_USART0 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART0 || defined(__DOXYGEN__)
static void notify1(GenericQueue *qp) {
(void)qp;
@@ -147,7 +166,7 @@ static void usart0_deinit(void) {
}
#endif
-#if USE_AVR_USART1 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART1 || defined(__DOXYGEN__)
static void notify2(GenericQueue *qp) {
(void)qp;
@@ -200,13 +219,13 @@ static void usart1_deinit(void) {
/* Driver interrupt handlers. */
/*===========================================================================*/
-#if USE_AVR_USART0 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART0 || defined(__DOXYGEN__)
/**
* @brief USART0 RX interrupt handler.
*
* @isr
*/
-CH_IRQ_HANDLER(USART0_RX_vect) {
+CH_IRQ_HANDLER(AVR_SD1_RX_VECT) {
uint8_t sra;
CH_IRQ_PROLOGUE();
@@ -226,7 +245,7 @@ CH_IRQ_HANDLER(USART0_RX_vect) {
*
* @isr
*/
-CH_IRQ_HANDLER(USART0_UDRE_vect) {
+CH_IRQ_HANDLER(AVR_SD1_TX_VECT) {
msg_t b;
CH_IRQ_PROLOGUE();
@@ -241,15 +260,15 @@ CH_IRQ_HANDLER(USART0_UDRE_vect) {
CH_IRQ_EPILOGUE();
}
-#endif /* USE_AVR_USART0 */
+#endif /* AVR_SERIAL_USE_USART0 */
-#if USE_AVR_USART1 || defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART1 || defined(__DOXYGEN__)
/**
* @brief USART1 RX interrupt handler.
*
* @isr
*/
-CH_IRQ_HANDLER(USART1_RX_vect) {
+CH_IRQ_HANDLER(AVR_SD2_RX_VECT) {
uint8_t sra;
CH_IRQ_PROLOGUE();
@@ -269,7 +288,7 @@ CH_IRQ_HANDLER(USART1_RX_vect) {
*
* @isr
*/
-CH_IRQ_HANDLER(USART1_UDRE_vect) {
+CH_IRQ_HANDLER(AVR_SD2_TX_VECT) {
msg_t b;
CH_IRQ_PROLOGUE();
@@ -284,7 +303,7 @@ CH_IRQ_HANDLER(USART1_UDRE_vect) {
CH_IRQ_EPILOGUE();
}
-#endif /* USE_AVR_USART1 */
+#endif /* AVR_SERIAL_USE_USART1 */
/*===========================================================================*/
/* Driver exported functions. */
@@ -297,10 +316,10 @@ CH_IRQ_HANDLER(USART1_UDRE_vect) {
*/
void sd_lld_init(void) {
-#if USE_AVR_USART0
+#if AVR_SERIAL_USE_USART0
sdObjectInit(&SD1, NULL, notify1);
#endif
-#if USE_AVR_USART1
+#if AVR_SERIAL_USE_USART1
sdObjectInit(&SD2, NULL, notify2);
#endif
}
@@ -320,13 +339,13 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {
if (config == NULL)
config = &default_config;
-#if USE_AVR_USART0
+#if AVR_SERIAL_USE_USART0
if (&SD1 == sdp) {
usart0_init(config);
return;
}
#endif
-#if USE_AVR_USART1
+#if AVR_SERIAL_USE_USART1
if (&SD2 == sdp) {
usart1_init(config);
return;
@@ -345,11 +364,11 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {
*/
void sd_lld_stop(SerialDriver *sdp) {
-#if USE_AVR_USART0
+#if AVR_SERIAL_USE_USART0
if (&SD1 == sdp)
usart0_deinit();
#endif
-#if USE_AVR_USART1
+#if AVR_SERIAL_USE_USART1
if (&SD2 == sdp)
usart1_deinit();
#endif
diff --git a/os/hal/platforms/AVR/serial_lld.h b/os/hal/platforms/AVR/serial_lld.h
index 5a19befc7..18c6c1d56 100644
--- a/os/hal/platforms/AVR/serial_lld.h
+++ b/os/hal/platforms/AVR/serial_lld.h
@@ -40,8 +40,8 @@
* @details If set to @p TRUE the support for USART0 is included.
* @note The default is @p FALSE.
*/
-#if !defined(USE_AVR_USART0) || defined(__DOXYGEN__)
-#define USE_AVR_USART0 TRUE
+#if !defined(AVR_SERIAL_USE_USART0) || defined(__DOXYGEN__)
+ #define AVR_SERIAL_USE_USART0 TRUE
#endif
/**
@@ -49,8 +49,8 @@
* @details If set to @p TRUE the support for USART1 is included.
* @note The default is @p TRUE.
*/
-#if !defined(USE_AVR_USART1) || defined(__DOXYGEN__)
-#define USE_AVR_USART1 TRUE
+#if !defined(AVR_SERIAL_USE_USART1) || defined(__DOXYGEN__)
+#define AVR_SERIAL_USE_USART1 TRUE
#endif
/*===========================================================================*/
@@ -134,10 +134,10 @@ typedef struct {
/* External declarations. */
/*===========================================================================*/
-#if USE_AVR_USART0 && !defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART0 && !defined(__DOXYGEN__)
extern SerialDriver SD1;
#endif
-#if USE_AVR_USART1 && !defined(__DOXYGEN__)
+#if AVR_SERIAL_USE_USART1 && !defined(__DOXYGEN__)
extern SerialDriver SD2;
#endif
diff --git a/os/hal/platforms/AVR/spi_lld.c b/os/hal/platforms/AVR/spi_lld.c
index 124411a2b..8616068b4 100644
--- a/os/hal/platforms/AVR/spi_lld.c
+++ b/os/hal/platforms/AVR/spi_lld.c
@@ -42,8 +42,8 @@
/**
* @brief SPI1 driver identifier.
*/
-#if USE_AVR_SPI || defined(__DOXYGEN__)
-SPIDriver SPID;
+#if AVR_SPI_USE_SPI1 || defined(__DOXYGEN__)
+SPIDriver SPID1;
#endif
/*===========================================================================*/
@@ -58,7 +58,7 @@ SPIDriver SPID;
/* Driver interrupt handlers. */
/*===========================================================================*/
-#if USE_AVR_SPI || defined(__DOXYGEN__)
+#if AVR_SPI_USE_SPI1 || defined(__DOXYGEN__)
/**
* @brief SPI event interrupt handler.
*
@@ -67,44 +67,35 @@ SPIDriver SPID;
CH_IRQ_HANDLER(SPI_STC_vect) {
CH_IRQ_PROLOGUE();
- SPIDriver *spip = &SPID;
+ SPIDriver *spip = &SPID1;
- /* spi_lld_exchange */
- if (spip->rxbuf && spip->txbuf) {
- spip->rxbuf[spip->rxidx++] = SPDR;
- if (spip->rxidx == spip->rxbytes) {
- _spi_isr_code(spip);
+ /* spi_lld_exchange or spi_lld_receive */
+ if (spip->rxbuf && spip->rxidx < spip->rxbytes) {
+ spip->rxbuf[spip->rxidx++] = SPDR; // receive
+ }
+
+ /* spi_lld_exchange, spi_lld_send or spi_lld_ignore */
+ if (spip->txidx < spip->txbytes) {
+ if (spip->txbuf) {
+ SPDR = spip->txbuf[spip->txidx++]; // send
} else {
- SPDR = spip->txbuf[spip->txidx++];
+ SPDR = 0; spip->txidx++; // dummy send
}
+ }
+
/* spi_lld_send */
- } else if (spip->txbuf) {
- if (spip->txidx < spip->txbytes) {
- SPDR = spip->txbuf[spip->txidx++];
- } else {
- _spi_isr_code(spip);
- }
- /* spi_lld_receive */
- } else if (spip->rxbuf) {
- spip->rxbuf[spip->rxidx++] = SPDR;
- if (spip->rxidx < spip->rxbytes) {
- /* must keep clocking SCK */
- SPDR = 0;
- } else {
- _spi_isr_code(spip);
- }
- /* spi_lld_ignore */
- } else {
- if (spip->txidx < spip->txbytes) {
- SPDR = 0;
- } else {
- _spi_isr_code(spip);
- }
+ else if (spip->rxidx < spip->rxbytes) { /* rx not done */
+ SPDR = 0; // dummy send to keep the clock going
+ }
+
+ /* rx done and tx done */
+ if (spip->rxidx >= spip->rxbytes && spip->txidx >= spip->txbytes) {
+ _spi_isr_code(spip);
}
CH_IRQ_EPILOGUE();
}
-#endif /* USE_AVR_SPI */
+#endif /* AVR_SPI_USE_SPI1 */
/*===========================================================================*/
/* Driver exported functions. */
@@ -117,10 +108,10 @@ CH_IRQ_HANDLER(SPI_STC_vect) {
*/
void spi_lld_init(void) {
-#if USE_AVR_SPI
+#if AVR_SPI_USE_SPI1
/* Driver initialization.*/
- spiObjectInit(&SPID);
-#endif /* USE_AVR_SPI */
+ spiObjectInit(&SPID1);
+#endif /* AVR_SPI_USE_SPI1 */
}
/**
@@ -138,19 +129,31 @@ void spi_lld_start(SPIDriver *spip) {
if (spip->state == SPI_STOP) {
/* Enables the peripheral.*/
-#if USE_AVR_SPI
- if (&SPID == spip) {
- /* enable SPI clock */
+#if AVR_SPI_USE_SPI1
+ if (&SPID1 == spip) {
+ /* Enable SPI clock using Power Reduction Register */
+#if defined(PRR0)
PRR0 &= ~(1 << PRSPI);
+#elif defined(PRR)
+ PRR &= ~(1 << PRSPI);
+#endif
- /* SPI interrupt enable, SPI enable, Master mode */
- SPCR |= ((1 << SPE) | (1 << MSTR));
-
- spip->config->ssport->dir |= (1 << spip->config->sspad);
+ /* SPI enable, SPI interrupt enable */
+ SPCR |= ((1 << SPE) | (1 << SPIE));
- /* XXX: For SPI to work as master, MOSI/SCK must be
- * configured as outputs on your own code!
- */
+ switch (spip->config->role) {
+ case SPI_ROLE_SLAVE:
+ SPCR &= ~(1 << MSTR); /* master mode */
+ DDR_SPI1 |= (1 << SPI1_MISO); /* output */
+ DDR_SPI1 &= ~((1 << SPI1_MOSI) | (1 << SPI1_SCK) | (1 << SPI1_SS)); /* input */
+ break;
+ case SPI_ROLE_MASTER: /* fallthrough */
+ default:
+ SPCR |= (1 << MSTR); /* slave mode */
+ DDR_SPI1 |= ((1 << SPI1_MOSI) | (1 << SPI1_SCK)); /* output */
+ DDR_SPI1 &= ~(1 << SPI1_MISO); /* input */
+ spip->config->ssport->dir |= (1 << spip->config->sspad);
+ }
switch (spip->config->bitorder) {
case SPI_LSB_FIRST:
@@ -207,9 +210,10 @@ void spi_lld_start(SPIDriver *spip) {
/* dummy reads before enabling interrupt */
dummy = SPSR;
dummy = SPDR;
+ (void) dummy; /* suppress warning about unused variable */
SPCR |= (1 << SPIE);
}
-#endif /* USE_AVR_SPI */
+#endif /* AVR_SPI_USE_SPI1 */
}
}
@@ -226,12 +230,18 @@ void spi_lld_stop(SPIDriver *spip) {
/* Resets the peripheral.*/
/* Disables the peripheral.*/
-#if USE_AVR_SPI
- if (&SPID == spip) {
+#if AVR_SPI_USE_SPI1
+ if (&SPID1 == spip) {
SPCR &= ((1 << SPIE) | (1 << SPE));
spip->config->ssport->dir &= ~(1 << spip->config->sspad);
}
-#endif /* USE_AVR_SPI */
+/* Disable SPI clock using Power Reduction Register */
+#if defined(PRR0)
+ PRR0 |= (1 << PRSPI);
+#elif defined(PRR)
+ PRR |= (1 << PRSPI);
+#endif
+#endif /* AVR_SPI_USE_SPI1 */
}
}
@@ -243,7 +253,10 @@ void spi_lld_stop(SPIDriver *spip) {
* @notapi
*/
void spi_lld_select(SPIDriver *spip) {
-
+
+ /**
+ * NOTE: This should only be called in master mode
+ */
spip->config->ssport->out &= ~(1 << spip->config->sspad);
}
@@ -258,6 +271,9 @@ void spi_lld_select(SPIDriver *spip) {
*/
void spi_lld_unselect(SPIDriver *spip) {
+ /**
+ * NOTE: This should only be called in master mode
+ */
spip->config->ssport->out |= (1 << spip->config->sspad);
}
@@ -367,6 +383,7 @@ void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf) {
* @param[in] frame the data frame to send over the SPI bus
* @return The received data frame from the SPI bus.
*/
+#if AVR_SPI_USE_16BIT_POLLED_EXCHANGE
uint16_t spi_lld_polled_exchange(SPIDriver *spip, uint16_t frame) {
uint16_t spdr = 0;
@@ -385,10 +402,32 @@ uint16_t spi_lld_polled_exchange(SPIDriver *spip, uint16_t frame) {
dummy = SPSR;
dummy = SPDR;
+ (void) dummy; /* suppress warning about unused variable */
+ SPCR |= (1 << SPIE);
+
+ return spdr;
+}
+#else /* AVR_SPI_USE_16BIT_POLLED_EXCHANGE */
+uint8_t spi_lld_polled_exchange(SPIDriver *spip, uint8_t frame) {
+
+ uint8_t spdr = 0;
+ uint8_t dummy;
+
+ /* disable interrupt */
+ SPCR &= ~(1 << SPIE);
+
+ SPDR = frame;
+ while (!(SPSR & (1 << SPIF))) ;
+ spdr = SPDR;
+
+ dummy = SPSR;
+ dummy = SPDR;
+ (void) dummy; /* suppress warning about unused variable */
SPCR |= (1 << SPIE);
return spdr;
}
+#endif /* AVR_SPI_USE_16BIT_POLLED_EXCHANGE */
#endif /* HAL_USE_SPI */
diff --git a/os/hal/platforms/AVR/spi_lld.h b/os/hal/platforms/AVR/spi_lld.h
index 136ca3ba1..ef4953881 100644
--- a/os/hal/platforms/AVR/spi_lld.h
+++ b/os/hal/platforms/AVR/spi_lld.h
@@ -36,6 +36,10 @@
/*===========================================================================*/
/** @brief SPI Mode (Polarity/Phase) */
+#define SPI_ROLE_MASTER 0
+#define SPI_ROLE_SLAVE 1
+
+/** @brief SPI Mode (Polarity/Phase) */
#define SPI_CPOL0_CPHA0 0
#define SPI_CPOL0_CPHA1 1
#define SPI_CPOL1_CPHA0 2
@@ -71,8 +75,8 @@
* @brief SPI driver enable switch.
* @details If set to @p TRUE the support for SPI1 is included.
*/
-#if !defined(USE_AVR_SPI) || defined(__DOXYGEN__)
-#define USE_AVR_SPI FALSE
+#if !defined(AVR_SPI_USE_SPI1) || defined(__DOXYGEN__)
+#define AVR_SPI_USE_SPI1 FALSE
#endif
/** @} */
@@ -104,6 +108,10 @@ typedef void (*spicallback_t)(SPIDriver *spip);
*/
typedef struct {
/**
+ * @brief Role: Master or Slave
+ */
+ uint8_t role;
+ /**
* @brief Port used of Slave Select
*/
ioportid_t ssport;
@@ -166,7 +174,7 @@ struct SPIDriver {
/**
* @brief Pointer to the buffer with data to send.
*/
- const uint8_t *txbuf;
+ uint8_t *txbuf;
/**
* @brief Number of bytes of data to send.
*/
@@ -197,8 +205,8 @@ struct SPIDriver {
/* External declarations. */
/*===========================================================================*/
-#if USE_AVR_SPI && !defined(__DOXYGEN__)
-extern SPIDriver SPID;
+#if AVR_SPI_USE_SPI1 && !defined(__DOXYGEN__)
+extern SPIDriver SPID1;
#endif
#ifdef __cplusplus
@@ -214,7 +222,14 @@ extern "C" {
const void *txbuf, void *rxbuf);
void spi_lld_send(SPIDriver *spip, size_t n, const void *txbuf);
void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf);
+
+#if AVR_SPI_USE_16BIT_POLLED_EXCHANGE
uint16_t spi_lld_polled_exchange(SPIDriver *spip, uint16_t frame);
+#else
+ uint8_t spi_lld_polled_exchange(SPIDriver *spip, uint8_t frame);
+#endif
+
+
#ifdef __cplusplus
}
#endif