1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-07-30 16:24:09 +03:00

[sam] fixing last stupid commit

This commit is contained in:
Thibaut VIARD
2011-09-06 21:05:41 +02:00
parent 8f01f92e87
commit a5d2349761
550 changed files with 16866 additions and 17198 deletions

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup adc_module Working with ADC
* The ADC driver provides the interface to configure and use the ADC peripheral.
@ -91,7 +66,7 @@
extern void ADC_Initialize( Adc* pAdc, uint32_t idAdc )
{
/* Enable peripheral clock*/
PMC->PMC_PCER0 = 1 << idAdc;
PMC_EnablePeripheral( idAdc ) ;
/* Reset the controller */
pAdc->ADC_CR = ADC_CR_SWRST;
@ -100,7 +75,7 @@ extern void ADC_Initialize( Adc* pAdc, uint32_t idAdc )
/* TrackTime set to 0 */
/* Transfer set to 1 */
/* settling set to 3 */
pAdc->ADC_MR = ADC_MR_TRANSFER(1) | ADC_MR_TRACKTIM(0) | ADC_MR_SETTLING(3);
pAdc->ADC_MR = ADC_MR_TRANSFER(1) | ADC_MR_TRACKTIM(0) | ADC_MR_SETTLING_AST17 ;
}
/**
@ -109,7 +84,7 @@ extern void ADC_Initialize( Adc* pAdc, uint32_t idAdc )
extern void ADC_CfgTiming( Adc* pAdc, uint32_t tracking, uint32_t settling, uint32_t transfer )
{
pAdc->ADC_MR = ADC_MR_TRANSFER( transfer )
| ADC_MR_SETTLING( settling )
| settling
| ADC_MR_TRACKTIM( tracking ) ;
}

View File

@ -1,289 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/** \addtogroup efc_module Working with EEFC
* The EEFC driver provides the interface to configure and use the EEFC
* peripheral.
*
* The user needs to set the number of wait states depending on the frequency used.\n
* Configure number of cycles for flash read/write operations in the FWS field of EEFC_FMR.
*
* It offers a function to send flash command to EEFC and waits for the
* flash to be ready.
*
* To send flash command, the user could do in either of following way:
* <ul>
* <li>Write a correct key, command and argument in EEFC_FCR. </li>
* <li>Or, Use IAP (In Application Programming) function which is executed from
* ROM directly, this allows flash programming to be done by code running in flash.</li>
* <li>Once the command is achieved, it can be detected even by polling EEFC_FSR or interrupt.
* </ul>
*
* The command argument could be a page number,GPNVM number or nothing, it depends on
* the command itself. Some useful functions in this driver could help user tranlate physical
* flash address into a page number and vice verse.
*
* For more accurate information, please look at the EEFC section of the
* Datasheet.
*
* Related files :\n
* \ref efc.c\n
* \ref efc.h.\n
*/
/*@{*/
/*@}*/
/**
* \file
*
* Implementation of Enhanced Embedded Flash Controller (EEFC).
*
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "chip.h"
#include <assert.h>
#include <stdlib.h>
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
/**
* \brief Enables the flash ready interrupt source on the EEFC peripheral.
*
* \param efc Pointer to a Efc instance
*/
extern void EFC_EnableFrdyIt( Efc* efc )
{
efc->EEFC_FMR |= EEFC_FMR_FRDY ;
}
/**
* \brief Disables the flash ready interrupt source on the EEFC peripheral.
*
* \param efc Pointer to a Efc instance
*/
extern void EFC_DisableFrdyIt( Efc* efc )
{
efc->EEFC_FMR &= ~((uint32_t)EEFC_FMR_FRDY) ;
}
/**
* \brief Set read/write wait state on the EEFC perpherial.
*
* \param efc Pointer to a Efc instance
* \param cycles the number of wait states in cycle.
*/
extern void EFC_SetWaitState( Efc* efc, uint8_t ucCycles )
{
uint32_t dwValue ;
dwValue = efc->EEFC_FMR ;
dwValue &= ~((uint32_t)EEFC_FMR_FWS_Msk) ;
dwValue |= EEFC_FMR_FWS(ucCycles);
efc->EEFC_FMR = dwValue ;
}
/**
* \brief Returns the current status of the EEFC.
*
* \note Keep in mind that this function clears the value of some status bits (LOCKE, PROGE).
*
* \param efc Pointer to a Efc instance
*/
extern uint32_t EFC_GetStatus( Efc* efc )
{
return efc->EEFC_FSR ;
}
/**
* \brief Returns the result of the last executed command.
*
* \param efc Pointer to a Efc instance
*/
extern uint32_t EFC_GetResult( Efc* efc )
{
return efc->EEFC_FRR ;
}
/**
* \brief Translates the given address page and offset values.
* \note The resulting values are stored in the provided variables if they are not null.
*
* \param efc Pointer to a Efc instance
* \param address Address to translate.
* \param pPage First page accessed.
* \param pOffset Byte offset in first page.
*/
extern void EFC_TranslateAddress( Efc** ppEfc, uint32_t dwAddress, uint16_t* pwPage, uint16_t* pwOffset )
{
Efc *pEfc ;
uint16_t wPage ;
uint16_t wOffset ;
assert( dwAddress >= IFLASH_ADDR ) ;
assert( dwAddress <= (IFLASH_ADDR + IFLASH_SIZE) ) ;
pEfc = EFC ;
wPage = (dwAddress - IFLASH_ADDR) / IFLASH_PAGE_SIZE;
wOffset = (dwAddress - IFLASH_ADDR) % IFLASH_PAGE_SIZE;
/* Store values */
if ( pEfc )
{
*ppEfc = pEfc ;
}
if ( pwPage )
{
*pwPage = wPage ;
}
if ( pwOffset )
{
*pwOffset = wOffset ;
}
}
/**
* \brief Computes the address of a flash access given the page and offset.
*
* \param efc Pointer to a Efc instance
* \param page Page number.
* \param offset Byte offset inside page.
* \param pAddress Computed address (optional).
*/
extern void EFC_ComputeAddress( Efc *efc, uint16_t wPage, uint16_t wOffset, uint32_t *pdwAddress )
{
uint32_t dwAddress ;
assert( efc ) ;
assert( wPage <= IFLASH_NB_OF_PAGES ) ;
assert( wOffset < IFLASH_PAGE_SIZE ) ;
/* Compute address */
dwAddress = IFLASH_ADDR + wPage * IFLASH_PAGE_SIZE + wOffset ;
/* Store result */
if ( pdwAddress != NULL )
{
*pdwAddress = dwAddress ;
}
}
/**
* \brief Starts the executing the given command on the EEFC and returns as soon as the command is started.
*
* \note It does NOT set the FMCN field automatically.
* \param efc Pointer to a Efc instance
* \param command Command to execute.
* \param argument Command argument (should be 0 if not used).
*/
extern void EFC_StartCommand( Efc* efc, uint32_t dwCommand, uint32_t dwArgument )
{
/* Check command & argument */
switch ( dwCommand )
{
case EFC_FCMD_WP:
case EFC_FCMD_WPL:
case EFC_FCMD_EWP:
case EFC_FCMD_EWPL:
case EFC_FCMD_SLB:
case EFC_FCMD_CLB:
assert( dwArgument < IFLASH_NB_OF_PAGES ) ;
break ;
case EFC_FCMD_SFB:
case EFC_FCMD_CFB:
assert( dwArgument < 2 ) ;
break;
case EFC_FCMD_GETD:
case EFC_FCMD_EA:
case EFC_FCMD_GLB:
case EFC_FCMD_GFB:
case EFC_FCMD_STUI:
assert( dwArgument == 0 ) ;
break;
default: assert( 0 ) ;
}
/* Start command Embedded flash */
assert( (efc->EEFC_FSR & EEFC_FMR_FRDY) == EEFC_FMR_FRDY ) ;
efc->EEFC_FCR = EEFC_FCR_FKEY(0x5A) | EEFC_FCR_FARG(dwArgument) | EEFC_FCR_FCMD(dwCommand) ;
}
/**
* \brief Performs the given command and wait until its completion (or an error).
*
* \param efc Pointer to a Efc instance
* \param command Command to perform.
* \param argument Optional command argument.
*
* \return 0 if successful, otherwise returns an error code.
*/
extern uint32_t EFC_PerformCommand( Efc* efc, uint32_t dwCommand, uint32_t dwArgument, uint32_t dwUseIAP )
{
if ( dwUseIAP != 0 )
{
/* Pointer on IAP function in ROM */
static uint32_t (*IAP_PerformCommand)( uint32_t, uint32_t ) ;
IAP_PerformCommand = (uint32_t (*)( uint32_t, uint32_t )) *((uint32_t*)CHIP_FLASH_IAP_ADDRESS ) ;
IAP_PerformCommand( 0, EEFC_FCR_FKEY(0x5A) | EEFC_FCR_FARG(dwArgument) | EEFC_FCR_FCMD(dwCommand) ) ;
return (efc->EEFC_FSR & (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE)) ;
}
else
{
uint32_t dwStatus ;
efc->EEFC_FCR = EEFC_FCR_FKEY(0x5A) | EEFC_FCR_FARG(dwArgument) | EEFC_FCR_FCMD(dwCommand) ;
do
{
dwStatus = efc->EEFC_FSR ;
}
while ( (dwStatus & EEFC_FSR_FRDY) != EEFC_FSR_FRDY ) ;
return ( dwStatus & (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE) ) ;
}
}

View File

@ -1,101 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/**
* \file
* This file contains the default exception handlers.
*
* \note
* The exception handler has weak aliases.
* As they are weak aliases, any function with the same name will override
* this definition.
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "chip.h"
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
/* Cortex-M3 core handlers */
extern void NMI_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void HardFault_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void MemManage_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void BusFault_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void UsageFault_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SVC_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void DebugMon_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PendSV_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SysTick_Handler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
/* Peripherals handlers */
extern void ACC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void ADC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void CRCCU_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void DAC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void EEFC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void MCI_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PIOA_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PIOB_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PIOC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PMC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void PWM_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void RSTC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void RTC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void RTT_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SMC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SPI_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SSC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void SUPC_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC0_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC1_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC2_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC3_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC4_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TC5_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TWI0_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void TWI1_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void UART0_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void UART1_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void USART0_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void USART1_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void USBD_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
extern void WDT_IrqHandler( void ) __attribute__ ((weak, alias ("Dummy_Handler"))) ;
/**
* \brief Default interrupt handler for not used irq.
*/
void Dummy_Handler( void )
{
while ( 1 ) ;
}

View File

@ -1,511 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/** \addtogroup flashd_module Flash Memory Interface
* The flash driver manages the programming, erasing, locking and unlocking sequences
* with dedicated commands.
*
* To implement flash programing operation, the user has to follow these few steps :
* <ul>
* <li>Configue flash wait states to initializes the flash. </li>
* <li>Checks whether a region to be programmed is locked. </li>
* <li>Unlocks the user region to be programmed if the region have locked before.</li>
* <li>Erases the user page before program (optional).</li>
* <li>Writes the user page from the page buffer.</li>
* <li>Locks the region of programmed area if any.</li>
* </ul>
*
* Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption.
* A check of this validity and padding for 32-bit alignment should be done in write algorithm.
* Lock/unlock range associated with the user address range is automatically translated.
*
* This security bit can be enabled through the command "Set General Purpose NVM Bit 0".
*
* A 128-bit factory programmed unique ID could be read to serve several purposes.
*
* The driver accesses the flash memory by calling the lowlevel module provided in \ref efc_module.
* For more accurate information, please look at the EEFC section of the Datasheet.
*
* Related files :\n
* \ref flashd.c\n
* \ref flashd.h.\n
* \ref efc.c\n
* \ref efc.h.\n
*/
/*@{*/
/*@}*/
/**
* \file
*
* The flash driver provides the unified interface for flash program operations.
*
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "chip.h"
#include <string.h>
#include <assert.h>
/*----------------------------------------------------------------------------
* Local variables
*----------------------------------------------------------------------------*/
//static NO_INIT uint8_t _aucPageBuffer[IFLASH_PAGE_SIZE] ;
static NO_INIT uint32_t _adwPageBuffer[IFLASH_PAGE_SIZE/4] ;
static uint8_t* _aucPageBuffer = (uint8_t*)_adwPageBuffer;
static NO_INIT uint32_t _dwUseIAP ;
/*----------------------------------------------------------------------------
* Local macros
*----------------------------------------------------------------------------*/
#define min( a, b ) (((a) < (b)) ? (a) : (b))
/*----------------------------------------------------------------------------
* Local functions
*----------------------------------------------------------------------------*/
/**
* \brief Computes the lock range associated with the given address range.
*
* \param dwStart Start address of lock range.
* \param dwEnd End address of lock range.
* \param pdwActualStart Actual start address of lock range.
* \param pdwActualEnd Actual end address of lock range.
*/
static void ComputeLockRange( uint32_t dwStart, uint32_t dwEnd, uint32_t *pdwActualStart, uint32_t *pdwActualEnd )
{
Efc* pStartEfc ;
Efc* pEndEfc ;
uint16_t wStartPage ;
uint16_t wEndPage ;
uint16_t wNumPagesInRegion ;
uint16_t wActualStartPage ;
uint16_t wActualEndPage ;
// Convert start and end address in page numbers
EFC_TranslateAddress( &pStartEfc, dwStart, &wStartPage, 0 ) ;
EFC_TranslateAddress( &pEndEfc, dwEnd, &wEndPage, 0 ) ;
// Find out the first page of the first region to lock
wNumPagesInRegion = IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE ;
wActualStartPage = wStartPage - (wStartPage % wNumPagesInRegion) ;
wActualEndPage = wEndPage ;
if ( (wEndPage % wNumPagesInRegion) != 0 )
{
wActualEndPage += wNumPagesInRegion - (wEndPage % wNumPagesInRegion) ;
}
// Store actual page numbers
EFC_ComputeAddress( pStartEfc, wActualStartPage, 0, pdwActualStart ) ;
EFC_ComputeAddress( pEndEfc, wActualEndPage, 0, pdwActualEnd ) ;
}
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
/**
* \brief Initializes the flash driver.
*
* \param mck Master clock frequency in Hz.
*/
extern void FLASHD_Initialize( uint32_t dwMCk, uint32_t dwUseIAP )
{
EFC_DisableFrdyIt( EFC ) ;
if ( (dwMCk/1000000) >= 64 )
{
EFC_SetWaitState( EFC, 2 ) ;
}
else
{
if ( (dwMCk/1000000) >= 50 )
{
EFC_SetWaitState( EFC, 1 ) ;
}
else
{
EFC_SetWaitState( EFC, 0 ) ;
}
}
_dwUseIAP=dwUseIAP ;
}
/**
* \brief Erases the entire flash.
*
* \param address Flash start address.
* \return 0 if successful; otherwise returns an error code.
*/
extern uint32_t FLASHD_Erase( uint32_t dwAddress )
{
Efc* pEfc ;
uint16_t wPage ;
uint16_t wOffset ;
uint32_t dwError ;
assert( (dwAddress >=IFLASH_ADDR) || (dwAddress <= (IFLASH_ADDR + IFLASH_SIZE)) ) ;
// Translate write address
EFC_TranslateAddress( &pEfc, dwAddress, &wPage, &wOffset ) ;
dwError = EFC_PerformCommand( pEfc, EFC_FCMD_EA, 0, _dwUseIAP ) ;
return dwError ;
}
/**
* \brief Writes a data buffer in the internal flash
*
* \note This function works in polling mode, and thus only returns when the
* data has been effectively written.
* \param address Write address.
* \param pBuffer Data buffer.
* \param size Size of data buffer in bytes.
* \return 0 if successful, otherwise returns an error code.
*/
extern uint32_t FLASHD_Write( uint32_t dwAddress, const void *pvBuffer, uint32_t dwSize )
{
Efc* pEfc ;
uint16_t page ;
uint16_t offset ;
uint32_t writeSize ;
uint32_t pageAddress ;
uint16_t padding ;
uint32_t dwError ;
uint32_t sizeTmp ;
uint32_t *pAlignedDestination ;
uint32_t *pAlignedSource ;
assert( pvBuffer ) ;
assert( dwAddress >=IFLASH_ADDR ) ;
assert( (dwAddress + dwSize) <= (IFLASH_ADDR + IFLASH_SIZE) ) ;
/* Translate write address */
EFC_TranslateAddress( &pEfc, dwAddress, &page, &offset ) ;
/* Write all pages */
while ( dwSize > 0 )
{
/* Copy data in temporary buffer to avoid alignment problems */
writeSize = min((uint32_t)IFLASH_PAGE_SIZE - offset, dwSize ) ;
EFC_ComputeAddress(pEfc, page, 0, &pageAddress ) ;
padding = IFLASH_PAGE_SIZE - offset - writeSize ;
/* Pre-buffer data */
memcpy( _aucPageBuffer, (void *) pageAddress, offset);
/* Buffer data */
memcpy( _aucPageBuffer + offset, pvBuffer, writeSize);
/* Post-buffer data */
memcpy( _aucPageBuffer + offset + writeSize, (void *) (pageAddress + offset + writeSize), padding);
/* Write page
* Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption
*/
pAlignedDestination = (uint32_t*)pageAddress ;
pAlignedSource = (uint32_t*)_adwPageBuffer ;
sizeTmp = IFLASH_PAGE_SIZE ;
while ( sizeTmp >= 4 )
{
*pAlignedDestination++ = *pAlignedSource++;
sizeTmp -= 4;
}
/* Send writing command */
dwError = EFC_PerformCommand( pEfc, EFC_FCMD_EWP, page, _dwUseIAP ) ;
if ( dwError )
{
return dwError ;
}
/* Progression */
dwAddress += IFLASH_PAGE_SIZE ;
pvBuffer = (void *)((uint32_t) pvBuffer + writeSize) ;
dwSize -= writeSize ;
page++;
offset = 0;
}
return 0 ;
}
/**
* \brief Locks all the regions in the given address range. The actual lock range is
* reported through two output parameters.
*
* \param start Start address of lock range.
* \param end End address of lock range.
* \param pActualStart Start address of the actual lock range (optional).
* \param pActualEnd End address of the actual lock range (optional).
* \return 0 if successful, otherwise returns an error code.
*/
extern uint32_t FLASHD_Lock( uint32_t start, uint32_t end, uint32_t *pActualStart, uint32_t *pActualEnd )
{
Efc *pEfc ;
uint32_t actualStart, actualEnd ;
uint16_t startPage, endPage ;
uint32_t dwError ;
uint16_t numPagesInRegion = IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE;
/* Compute actual lock range and store it */
ComputeLockRange( start, end, &actualStart, &actualEnd ) ;
if ( pActualStart != NULL )
{
*pActualStart = actualStart ;
}
if ( pActualEnd != NULL )
{
*pActualEnd = actualEnd;
}
/* Compute page numbers */
EFC_TranslateAddress( &pEfc, actualStart, &startPage, 0 ) ;
EFC_TranslateAddress( 0, actualEnd, &endPage, 0 ) ;
/* Lock all pages */
while ( startPage < endPage )
{
dwError = EFC_PerformCommand( pEfc, EFC_FCMD_SLB, startPage, _dwUseIAP ) ;
if ( dwError )
{
return dwError ;
}
startPage += numPagesInRegion;
}
return 0 ;
}
/**
* \brief Unlocks all the regions in the given address range. The actual unlock range is
* reported through two output parameters.
* \param start Start address of unlock range.
* \param end End address of unlock range.
* \param pActualStart Start address of the actual unlock range (optional).
* \param pActualEnd End address of the actual unlock range (optional).
* \return 0 if successful, otherwise returns an error code.
*/
extern uint32_t FLASHD_Unlock( uint32_t start, uint32_t end, uint32_t *pActualStart, uint32_t *pActualEnd )
{
Efc* pEfc ;
uint32_t actualStart, actualEnd ;
uint16_t startPage, endPage ;
uint32_t dwError ;
uint16_t numPagesInRegion = IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE;
// Compute actual unlock range and store it
ComputeLockRange(start, end, &actualStart, &actualEnd);
if ( pActualStart != NULL )
{
*pActualStart = actualStart ;
}
if ( pActualEnd != NULL )
{
*pActualEnd = actualEnd ;
}
// Compute page numbers
EFC_TranslateAddress( &pEfc, actualStart, &startPage, 0 ) ;
EFC_TranslateAddress( 0, actualEnd, &endPage, 0 ) ;
// Unlock all pages
while ( startPage < endPage )
{
dwError = EFC_PerformCommand( pEfc, EFC_FCMD_CLB, startPage, _dwUseIAP ) ;
if ( dwError )
{
return dwError ;
}
startPage += numPagesInRegion ;
}
return 0 ;
}
/**
* \brief Returns the number of locked regions inside the given address range.
*
* \param start Start address of range
* \param end End address of range.
*/
extern uint32_t FLASHD_IsLocked( uint32_t start, uint32_t end )
{
Efc *pEfc ;
uint16_t startPage, endPage ;
uint8_t startRegion, endRegion ;
uint32_t numPagesInRegion ;
uint32_t status ;
uint32_t dwError ;
uint32_t numLockedRegions = 0 ;
assert( end >= start ) ;
assert( (start >=IFLASH_ADDR) && (end <= IFLASH_ADDR + IFLASH_SIZE) ) ;
// Compute page numbers
EFC_TranslateAddress( &pEfc, start, &startPage, 0 ) ;
EFC_TranslateAddress( 0, end, &endPage, 0 ) ;
// Compute region numbers
numPagesInRegion = IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE ;
startRegion = startPage / numPagesInRegion ;
endRegion = endPage / numPagesInRegion ;
if ((endPage % numPagesInRegion) != 0)
{
endRegion++ ;
}
// Retrieve lock status
dwError = EFC_PerformCommand( pEfc, EFC_FCMD_GLB, 0, _dwUseIAP ) ;
assert( !dwError ) ;
status = EFC_GetResult( pEfc ) ;
// Check status of each involved region
while ( startRegion < endRegion )
{
if ( (status & (1 << startRegion)) != 0 )
{
numLockedRegions++ ;
}
startRegion++ ;
}
return numLockedRegions ;
}
/**
* \brief Check if the given GPNVM bit is set or not.
*
* \param gpnvm GPNVM bit index.
* \returns 1 if the given GPNVM bit is currently set; otherwise returns 0.
*/
extern uint32_t FLASHD_IsGPNVMSet( uint8_t ucGPNVM )
{
uint32_t dwError ;
uint32_t dwStatus ;
assert( ucGPNVM < 2 ) ;
/* Get GPNVMs status */
dwError = EFC_PerformCommand( EFC, EFC_FCMD_GFB, 0, _dwUseIAP ) ;
assert( !dwError ) ;
dwStatus = EFC_GetResult( EFC ) ;
/* Check if GPNVM is set */
if ( (dwStatus & (1 << ucGPNVM)) != 0 )
{
return 1 ;
}
else
{
return 0 ;
}
}
/**
* \brief Sets the selected GPNVM bit.
*
* \param gpnvm GPNVM bit index.
* \returns 0 if successful; otherwise returns an error code.
*/
extern uint32_t FLASHD_SetGPNVM( uint8_t ucGPNVM )
{
assert( ucGPNVM < 2 ) ;
if ( !FLASHD_IsGPNVMSet( ucGPNVM ) )
{
return EFC_PerformCommand( EFC, EFC_FCMD_SFB, ucGPNVM, _dwUseIAP ) ;
}
else
{
return 0 ;
}
}
/**
* \brief Clears the selected GPNVM bit.
*
* \param gpnvm GPNVM bit index.
* \returns 0 if successful; otherwise returns an error code.
*/
extern uint32_t FLASHD_ClearGPNVM( uint8_t ucGPNVM )
{
assert( ucGPNVM < 2 ) ;
if ( FLASHD_IsGPNVMSet( ucGPNVM ) )
{
return EFC_PerformCommand( EFC, EFC_FCMD_CFB, ucGPNVM, _dwUseIAP ) ;
}
else
{
return 0 ;
}
}
/**
* \brief Read the unique ID.
*
* \param uniqueID pointer on a 4bytes char containing the unique ID value.
* \returns 0 if successful; otherwise returns an error code.
*/
extern uint32_t FLASHD_ReadUniqueID( uint32_t* pdwUniqueID )
{
uint32_t dwError ;
assert( pdwUniqueID != NULL ) ;
pdwUniqueID[0] = 0 ;
pdwUniqueID[1] = 0 ;
pdwUniqueID[2] = 0 ;
pdwUniqueID[3] = 0 ;
EFC_StartCommand( EFC, EFC_FCMD_STUI, 0 ) ;
pdwUniqueID[0] = *(uint32_t*) IFLASH_ADDR;
pdwUniqueID[1] = *(uint32_t*)(IFLASH_ADDR + 4) ;
pdwUniqueID[2] = *(uint32_t*)(IFLASH_ADDR + 8) ;
pdwUniqueID[3] = *(uint32_t*)(IFLASH_ADDR + 12) ;
dwError = EFC_PerformCommand( EFC, EFC_FCMD_SPUI, 0, _dwUseIAP ) ;
if ( dwError )
{
return dwError ;
}
return 0 ;
}

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2010, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \file */
@ -301,20 +276,6 @@ extern uint32_t PIO_Configure( Pio* pPio, const EPioType dwType, const uint32_t
break;
case PIO_INPUT :
switch ( (uint32_t)pPio )
{
case (uint32_t)PIOA :
PMC_EnablePeripheral( ID_PIOA ) ;
break ;
case (uint32_t)PIOB :
PMC_EnablePeripheral( ID_PIOB ) ;
break ;
case (uint32_t)PIOC :
PMC_EnablePeripheral( ID_PIOC ) ;
break ;
}
PIO_SetInput( pPio, dwMask, dwAttribute ) ;
break;

View File

@ -1,3 +1,7 @@
/*
%atmel_license%
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/*----------------------------------------------------------------------------
* Headers

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup pwm_module Working with PWM
* The PWM driver provides the interface to configure and use the PWM
@ -580,13 +555,13 @@ void PWMC_ConfigureComparisonUnit( Pwm* pPwm, uint32_t x, uint32_t value, uint32
/* If channel is disabled, write to CMPxM & CMPxV */
if ((pPwm->PWM_SR & (1 << 0)) == 0) {
pPwm->PWM_CMP[x].PWM_CMPxM = mode;
pPwm->PWM_CMP[x].PWM_CMPxV = value;
pPwm->PWM_CMP[x].PWM_CMPM = mode;
pPwm->PWM_CMP[x].PWM_CMPV = value;
}
/* Otherwise use update register */
else {
pPwm->PWM_CMP[x].PWM_CMPxMUPD = mode;
pPwm->PWM_CMP[x].PWM_CMPxVUPD = value;
pPwm->PWM_CMP[x].PWM_CMPMUPD = mode;
pPwm->PWM_CMP[x].PWM_CMPVUPD = value;
}
}
@ -600,9 +575,15 @@ void PWMC_ConfigureEventLineMode( Pwm* pPwm, uint32_t x, uint32_t mode)
{
assert(x < 2);
if (x == 0) {
pPwm->PWM_ELxMR[0] = mode;
} else if (x == 1) {
pPwm->PWM_ELxMR[1] = mode;
if (x == 0)
{
pPwm->PWM_ELMR[0] = mode;
}
else
{
if (x == 1)
{
pPwm->PWM_ELMR[1] = mode;
}
}
}

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup rtc_module Working with RTC
* The RTC driver provides the interface to configure and use the RTC

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup rtt_module Working with RTT
* The RTT driver provides the interface to configure and use the RTT

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup spi_module Working with SPI
* The SPI driver provides the interface to configure and use the SPI

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/**
* \file

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/**
* \file

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup twi_module Working with TWI
* The TWI driver provides the interface to configure and use the TWI

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/** \addtogroup usart_module Working with USART
* The USART driver provides the interface to configure and use the USART peripheral.\n

View File

@ -1,31 +1,6 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/*
%atmel_license%
*/
/**
* \file