Contiki 2.6
|
00001 /* Copyright (c) 2008, Swedish Institute of Computer Science 00002 * All rights reserved. 00003 * 00004 * Additional fixes for AVR contributed by: 00005 * 00006 * Colin O'Flynn coflynn@newae.com 00007 * Eric Gnoske egnoske@gmail.com 00008 * Blake Leverett bleverett@gmail.com 00009 * Mike Vidales mavida404@gmail.com 00010 * Kevin Brown kbrown3@uccs.edu 00011 * Nate Bohlmann nate@elfwerks.com 00012 * 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in 00022 * the documentation and/or other materials provided with the 00023 * distribution. 00024 * * Neither the name of the copyright holders nor the names of 00025 * contributors may be used to endorse or promote products derived 00026 * from this software without specific prior written permission. 00027 * 00028 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00029 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00030 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00031 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00032 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00033 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00034 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00035 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00036 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00037 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00038 * POSSIBILITY OF SUCH DAMAGE. 00039 */ 00040 00041 /** 00042 * \addtogroup hal 00043 * @{ 00044 */ 00045 00046 /** 00047 * \file 00048 * \brief This file contains low-level radio driver code. 00049 * 00050 * $Id: hal.h,v 1.5 2010/02/26 21:15:28 dak664 Exp $ 00051 */ 00052 00053 #ifndef HAL_AVR_H 00054 #define HAL_AVR_H 00055 /*============================ INCLUDE =======================================*/ 00056 #include <stdint.h> 00057 #include <stdbool.h> 00058 #include <avr/io.h> 00059 #include <avr/interrupt.h> 00060 #include <util/crc16.h> 00061 #include "contiki-conf.h" 00062 /*============================ MACROS ========================================*/ 00063 00064 // TEST CODE 00065 #define TRIG1 DDRB |= 0x04, PINB |= 0x04 00066 #define TRIG2 DDRD |= 0x80, PIND |= 0x80 00067 00068 /** \name This is the list of pin configurations needed for a given platform. 00069 * \brief Change these values to port to other platforms. 00070 * \{ 00071 */ 00072 /* Define all possible revisions here */ 00073 // Don't use zero, it will match if undefined! 00074 // RAVEN_D : Raven kit with LCD display 00075 // RAVENUSB_C : used for USB key or Raven card 00076 // RCB_B : RZ200 kit from Atmel based on 1281V 00077 // ZIGBIT : Zigbit module from Meshnetics 00078 // IRIS : IRIS Mote from MEMSIC 00079 #define RAVEN_D 1 00080 #define RAVENUSB_C 2 00081 #define RCB_B 3 00082 #define ZIGBIT 4 00083 #define IRIS 5 00084 00085 00086 00087 00088 #if PLATFORM_TYPE == RCB_B 00089 /* 1281 rcb */ 00090 # define SSPORT B 00091 # define SSPIN (0x00) 00092 # define SPIPORT B 00093 # define MOSIPIN (0x02) 00094 # define MISOPIN (0x03) 00095 # define SCKPIN (0x01) 00096 # define RSTPORT B 00097 # define RSTPIN (0x05) 00098 # define IRQPORT D 00099 # define IRQPIN (0x04) 00100 # define SLPTRPORT B 00101 # define SLPTRPIN (0x04) 00102 # define USART 1 00103 # define USARTVECT USART1_RX_vect 00104 # define TICKTIMER 3 00105 # define HAS_SPARE_TIMER 00106 00107 #elif PLATFORM_TYPE == ZIGBIT 00108 /* 1281V Zigbit */ 00109 # define SSPORT B 00110 # define SSPIN (0x00) 00111 # define SPIPORT B 00112 # define MOSIPIN (0x02) 00113 # define MISOPIN (0x03) 00114 # define SCKPIN (0x01) 00115 # define RSTPORT A 00116 # define RSTPIN (0x07) 00117 # define IRQPORT E 00118 # define IRQPIN (0x05) 00119 # define SLPTRPORT B 00120 # define SLPTRPIN (0x04) 00121 # define TXCWPORT B 00122 # define TXCWPIN (0x07) 00123 # define USART 1 00124 # define USARTVECT USART1_RX_vect 00125 //# define TICKTIMER 3 00126 //# define HAS_SPARE_TIMER // Not used 00127 00128 00129 #elif RAVEN_REVISION == RAVEN_D 00130 /* 1284 raven */ 00131 # define SSPORT B 00132 # define SSPIN (0x04) 00133 # define SPIPORT B 00134 # define MOSIPIN (0x05) 00135 # define MISOPIN (0x06) 00136 # define SCKPIN (0x07) 00137 # define RSTPORT B 00138 # define RSTPIN (0x01) 00139 # define IRQPORT D 00140 # define IRQPIN (0x06) 00141 # define SLPTRPORT B 00142 # define SLPTRPIN (0x03) 00143 # define TXCWPORT B 00144 # define TXCWPIN (0x00) 00145 # define USART 1 00146 # define USARTVECT USART1_RX_vect 00147 # define TICKTIMER 3 00148 # define HAS_CW_MODE 00149 # define HAS_SPARE_TIMER 00150 00151 #elif RAVEN_REVISION == RAVENUSB_C 00152 /* 1287USB raven */ 00153 # define SSPORT B 00154 # define SSPIN (0x00) 00155 # define SPIPORT B 00156 # define MOSIPIN (0x02) 00157 # define MISOPIN (0x03) 00158 # define SCKPIN (0x01) 00159 # define RSTPORT B 00160 # define RSTPIN (0x05) 00161 # define IRQPORT D 00162 # define IRQPIN (0x04) 00163 # define SLPTRPORT B 00164 # define SLPTRPIN (0x04) 00165 # define TXCWPORT B 00166 # define TXCWPIN (0x07) 00167 # define USART 1 00168 # define USARTVECT USART1_RX_vect 00169 # define TICKTIMER 3 00170 # define HAS_CW_MODE 00171 # define HAS_SPARE_TIMER 00172 00173 #elif PLATFORM_TYPE == IRIS 00174 /* 1281 IRIS */ 00175 # define SSPORT B 00176 # define SSPIN (0x00) 00177 # define SPIPORT B 00178 # define MOSIPIN (0x02) 00179 # define MISOPIN (0x03) 00180 # define SCKPIN (0x01) 00181 # define RSTPORT A 00182 # define RSTPIN (0x06) 00183 # define IRQPORT D 00184 # define IRQPIN (0x04) 00185 # define SLPTRPORT B 00186 # define SLPTRPIN (0x07) 00187 //# define TXCWPORT B 00188 //# define TXCWPIN (0x07) 00189 # define USART 1 00190 # define USARTVECT USART1_RX_vect 00191 //# define TICKTIMER 3 00192 //# define HAS_SPARE_TIMER // Not used 00193 #else 00194 00195 #error "Platform undefined in hal.h" 00196 00197 #endif 00198 00199 /** \} */ 00200 00201 /** 00202 * \name Macros used to generate read register names from platform-specific definitions of ports. 00203 * \brief The various CAT macros (DDR, PORT, and PIN) are used to 00204 * assign port/pin/DDR names to various macro variables. The 00205 * variables are assigned based on the specific connections made in 00206 * the hardware. For example TCCR(TICKTIMER,A) can be used in place of TCCR0A 00207 * if TICKTIMER is defined as 0. 00208 * \{ 00209 */ 00210 #define CAT(x, y) x##y 00211 #define CAT2(x, y, z) x##y##z 00212 #define DDR(x) CAT(DDR, x) 00213 #define PORT(x) CAT(PORT, x) 00214 #define PIN(x) CAT(PIN, x) 00215 #define UCSR(num, let) CAT2(UCSR,num,let) 00216 #define RXEN(x) CAT(RXEN,x) 00217 #define TXEN(x) CAT(TXEN,x) 00218 #define TXC(x) CAT(TXC,x) 00219 #define RXC(x) CAT(RXC,x) 00220 #define RXCIE(x) CAT(RXCIE,x) 00221 #define UCSZ(x,y) CAT2(UCSZ,x,y) 00222 #define UBRR(x,y) CAT2(UBRR,x,y) 00223 #define UDRE(x) CAT(UDRE,x) 00224 #define UDRIE(x) CAT(UDRIE,x) 00225 #define UDR(x) CAT(UDR,x) 00226 #define TCNT(x) CAT(TCNT,x) 00227 #define TIMSK(x) CAT(TIMSK,x) 00228 #define TCCR(x,y) CAT2(TCCR,x,y) 00229 #define COM(x,y) CAT2(COM,x,y) 00230 #define OCR(x,y) CAT2(OCR,x,y) 00231 #define CS(x,y) CAT2(CS,x,y) 00232 #define WGM(x,y) CAT2(WGM,x,y) 00233 #define OCIE(x,y) CAT2(OCIE,x,y) 00234 #define COMPVECT(x) CAT2(TIMER,x,_COMPA_vect) 00235 #define UDREVECT(x) CAT2(USART,x,_UDRE_vect) 00236 #define RXVECT(x) CAT2(USART,x,_RX_vect) 00237 /** \} */ 00238 00239 /** 00240 * \name Pin macros 00241 * \brief These macros convert the platform-specific pin defines into names and functions 00242 * that the source code can directly use. 00243 * \{ 00244 */ 00245 #define SLP_TR SLPTRPIN /**< Pin number that corresponds to the SLP_TR pin. */ 00246 #define DDR_SLP_TR DDR( SLPTRPORT ) /**< Data Direction Register that corresponds to the port where SLP_TR is connected. */ 00247 #define PORT_SLP_TR PORT( SLPTRPORT ) /**< Port (Write Access) where SLP_TR is connected. */ 00248 #define PIN_SLP_TR PIN( SLPTRPORT ) /**< Pin (Read Access) where SLP_TR is connected. */ 00249 #define hal_set_slptr_high( ) ( PORT_SLP_TR |= ( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin high. */ 00250 #define hal_set_slptr_low( ) ( PORT_SLP_TR &= ~( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin low. */ 00251 #define hal_get_slptr( ) ( ( PIN_SLP_TR & ( 1 << SLP_TR ) ) >> SLP_TR ) /**< Read current state of the SLP_TR pin (High/Low). */ 00252 #define RST RSTPIN /**< Pin number that corresponds to the RST pin. */ 00253 #define DDR_RST DDR( RSTPORT ) /**< Data Direction Register that corresponds to the port where RST is */ 00254 #define PORT_RST PORT( RSTPORT ) /**< Port (Write Access) where RST is connected. */ 00255 #define PIN_RST PIN( RSTPORT ) /**< Pin (Read Access) where RST is connected. */ 00256 #define hal_set_rst_high( ) ( PORT_RST |= ( 1 << RST ) ) /**< This macro pulls the RST pin high. */ 00257 #define hal_set_rst_low( ) ( PORT_RST &= ~( 1 << RST ) ) /**< This macro pulls the RST pin low. */ 00258 #define hal_get_rst( ) ( ( PIN_RST & ( 1 << RST ) ) >> RST ) /**< Read current state of the RST pin (High/Low). */ 00259 #define HAL_SS_PIN SSPIN /**< The slave select pin. */ 00260 #define HAL_PORT_SPI PORT( SPIPORT ) /**< The SPI module is located on PORTB. */ 00261 #define HAL_DDR_SPI DDR( SPIPORT ) /**< Data Direction Register for PORTB. */ 00262 #define HAL_DD_SS SSPIN /**< Data Direction bit for SS. */ 00263 #define HAL_DD_SCK SCKPIN /**< Data Direction bit for SCK. */ 00264 #define HAL_DD_MOSI MOSIPIN /**< Data Direction bit for MOSI. */ 00265 #define HAL_DD_MISO MISOPIN /**< Data Direction bit for MISO. */ 00266 /** \} */ 00267 00268 00269 #define HAL_SS_HIGH( ) (HAL_PORT_SPI |= ( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS high. */ 00270 #define HAL_SS_LOW( ) (HAL_PORT_SPI &= ~( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS low. */ 00271 00272 /** \brief Macros defined for HAL_TIMER1. 00273 * 00274 * These macros are used to define the correct setupt of the AVR's Timer1, and 00275 * to ensure that the hal_get_system_time function returns the system time in 00276 * symbols (16 us ticks). 00277 */ 00278 00279 #if ( F_CPU == 16000000UL ) 00280 #define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS12 ) ) 00281 #define HAL_US_PER_SYMBOL ( 1 ) 00282 #define HAL_SYMBOL_MASK ( 0xFFFFffff ) 00283 #elif ( F_CPU == 8000000UL ) 00284 #define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) ) 00285 #define HAL_US_PER_SYMBOL ( 2 ) 00286 #define HAL_SYMBOL_MASK ( 0x7FFFffff ) 00287 #elif ( F_CPU == 4000000UL ) 00288 #define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) ) 00289 #define HAL_US_PER_SYMBOL ( 1 ) 00290 #define HAL_SYMBOL_MASK ( 0xFFFFffff ) 00291 #elif ( F_CPU == 1000000UL ) 00292 #define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) ) 00293 #define HAL_US_PER_SYMBOL ( 2 ) 00294 #define HAL_SYMBOL_MASK ( 0x7FFFffff ) 00295 #else 00296 #error "Clock speed not supported." 00297 #endif 00298 00299 #if PLATFORM_TYPE == ZIGBIT 00300 // IRQ E5 for Zigbit example 00301 #define RADIO_VECT INT5_vect 00302 #define HAL_ENABLE_RADIO_INTERRUPT( ) { ( EIMSK |= ( 1 << INT5 ) ) ; EICRB |= 0x0C ; PORTE &= ~(1<<PE5); DDRE &= ~(1<<DDE5); } 00303 #define HAL_DISABLE_RADIO_INTERRUPT( ) ( EIMSK &= ~( 1 << INT5 ) ) 00304 #else 00305 #define RADIO_VECT TIMER1_CAPT_vect 00306 #define HAL_ENABLE_RADIO_INTERRUPT( ) ( TIMSK1 |= ( 1 << ICIE1 ) ) 00307 #define HAL_DISABLE_RADIO_INTERRUPT( ) ( TIMSK1 &= ~( 1 << ICIE1 ) ) 00308 #endif 00309 00310 #define HAL_ENABLE_OVERFLOW_INTERRUPT( ) ( TIMSK1 |= ( 1 << TOIE1 ) ) 00311 #define HAL_DISABLE_OVERFLOW_INTERRUPT( ) ( TIMSK1 &= ~( 1 << TOIE1 ) ) 00312 00313 /** This macro will protect the following code from interrupts.*/ 00314 #define AVR_ENTER_CRITICAL_REGION( ) {uint8_t volatile saved_sreg = SREG; cli( ) 00315 00316 /** This macro must always be used in conjunction with AVR_ENTER_CRITICAL_REGION 00317 so that interrupts are enabled again.*/ 00318 #define AVR_LEAVE_CRITICAL_REGION( ) SREG = saved_sreg;} 00319 00320 00321 /** \brief Enable the interrupt from the radio transceiver. 00322 */ 00323 #define hal_enable_trx_interrupt( ) HAL_ENABLE_RADIO_INTERRUPT( ) 00324 00325 /** \brief Disable the interrupt from the radio transceiver. 00326 * 00327 * \retval 0 if the pin is low, 1 if the pin is high. 00328 */ 00329 #define hal_disable_trx_interrupt( ) HAL_DISABLE_RADIO_INTERRUPT( ) 00330 /*============================ TYPDEFS =======================================*/ 00331 /*============================ PROTOTYPES ====================================*/ 00332 /*============================ MACROS ========================================*/ 00333 /** \name Macros for radio operation. 00334 * \{ 00335 */ 00336 #define HAL_BAT_LOW_MASK ( 0x80 ) /**< Mask for the BAT_LOW interrupt. */ 00337 #define HAL_TRX_UR_MASK ( 0x40 ) /**< Mask for the TRX_UR interrupt. */ 00338 #define HAL_TRX_END_MASK ( 0x08 ) /**< Mask for the TRX_END interrupt. */ 00339 #define HAL_RX_START_MASK ( 0x04 ) /**< Mask for the RX_START interrupt. */ 00340 #define HAL_PLL_UNLOCK_MASK ( 0x02 ) /**< Mask for the PLL_UNLOCK interrupt. */ 00341 #define HAL_PLL_LOCK_MASK ( 0x01 ) /**< Mask for the PLL_LOCK interrupt. */ 00342 00343 #define HAL_MIN_FRAME_LENGTH ( 0x03 ) /**< A frame should be at least 3 bytes. */ 00344 #define HAL_MAX_FRAME_LENGTH ( 0x7F ) /**< A frame should no more than 127 bytes. */ 00345 /** \} */ 00346 /*============================ TYPDEFS =======================================*/ 00347 /** \struct hal_rx_frame_t 00348 * \brief This struct defines the rx data container. 00349 * 00350 * \see hal_frame_read 00351 */ 00352 typedef struct{ 00353 uint8_t length; /**< Length of frame. */ 00354 uint8_t data[ HAL_MAX_FRAME_LENGTH ]; /**< Actual frame data. */ 00355 uint8_t lqi; /**< LQI value for received frame. */ 00356 bool crc; /**< Flag - did CRC pass for received frame? */ 00357 } hal_rx_frame_t; 00358 00359 /** RX_START event handler callback type. Is called with timestamp in IEEE 802.15.4 symbols and frame length. See hal_set_rx_start_event_handler(). */ 00360 typedef void (*hal_rx_start_isr_event_handler_t)(uint32_t const isr_timestamp, uint8_t const frame_length); 00361 00362 /** RRX_END event handler callback type. Is called with timestamp in IEEE 802.15.4 symbols and frame length. See hal_set_trx_end_event_handler(). */ 00363 typedef void (*hal_trx_end_isr_event_handler_t)(uint32_t const isr_timestamp); 00364 00365 typedef void (*rx_callback_t) (uint16_t data); 00366 00367 /*============================ PROTOTYPES ====================================*/ 00368 void hal_init( void ); 00369 00370 void hal_reset_flags( void ); 00371 uint8_t hal_get_bat_low_flag( void ); 00372 void hal_clear_bat_low_flag( void ); 00373 00374 hal_trx_end_isr_event_handler_t hal_get_trx_end_event_handler( void ); 00375 void hal_set_trx_end_event_handler( hal_trx_end_isr_event_handler_t trx_end_callback_handle ); 00376 void hal_clear_trx_end_event_handler( void ); 00377 00378 hal_rx_start_isr_event_handler_t hal_get_rx_start_event_handler( void ); 00379 void hal_set_rx_start_event_handler( hal_rx_start_isr_event_handler_t rx_start_callback_handle ); 00380 void hal_clear_rx_start_event_handler( void ); 00381 00382 uint8_t hal_get_pll_lock_flag( void ); 00383 void hal_clear_pll_lock_flag( void ); 00384 00385 uint8_t hal_register_read( uint8_t address ); 00386 void hal_register_write( uint8_t address, uint8_t value ); 00387 uint8_t hal_subregister_read( uint8_t address, uint8_t mask, uint8_t position ); 00388 void hal_subregister_write( uint8_t address, uint8_t mask, uint8_t position, 00389 uint8_t value ); 00390 void hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback); 00391 void hal_frame_write( uint8_t *write_buffer, uint8_t length ); 00392 void hal_sram_read( uint8_t address, uint8_t length, uint8_t *data ); 00393 void hal_sram_write( uint8_t address, uint8_t length, uint8_t *data ); 00394 00395 #endif 00396 /** @} */ 00397 /*EOF*/