Merge pull request #12093 from p3p/pr_bf2_pulloutlpcframework
[HAL][LPC176x] Pull out framework, improve build, fix things
This commit is contained in:
commit
3d5be2ea4b
318
Marlin/src/HAL/HAL_LPC1768/DebugMonitor_LPC1768.cpp
Normal file
318
Marlin/src/HAL/HAL_LPC1768/DebugMonitor_LPC1768.cpp
Normal file
|
@ -0,0 +1,318 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../core/macros.h"
|
||||
#include "../../core/serial.h"
|
||||
#include <stdarg.h>
|
||||
|
||||
#include "../shared/backtrace/unwinder.h"
|
||||
#include "../shared/backtrace/unwmemaccess.h"
|
||||
#include "watchdog.h"
|
||||
#include <debug_frmwrk.h>
|
||||
|
||||
|
||||
// Debug monitor that dumps to the Programming port all status when
|
||||
// an exception or WDT timeout happens - And then resets the board
|
||||
|
||||
// All the Monitor routines must run with interrupts disabled and
|
||||
// under an ISR execution context. That is why we cannot reuse the
|
||||
// Serial interrupt routines or any C runtime, as we don't know the
|
||||
// state we are when running them
|
||||
|
||||
// A SW memory barrier, to ensure GCC does not overoptimize loops
|
||||
#define sw_barrier() __asm__ volatile("": : :"memory");
|
||||
|
||||
// (re)initialize UART0 as a monitor output to 250000,n,8,1
|
||||
static void TXBegin(void) {
|
||||
}
|
||||
|
||||
// Send character through UART with no interrupts
|
||||
static void TX(char c) {
|
||||
_DBC(c);
|
||||
}
|
||||
|
||||
// Send String through UART
|
||||
static void TX(const char* s) {
|
||||
while (*s) TX(*s++);
|
||||
}
|
||||
|
||||
static void TXDigit(uint32_t d) {
|
||||
if (d < 10) TX((char)(d+'0'));
|
||||
else if (d < 16) TX((char)(d+'A'-10));
|
||||
else TX('?');
|
||||
}
|
||||
|
||||
// Send Hex number thru UART
|
||||
static void TXHex(uint32_t v) {
|
||||
TX("0x");
|
||||
for (uint8_t i = 0; i < 8; i++, v <<= 4)
|
||||
TXDigit((v >> 28) & 0xF);
|
||||
}
|
||||
|
||||
// Send Decimal number thru UART
|
||||
static void TXDec(uint32_t v) {
|
||||
if (!v) {
|
||||
TX('0');
|
||||
return;
|
||||
}
|
||||
|
||||
char nbrs[14];
|
||||
char *p = &nbrs[0];
|
||||
while (v != 0) {
|
||||
*p++ = '0' + (v % 10);
|
||||
v /= 10;
|
||||
}
|
||||
do {
|
||||
p--;
|
||||
TX(*p);
|
||||
} while (p != &nbrs[0]);
|
||||
}
|
||||
|
||||
// Dump a backtrace entry
|
||||
static bool UnwReportOut(void* ctx, const UnwReport* bte) {
|
||||
int* p = (int*)ctx;
|
||||
|
||||
(*p)++;
|
||||
TX('#'); TXDec(*p); TX(" : ");
|
||||
TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function);
|
||||
TX('+'); TXDec(bte->address - bte->function);
|
||||
TX(" PC:");TXHex(bte->address); TX('\n');
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifdef UNW_DEBUG
|
||||
void UnwPrintf(const char* format, ...) {
|
||||
char dest[256];
|
||||
va_list argptr;
|
||||
va_start(argptr, format);
|
||||
vsprintf(dest, format, argptr);
|
||||
va_end(argptr);
|
||||
TX(&dest[0]);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Table of function pointers for passing to the unwinder */
|
||||
static const UnwindCallbacks UnwCallbacks = {
|
||||
UnwReportOut,
|
||||
UnwReadW,
|
||||
UnwReadH,
|
||||
UnwReadB
|
||||
#if defined(UNW_DEBUG)
|
||||
,UnwPrintf
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
/**
|
||||
* HardFaultHandler_C:
|
||||
* This is called from the HardFault_HandlerAsm with a pointer the Fault stack
|
||||
* as the parameter. We can then read the values from the stack and place them
|
||||
* into local variables for ease of reading.
|
||||
* We then read the various Fault Status and Address Registers to help decode
|
||||
* cause of the fault.
|
||||
* The function ends with a BKPT instruction to force control back into the debugger
|
||||
*/
|
||||
extern "C"
|
||||
void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) {
|
||||
|
||||
static const char* causestr[] = {
|
||||
"NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
|
||||
};
|
||||
|
||||
UnwindFrame btf;
|
||||
|
||||
// Dump report to the Programming port (interrupts are DISABLED)
|
||||
TXBegin();
|
||||
TX("\n\n## Software Fault detected ##\n");
|
||||
TX("Cause: "); TX(causestr[cause]); TX('\n');
|
||||
|
||||
TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n');
|
||||
TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n');
|
||||
TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n');
|
||||
TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n');
|
||||
TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n');
|
||||
TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n');
|
||||
TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n');
|
||||
TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n');
|
||||
|
||||
// Configurable Fault Status Register
|
||||
// Consists of MMSR, BFSR and UFSR
|
||||
TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n');
|
||||
|
||||
// Hard Fault Status Register
|
||||
TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n');
|
||||
|
||||
// Debug Fault Status Register
|
||||
TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n');
|
||||
|
||||
// Auxiliary Fault Status Register
|
||||
TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n');
|
||||
|
||||
// Read the Fault Address Registers. These may not contain valid values.
|
||||
// Check BFARVALID/MMARVALID to see if they are valid values
|
||||
// MemManage Fault Address Register
|
||||
TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n');
|
||||
|
||||
// Bus Fault Address Register
|
||||
TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n');
|
||||
|
||||
TX("ExcLR: "); TXHex(lr); TX('\n');
|
||||
TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n');
|
||||
|
||||
btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer
|
||||
btf.fp = btf.sp;
|
||||
btf.lr = ((unsigned long)sp[5]);
|
||||
btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it
|
||||
|
||||
// Perform a backtrace
|
||||
TX("\nBacktrace:\n\n");
|
||||
int ctr = 0;
|
||||
UnwindStart(&btf, &UnwCallbacks, &ctr);
|
||||
|
||||
// Disable all NVIC interrupts
|
||||
NVIC->ICER[0] = 0xFFFFFFFF;
|
||||
NVIC->ICER[1] = 0xFFFFFFFF;
|
||||
|
||||
// Relocate VTOR table to default position
|
||||
SCB->VTOR = 0;
|
||||
|
||||
// Clear cause of reset to prevent entering smoothie bootstrap
|
||||
HAL_clear_reset_source();
|
||||
// Restart watchdog
|
||||
//WDT_Restart(WDT);
|
||||
watchdog_init();
|
||||
|
||||
// Reset controller
|
||||
NVIC_SystemReset();
|
||||
|
||||
while(1) { watchdog_init(); }
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
__attribute__((naked)) void NMI_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#0")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void HardFault_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#1")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void MemManage_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#2")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void BusFault_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#3")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void UsageFault_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#4")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void DebugMon_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#5")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
|
||||
__attribute__((naked)) void WDT_IRQHandler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#6")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void RSTC_Handler(void) {
|
||||
__asm__ __volatile__ (
|
||||
".syntax unified" "\n\t"
|
||||
A("tst lr, #4")
|
||||
A("ite eq")
|
||||
A("mrseq r0, msp")
|
||||
A("mrsne r0, psp")
|
||||
A("mov r1,lr")
|
||||
A("mov r2,#7")
|
||||
A("b HardFault_HandlerC")
|
||||
);
|
||||
}
|
||||
}
|
||||
#endif // TARGET_LPC1768
|
|
@ -22,8 +22,7 @@
|
|||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
HalSerial usb_serial;
|
||||
#include "../../../gcode/parser.h"
|
||||
|
||||
// U8glib required functions
|
||||
extern "C" void u8g_xMicroDelay(uint16_t val) {
|
||||
|
@ -51,231 +50,11 @@ int freeMemory() {
|
|||
return result;
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// ADC
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define ADC_DONE 0x80000000
|
||||
#define ADC_OVERRUN 0x40000000
|
||||
|
||||
void HAL_adc_init(void) {
|
||||
LPC_SC->PCONP |= (1 << 12); // Enable CLOCK for internal ADC controller
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << 24);
|
||||
LPC_SC->PCLKSEL0 |= (0x1 << 24); // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to ADC clock divider
|
||||
LPC_ADC->ADCR = (0 << 0) // SEL: 0 = no channels selected
|
||||
| (0xFF << 8) // select slowest clock for A/D conversion 150 - 190 uS for a complete conversion
|
||||
| (0 << 16) // BURST: 0 = software control
|
||||
| (0 << 17) // CLKS: not applicable
|
||||
| (1 << 21) // PDN: 1 = operational
|
||||
| (0 << 24) // START: 0 = no start
|
||||
| (0 << 27); // EDGE: not applicable
|
||||
}
|
||||
|
||||
// externals need to make the call to KILL compile
|
||||
#include "../../core/language.h"
|
||||
|
||||
extern void kill(PGM_P);
|
||||
|
||||
void HAL_adc_enable_channel(int ch) {
|
||||
pin_t pin = analogInputToDigitalPin(ch);
|
||||
|
||||
if (pin == -1) {
|
||||
serial_error_start();
|
||||
SERIAL_PRINTF("INVALID ANALOG PORT:%d\n", ch);
|
||||
kill(MSG_KILLED);
|
||||
}
|
||||
|
||||
int8_t pin_port = LPC1768_PIN_PORT(pin),
|
||||
pin_port_pin = LPC1768_PIN_PIN(pin),
|
||||
pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
|
||||
uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
|
||||
pin_port == 0 ? 1 :
|
||||
pin_port == 1 ? 3 : 10;
|
||||
|
||||
switch (pin_sel_register) {
|
||||
case 1:
|
||||
LPC_PINCON->PINSEL1 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL1 |= (0x1 << pinsel_start_bit);
|
||||
break;
|
||||
case 3:
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL3 |= (0x3 << pinsel_start_bit);
|
||||
break;
|
||||
case 0:
|
||||
LPC_PINCON->PINSEL0 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL0 |= (0x2 << pinsel_start_bit);
|
||||
break;
|
||||
};
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t ch) {
|
||||
if (analogInputToDigitalPin(ch) == -1) {
|
||||
SERIAL_PRINTF("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
|
||||
return;
|
||||
}
|
||||
|
||||
LPC_ADC->ADCR &= ~0xFF; // Reset
|
||||
SBI(LPC_ADC->ADCR, ch); // Select Channel
|
||||
SBI(LPC_ADC->ADCR, 24); // Start conversion
|
||||
}
|
||||
|
||||
bool HAL_adc_finished(void) {
|
||||
return LPC_ADC->ADGDR & ADC_DONE;
|
||||
}
|
||||
|
||||
// possible config options if something similar is extended to more platforms.
|
||||
#define ADC_USE_MEDIAN_FILTER // Filter out erroneous readings
|
||||
#define ADC_MEDIAN_FILTER_SIZE 23 // Higher values increase step delay (phase shift),
|
||||
// (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
|
||||
// Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
|
||||
// 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
|
||||
|
||||
#define ADC_USE_LOWPASS_FILTER // Filter out high frequency noise
|
||||
#define ADC_LOWPASS_K_VALUE 6 // Higher values increase rise time
|
||||
// Rise time sample delays for 100% signal convergence on full range step
|
||||
// (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
|
||||
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
|
||||
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
||||
|
||||
|
||||
// Sourced from https://embeddedgurus.com/stack-overflow/tag/median-filter/
|
||||
struct MedianFilter {
|
||||
#define STOPPER 0 // Smaller than any datum
|
||||
struct Pair {
|
||||
Pair *point; // Pointers forming list linked in sorted order
|
||||
uint16_t value; // Values to sort
|
||||
};
|
||||
|
||||
Pair buffer[ADC_MEDIAN_FILTER_SIZE] = {}; // Buffer of nwidth pairs
|
||||
Pair *datpoint = buffer; // Pointer into circular buffer of data
|
||||
Pair small = {NULL, STOPPER}; // Chain stopper
|
||||
Pair big = {&small, 0}; // Pointer to head (largest) of linked list.
|
||||
|
||||
uint16_t update(uint16_t datum) {
|
||||
Pair *successor; // Pointer to successor of replaced data item
|
||||
Pair *scan; // Pointer used to scan down the sorted list
|
||||
Pair *scanold; // Previous value of scan
|
||||
Pair *median; // Pointer to median
|
||||
uint16_t i;
|
||||
|
||||
if (datum == STOPPER) {
|
||||
datum = STOPPER + 1; // No stoppers allowed.
|
||||
}
|
||||
|
||||
if ( (++datpoint - buffer) >= (ADC_MEDIAN_FILTER_SIZE)) {
|
||||
datpoint = buffer; // Increment and wrap data in pointer.
|
||||
}
|
||||
|
||||
datpoint->value = datum; // Copy in new datum
|
||||
successor = datpoint->point; // Save pointer to old value's successor
|
||||
median = &big; // Median initially to first in chain
|
||||
scanold = NULL; // Scanold initially null.
|
||||
scan = &big; // Points to pointer to first (largest) datum in chain
|
||||
|
||||
// Handle chain-out of first item in chain as special case
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor;
|
||||
}
|
||||
scanold = scan; // Save this pointer and
|
||||
scan = scan->point ; // step down chain
|
||||
|
||||
// Loop through the chain, normal loop exit via break.
|
||||
for (i = 0 ; i < ADC_MEDIAN_FILTER_SIZE; ++i) {
|
||||
// Handle odd-numbered item in chain
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor; // Chain out the old datum
|
||||
}
|
||||
|
||||
if (scan->value < datum) { // If datum is larger than scanned value
|
||||
datpoint->point = scanold->point; // Chain it in here
|
||||
scanold->point = datpoint; // Mark it chained in
|
||||
datum = STOPPER;
|
||||
}
|
||||
|
||||
// Step median pointer down chain after doing odd-numbered element
|
||||
median = median->point; // Step median pointer
|
||||
if (scan == &small) {
|
||||
break; // Break at end of chain
|
||||
}
|
||||
scanold = scan; // Save this pointer and
|
||||
scan = scan->point; // step down chain
|
||||
|
||||
// Handle even-numbered item in chain.
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor;
|
||||
}
|
||||
|
||||
if (scan->value < datum) {
|
||||
datpoint->point = scanold->point;
|
||||
scanold->point = datpoint;
|
||||
datum = STOPPER;
|
||||
}
|
||||
|
||||
if (scan == &small) {
|
||||
break;
|
||||
}
|
||||
|
||||
scanold = scan;
|
||||
scan = scan->point;
|
||||
}
|
||||
return median->value;
|
||||
}
|
||||
};
|
||||
|
||||
struct LowpassFilter {
|
||||
uint32_t data_delay = 0;
|
||||
uint16_t update(const uint16_t value) {
|
||||
data_delay -= (data_delay >> (ADC_LOWPASS_K_VALUE)) - value;
|
||||
return (uint16_t)(data_delay >> (ADC_LOWPASS_K_VALUE));
|
||||
}
|
||||
};
|
||||
|
||||
uint16_t HAL_adc_get_result(void) {
|
||||
uint32_t adgdr = LPC_ADC->ADGDR;
|
||||
CBI(LPC_ADC->ADCR, 24); // Stop conversion
|
||||
|
||||
if (adgdr & ADC_OVERRUN) return 0;
|
||||
uint16_t data = (adgdr >> 4) & 0xFFF; // copy the 12bit data value
|
||||
uint8_t adc_channel = (adgdr >> 24) & 0x7; // copy the 3bit used channel
|
||||
|
||||
#ifdef ADC_USE_MEDIAN_FILTER
|
||||
static MedianFilter median_filter[NUM_ANALOG_INPUTS];
|
||||
data = median_filter[adc_channel].update(data);
|
||||
#endif
|
||||
|
||||
#ifdef ADC_USE_LOWPASS_FILTER
|
||||
static LowpassFilter lowpass_filter[NUM_ANALOG_INPUTS];
|
||||
data = lowpass_filter[adc_channel].update(data);
|
||||
#endif
|
||||
|
||||
return ((data >> 2) & 0x3FF); // return 10bit value as Marlin expects
|
||||
}
|
||||
|
||||
#define SBIT_CNTEN 0
|
||||
#define SBIT_PWMEN 2
|
||||
#define SBIT_PWMMR0R 1
|
||||
|
||||
#define PWM_1 0 //P2_00 (0-1 Bits of PINSEL4)
|
||||
#define PWM_2 2 //P2_01 (2-3 Bits of PINSEL4)
|
||||
#define PWM_3 4 //P2_02 (4-5 Bits of PINSEL4)
|
||||
#define PWM_4 6 //P2_03 (6-7 Bits of PINSEL4)
|
||||
#define PWM_5 8 //P2_04 (8-9 Bits of PINSEL4)
|
||||
#define PWM_6 10 //P2_05 (10-11 Bits of PINSEL4)
|
||||
|
||||
void HAL_pwm_init(void) {
|
||||
LPC_PINCON->PINSEL4 = _BV(PWM_5) | _BV(PWM_6);
|
||||
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_PWMEN);
|
||||
LPC_PWM1->PR = 0x0; // No prescalar
|
||||
LPC_PWM1->MCR = _BV(SBIT_PWMMR0R); // Reset on PWMMR0, reset TC if it matches MR0
|
||||
LPC_PWM1->MR0 = 255; // set PWM cycle(Ton+Toff)=255)
|
||||
LPC_PWM1->MR5 = 0; // Set 50% Duty Cycle for the channels
|
||||
LPC_PWM1->MR6 = 0;
|
||||
|
||||
// Trigger the latch Enable Bits to load the new Match Values MR0, MR5, MR6
|
||||
LPC_PWM1->LER = _BV(0) | _BV(5) | _BV(6);
|
||||
// Enable the PWM output pins for PWM_5-PWM_6(P2_04 - P2_05)
|
||||
LPC_PWM1->PCR = _BV(13) | _BV(14);
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
|
||||
const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
|
||||
? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
|
||||
return ind > -2 ? ind : dval;
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
||||
|
|
|
@ -29,42 +29,27 @@
|
|||
#define _HAL_LPC1768_H_
|
||||
|
||||
#define CPU_32_BIT
|
||||
#define HAL_INIT
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
void HAL_init();
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
#undef min
|
||||
#undef max
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
void _printf (const char *format, ...);
|
||||
void _putc(uint8_t c);
|
||||
uint8_t _getc();
|
||||
|
||||
extern "C" volatile uint32_t _millis;
|
||||
|
||||
//arduino: Print.h
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
//arduino: binary.h (weird defines)
|
||||
#define B01 1
|
||||
#define B10 2
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
#include <CDCSerial.h>
|
||||
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "fastio.h"
|
||||
#include <adc.h>
|
||||
#include "watchdog.h"
|
||||
#include "HAL_timers.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
//
|
||||
// Default graphical display delays
|
||||
|
@ -79,32 +64,20 @@ extern "C" volatile uint32_t _millis;
|
|||
#define ST7920_DELAY_3 DELAY_NS(750)
|
||||
#endif
|
||||
|
||||
//
|
||||
// Arduino-style serial ports
|
||||
//
|
||||
#include "serial.h"
|
||||
#include "HardwareSerial.h"
|
||||
|
||||
extern HalSerial usb_serial;
|
||||
|
||||
#if !WITHIN(SERIAL_PORT, -1, 3)
|
||||
#error "SERIAL_PORT must be from -1 to 3"
|
||||
#endif
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL0 usb_serial
|
||||
#define MYSERIAL0 UsbSerial
|
||||
#elif SERIAL_PORT == 0
|
||||
extern HardwareSerial Serial;
|
||||
#define MYSERIAL0 Serial
|
||||
#define MYSERIAL0 MSerial
|
||||
#elif SERIAL_PORT == 1
|
||||
extern HardwareSerial Serial1;
|
||||
#define MYSERIAL0 Serial1
|
||||
#define MYSERIAL0 MSerial1
|
||||
#elif SERIAL_PORT == 2
|
||||
extern HardwareSerial Serial2;
|
||||
#define MYSERIAL0 Serial2
|
||||
#define MYSERIAL0 MSerial2
|
||||
#elif SERIAL_PORT == 3
|
||||
#define MYSERIAL0 Serial3
|
||||
extern HardwareSerial Serial3;
|
||||
#define MYSERIAL0 MSerial3
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
|
@ -115,19 +88,15 @@ extern HalSerial usb_serial;
|
|||
#endif
|
||||
#define NUM_SERIAL 2
|
||||
#if SERIAL_PORT_2 == -1
|
||||
#define MYSERIAL1 usb_serial
|
||||
#define MYSERIAL1 UsbSerial
|
||||
#elif SERIAL_PORT_2 == 0
|
||||
extern HardwareSerial Serial;
|
||||
#define MYSERIAL1 Serial
|
||||
#define MYSERIAL1 MSerial
|
||||
#elif SERIAL_PORT_2 == 1
|
||||
extern HardwareSerial Serial1;
|
||||
#define MYSERIAL1 Serial1
|
||||
#define MYSERIAL1 MSerial1
|
||||
#elif SERIAL_PORT_2 == 2
|
||||
extern HardwareSerial Serial2;
|
||||
#define MYSERIAL1 Serial2
|
||||
#define MYSERIAL1 MSerial2
|
||||
#elif SERIAL_PORT_2 == 3
|
||||
extern HardwareSerial Serial3;
|
||||
#define MYSERIAL1 Serial3
|
||||
#define MYSERIAL1 MSerial3
|
||||
#endif
|
||||
#else
|
||||
#define NUM_SERIAL 1
|
||||
|
@ -159,17 +128,33 @@ void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
|
|||
uint8_t spiRec(uint32_t chan);
|
||||
|
||||
//
|
||||
// ADC
|
||||
// ADC API
|
||||
//
|
||||
#define HAL_ANALOG_SELECT(pin) HAL_adc_enable_channel(pin)
|
||||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_READ_ADC() HAL_adc_get_result()
|
||||
#define HAL_ADC_READY() HAL_adc_finished()
|
||||
|
||||
void HAL_adc_init(void);
|
||||
void HAL_adc_enable_channel(int pin);
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
uint16_t HAL_adc_get_result(void);
|
||||
bool HAL_adc_finished(void);
|
||||
#define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
|
||||
// (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
|
||||
// Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
|
||||
// 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
|
||||
|
||||
#define ADC_LOWPASS_K_VALUE (6) // Higher values increase rise time
|
||||
// Rise time sample delays for 100% signal convergence on full range step
|
||||
// (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
|
||||
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
|
||||
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
||||
|
||||
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
||||
#define HAL_adc_init() FilteredADC::init()
|
||||
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
|
||||
#define HAL_START_ADC(pin) FilteredADC::start_conversion(pin)
|
||||
#define HAL_READ_ADC() FilteredADC::get_result()
|
||||
#define HAL_ADC_READY() FilteredADC::finished_conversion()
|
||||
|
||||
// Parse a G-code word into a pin index
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
||||
// P0.6 thru P0.9 are for the onboard SD card
|
||||
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
|
||||
|
||||
#define HAL_IDLETASK 1
|
||||
void HAL_idletask(void);
|
||||
|
||||
#endif // _HAL_LPC1768_H_
|
||||
|
|
|
@ -49,7 +49,6 @@
|
|||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -59,7 +58,6 @@
|
|||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if ENABLED(LPC_SOFTWARE_SPI)
|
||||
|
||||
#include "SoftwareSPI.h"
|
||||
|
@ -127,8 +125,25 @@
|
|||
#include <lpc17xx_ssp.h>
|
||||
#include <lpc17xx_clkpwr.h>
|
||||
|
||||
void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0
|
||||
// decide which HW SPI device to use
|
||||
#ifndef LPC_HW_SPI_DEV
|
||||
#if (SCK_PIN == P0_07 && MISO_PIN == P0_08 && MOSI_PIN == P0_09)
|
||||
#define LPC_HW_SPI_DEV 1
|
||||
#else
|
||||
#if (SCK_PIN == P0_15 && MISO_PIN == P0_17 && MOSI_PIN == P0_18)
|
||||
#define LPC_HW_SPI_DEV 0
|
||||
#else
|
||||
#error "Invalid pins selected for hardware SPI"
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
#if (LPC_HW_SPI_DEV == 0)
|
||||
#define LPC_SSPn LPC_SSP0
|
||||
#else
|
||||
#define LPC_SSPn LPC_SSP1
|
||||
#endif
|
||||
|
||||
void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0
|
||||
PINSEL_CFG_Type PinCfg; // data structure to hold init values
|
||||
PinCfg.Funcnum = 2;
|
||||
PinCfg.OpenDrain = 0;
|
||||
|
@ -147,10 +162,13 @@
|
|||
PinCfg.Portnum = LPC1768_PIN_PORT(MOSI_PIN);
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
SET_OUTPUT(MOSI_PIN);
|
||||
// divide PCLK by 2 for SSP0
|
||||
CLKPWR_SetPCLKDiv(LPC_HW_SPI_DEV == 0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2);
|
||||
spiInit(0);
|
||||
SSP_Cmd(LPC_SSPn, ENABLE); // start SSP running
|
||||
}
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
SSP_Cmd(LPC_SSP0, DISABLE); // Disable SSP0 before changing rate
|
||||
// table to convert Marlin spiRates (0-5 plus default) into bit rates
|
||||
uint32_t Marlin_speed[7]; // CPSR is always 2
|
||||
Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED
|
||||
|
@ -160,33 +178,32 @@
|
|||
Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5
|
||||
Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6
|
||||
Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h
|
||||
|
||||
// divide PCLK by 2 for SSP0
|
||||
CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_SSP0, CLKPWR_PCLKSEL_CCLK_DIV_2);
|
||||
|
||||
// setup for SPI mode
|
||||
SSP_CFG_Type HW_SPI_init; // data structure to hold init values
|
||||
SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode
|
||||
HW_SPI_init.ClockRate = Marlin_speed[MIN(spiRate, 6)]; // put in the specified bit rate
|
||||
SSP_Init(LPC_SSP0, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers
|
||||
HW_SPI_init.Mode |= SSP_CR1_SSP_EN;
|
||||
SSP_Init(LPC_SSPn, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers
|
||||
}
|
||||
|
||||
SSP_Cmd(LPC_SSP0, ENABLE); // start SSP0 running
|
||||
|
||||
static uint8_t doio(uint8_t b) {
|
||||
/* send and receive a single byte */
|
||||
SSP_SendData(LPC_SSPn, b & 0x00FF);
|
||||
while (SSP_GetStatus(LPC_SSPn, SSP_STAT_BUSY)); // wait for it to finish
|
||||
return SSP_ReceiveData(LPC_SSPn) & 0x00FF;
|
||||
}
|
||||
|
||||
void spiSend(uint8_t b) {
|
||||
while (!SSP_GetStatus(LPC_SSP0, SSP_STAT_TXFIFO_NOTFULL)); // wait for room in the buffer
|
||||
SSP_SendData(LPC_SSP0, b & 0x00FF);
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
|
||||
doio(b);
|
||||
}
|
||||
|
||||
|
||||
void spiSend(const uint8_t* buf, size_t n) {
|
||||
if (n == 0) return;
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
while (!SSP_GetStatus(LPC_SSP0, SSP_STAT_TXFIFO_NOTFULL)); // wait for room in the buffer
|
||||
SSP_SendData(LPC_SSP0, buf[i] & 0x00FF);
|
||||
doio(buf[i]);
|
||||
}
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
|
||||
}
|
||||
|
||||
void spiSend(uint32_t chan, byte b) {
|
||||
|
@ -195,17 +212,9 @@
|
|||
void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
|
||||
}
|
||||
|
||||
static uint8_t get_one_byte() {
|
||||
// send a dummy byte so can clock in receive data
|
||||
SSP_SendData(LPC_SSP0,0x00FF);
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
|
||||
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
|
||||
}
|
||||
|
||||
// Read single byte from SPI
|
||||
uint8_t spiRec() {
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
|
||||
return get_one_byte();
|
||||
return doio(0xff);
|
||||
}
|
||||
|
||||
uint8_t spiRec(uint32_t chan) {
|
||||
|
@ -214,22 +223,25 @@
|
|||
|
||||
// Read from SPI into buffer
|
||||
void spiRead(uint8_t*buf, uint16_t nbyte) {
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
|
||||
if (nbyte == 0) return;
|
||||
for (int i = 0; i < nbyte; i++) {
|
||||
buf[i] = get_one_byte();
|
||||
buf[i] = doio(0xff);
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t spiTransfer(uint8_t b) {
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
|
||||
SSP_SendData(LPC_SSP0, b); // send the byte
|
||||
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
|
||||
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
|
||||
return doio(b);
|
||||
}
|
||||
|
||||
// Write from buffer to SPI
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
uint8_t response;
|
||||
response = spiTransfer(token);
|
||||
|
||||
for (uint16_t i = 0; i < 512; i++) {
|
||||
response = spiTransfer(buf[i]);
|
||||
}
|
||||
UNUSED(response);
|
||||
}
|
||||
|
||||
/** Begin SPI transaction, set clock, bit order, data mode */
|
||||
|
@ -270,4 +282,3 @@ uint16_t SPIClass::transfer16(uint16_t data) {
|
|||
SPIClass SPI;
|
||||
|
||||
#endif // TARGET_LPC1768
|
||||
|
||||
|
|
|
@ -1 +0,0 @@
|
|||
// blank file needed until I get platformio to update it's copy of U8Glib-HAL
|
|
@ -20,9 +20,8 @@
|
|||
*/
|
||||
|
||||
/**
|
||||
* HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
* HAL For LPC1768
|
||||
*/
|
||||
|
||||
#ifndef _HAL_TIMERS_H
|
||||
|
|
|
@ -1,576 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*/
|
||||
|
||||
/**
|
||||
* This is a hybrid system.
|
||||
*
|
||||
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins and D9 & D10 pins. This keeps
|
||||
* the pulse width jitter to under a microsecond.
|
||||
*
|
||||
* For all other pins a timer is used to generate interrupts. The ISR
|
||||
* routine does the actual setting/clearing of pins. The upside is that any pin can
|
||||
* have a PWM channel assigned to it. The downside is that there is more pulse width
|
||||
* jitter. The jitter depends on what else is happening in the system and what ISRs
|
||||
* pre-empt the PWM ISR.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The data structures are set up to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 5-14µs depending on how full the
|
||||
* ISR table is. 14uS is for a 20 element ISR table.
|
||||
*
|
||||
* Two tables are used. One table contains the data used by the ISR to update/control
|
||||
* the PWM pins. The other is used as an aid when updating the ISR table.
|
||||
*
|
||||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
/**
|
||||
* Directly controlled PWM pins (
|
||||
* NA means not being used as a directly controlled PWM pin
|
||||
*
|
||||
* Re-ARM MKS Sbase
|
||||
* PWM1.1 P1_18 SERVO3_PIN NA(no connection)
|
||||
* PWM1.1 P2_00 NA(E0_STEP_PIN) NA(X stepper)
|
||||
* PWM1.2 P1_20 SERVO0_PIN NA(no connection)
|
||||
* PWM1.2 P2_01 NA(X_STEP_PIN) NA(Y stepper)
|
||||
* PWM1.3 P1_21 SERVO1_PIN NA(no connection)
|
||||
* PWM1.3 P2_02 NA(Y_STEP_PIN) NA(Z stepper)
|
||||
* PWM1.4 P1_23 NA(SDSS(SSEL0)) SERVO0_PIN
|
||||
* PWM1.4 P2_03 NA(Z_STEP_PIN) NA(E0 stepper)
|
||||
* PWM1.5 P1_24 NA(X_MIN_PIN) NA(X_MIN_pin)
|
||||
* PWM1.5 P2_04 RAMPS_D9_PIN FAN_PIN
|
||||
* PWM1.6 P1_26 NA(Y_MIN_PIN) NA(Y_MIN_pin)
|
||||
* PWM1.6 P2_05 RAMPS_D10_PIN HEATER_BED_PIN
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include <lpc17xx_pinsel.h>
|
||||
#include "LPC1768_PWM.h"
|
||||
#include <Arduino.h>
|
||||
|
||||
#define NUM_ISR_PWMS 20
|
||||
|
||||
#define HAL_PWM_TIMER LPC_TIM3
|
||||
#define HAL_PWM_TIMER_ISR extern "C" void TIMER3_IRQHandler(void)
|
||||
#define HAL_PWM_TIMER_IRQn TIMER3_IRQn
|
||||
|
||||
#define LPC_PORT_OFFSET (0x0020)
|
||||
#define LPC_PIN(pin) (1UL << pin)
|
||||
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
|
||||
|
||||
typedef struct { // holds all data needed to control/init one of the PWM channels
|
||||
bool active_flag; // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
|
||||
pin_t pin;
|
||||
volatile uint32_t* set_register;
|
||||
volatile uint32_t* clr_register;
|
||||
uint32_t write_mask; // USED BY SET/CLEAR COMMANDS
|
||||
uint32_t microseconds; // value written to MR register
|
||||
uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register
|
||||
uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register
|
||||
uint8_t servo_index; // 0 - MAX_SERVO -1 : servo index, 0xFF : PWM channel
|
||||
} PWM_map;
|
||||
|
||||
PWM_map PWM1_map_A[NUM_ISR_PWMS]; // compiler will initialize to all zeros
|
||||
PWM_map PWM1_map_B[NUM_ISR_PWMS]; // compiler will initialize to all zeros
|
||||
|
||||
PWM_map *active_table = PWM1_map_A;
|
||||
PWM_map *work_table = PWM1_map_B;
|
||||
PWM_map *temp_table;
|
||||
|
||||
#define P1_18_PWM_channel 1 // servo 3
|
||||
#define P1_20_PWM_channel 2 // servo 0
|
||||
#define P1_21_PWM_channel 3 // servo 1
|
||||
#define P1_23_PWM_channel 4 // servo 0 for MKS Sbase
|
||||
#define P2_04_PWM_channel 5 // D9
|
||||
#define P2_05_PWM_channel 6 // D10
|
||||
|
||||
typedef struct {
|
||||
uint32_t min;
|
||||
uint32_t max;
|
||||
bool assigned;
|
||||
} table_direct;
|
||||
|
||||
table_direct direct_table[6]; // compiler will initialize to all zeros
|
||||
|
||||
/**
|
||||
* Prescale register and MR0 register values
|
||||
*
|
||||
* 100MHz PCLK 50MHz PCLK 25MHz PCLK 12.5MHz PCLK
|
||||
* ----------------- ----------------- ----------------- -----------------
|
||||
* desired prescale MR0 prescale MR0 prescale MR0 prescale MR0 resolution
|
||||
* prescale register register register register register register register register in degrees
|
||||
* freq value value value value value value value value
|
||||
*
|
||||
* 8 11.5 159,999 5.25 159,999 2.13 159,999 0.5625 159,999 0.023
|
||||
* 4 24 79,999 11.5 79,999 5.25 79,999 2.125 79,999 0.045
|
||||
* 2 49 39,999 24 39,999 11.5 39,999 5.25 39,999 0.090
|
||||
* 1 99 19,999 49 19,999 24 19,999 11.5 19,999 0.180
|
||||
* 0.5 199 9,999 99 9,999 49 9,999 24 9,999 0.360
|
||||
* 0.25 399 4,999 199 4,999 99 4,999 49 4,999 0.720
|
||||
* 0.125 799 2,499 399 2,499 199 2,499 99 2,499 1.440
|
||||
*
|
||||
* The desired prescale frequency column comes from an input in the range of 544 - 2400 microseconds
|
||||
* and the desire to just shift the input left or right as needed.
|
||||
*
|
||||
* A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
|
||||
* It also means we don't need to scale the input.
|
||||
*
|
||||
* The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
|
||||
* MR0 registers.
|
||||
*
|
||||
* Final settings:
|
||||
* PCLKSEL0: 0x0
|
||||
* PWM1PR: 0x018 (24)
|
||||
* PWM1MR0: 0x04E1F (19,999)
|
||||
*
|
||||
*/
|
||||
|
||||
void LPC1768_PWM_init(void) {
|
||||
|
||||
///// directly controlled PWM pins (interrupts not used for these)
|
||||
|
||||
#define SBIT_CNTEN 0 // PWM1 counter & pre-scaler enable/disable
|
||||
#define SBIT_CNTRST 1 // reset counters to known state
|
||||
#define SBIT_PWMEN 3 // 1 - PWM, 0 - timer
|
||||
#define SBIT_PWMMR0R 1
|
||||
#define PCPWM1 6
|
||||
#define PCLK_PWM1 12
|
||||
|
||||
SBI(LPC_SC->PCONP, PCPWM1); // Enable PWM1 controller (enabled on power up)
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
|
||||
LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
|
||||
|
||||
uint32_t PR = (CLKPWR_GetPCLK(CLKPWR_PCLKSEL_PWM1) / 1000000) - 1; // Prescalar to create 1 MHz output
|
||||
|
||||
LPC_PWM1->MR0 = LPC_PWM1_MR0; // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
|
||||
// MR0 must be set before TCR enables the PWM
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST) | _BV(SBIT_PWMEN); // Enable counters, reset counters, set mode to PWM
|
||||
CBI(LPC_PWM1->TCR, SBIT_CNTRST); // Take counters out of reset
|
||||
LPC_PWM1->PR = PR;
|
||||
LPC_PWM1->MCR = _BV(SBIT_PWMMR0R) | _BV(0); // Reset TC if it matches MR0, disable all interrupts except for MR0
|
||||
LPC_PWM1->CTCR = 0; // Disable counter mode (enable PWM mode)
|
||||
LPC_PWM1->LER = 0x07F; // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
|
||||
LPC_PWM1->PCR = 0; // Single edge mode for all channels, PWM1 control of outputs off
|
||||
|
||||
//// interrupt controlled PWM setup
|
||||
|
||||
LPC_SC->PCONP |= 1 << 23; // power on timer3
|
||||
HAL_PWM_TIMER->PR = PR;
|
||||
HAL_PWM_TIMER->MCR = 0x0B; // Interrupt on MR0 & MR1, reset on MR0
|
||||
HAL_PWM_TIMER->MR0 = LPC_PWM1_MR0;
|
||||
HAL_PWM_TIMER->MR1 = 0;
|
||||
HAL_PWM_TIMER->TCR = _BV(0); // enable
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
NVIC_SetPriority(HAL_PWM_TIMER_IRQn, NVIC_EncodePriority(0, 4, 0));
|
||||
}
|
||||
|
||||
|
||||
bool ISR_table_update = false; // flag to tell the ISR that the tables need to be updated & swapped
|
||||
uint8_t ISR_index = 0; // index used by ISR to skip already actioned entries
|
||||
#define COPY_ACTIVE_TABLE for (uint8_t i = 0; i < NUM_ISR_PWMS ; i++) work_table[i] = active_table[i]
|
||||
uint32_t first_MR1_value = LPC_PWM1_MR0 + 1;
|
||||
|
||||
void LPC1768_PWM_sort(void) {
|
||||
|
||||
for (uint8_t i = NUM_ISR_PWMS; --i;) { // (bubble) sort table by microseconds
|
||||
bool didSwap = false;
|
||||
PWM_map temp;
|
||||
for (uint16_t j = 0; j < i; ++j) {
|
||||
if (work_table[j].microseconds > work_table[j + 1].microseconds) {
|
||||
temp = work_table[j + 1];
|
||||
work_table[j + 1] = work_table[j];
|
||||
work_table[j] = temp;
|
||||
didSwap = true;
|
||||
}
|
||||
}
|
||||
if (!didSwap) break;
|
||||
}
|
||||
}
|
||||
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - 1) */, uint8_t servo_index /* = 0xFF */) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF)); // Sometimes the upper byte is garbled
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
direct_table[P1_23_PWM_channel - 1].min = min;
|
||||
direct_table[P1_23_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_23_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
direct_table[P1_20_PWM_channel - 1].min = min;
|
||||
direct_table[P1_20_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_20_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
direct_table[P1_21_PWM_channel - 1].min = min;
|
||||
direct_table[P1_21_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_21_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
direct_table[P1_18_PWM_channel - 1].min = min;
|
||||
direct_table[P1_18_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_18_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
direct_table[P2_04_PWM_channel - 1].min = min;
|
||||
direct_table[P2_04_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P2_04_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
direct_table[P2_05_PWM_channel - 1].min = min;
|
||||
direct_table[P2_05_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P2_05_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn); // make it safe to update the active table
|
||||
// OK to update the active table because the
|
||||
// ISR doesn't use any of the changed items
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (ISR_table_update) //use work table if that's the newest
|
||||
temp_table = work_table;
|
||||
else
|
||||
temp_table = active_table;
|
||||
|
||||
uint8_t slot = 0;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if already in table
|
||||
if (temp_table[i].pin == pin) {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 1;
|
||||
}
|
||||
|
||||
for (uint8_t i = 1; (i < NUM_ISR_PWMS + 1) && !slot; i++) // find empty slot
|
||||
if ( !(temp_table[i - 1].set_register)) { slot = i; break; } // any item that can't be zero when active or just attached is OK
|
||||
|
||||
if (!slot) {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 0;
|
||||
}
|
||||
|
||||
slot--; // turn it into array index
|
||||
|
||||
temp_table[slot].pin = pin; // init slot
|
||||
temp_table[slot].set_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
|
||||
temp_table[slot].clr_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
|
||||
temp_table[slot].write_mask = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
temp_table[slot].min = min;
|
||||
temp_table[slot].max = max; // different max for ISR PWMs than for direct PWMs
|
||||
temp_table[slot].servo_index = servo_index;
|
||||
temp_table[slot].active_flag = false;
|
||||
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_23_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 14); // return pin to general purpose I/O
|
||||
direct_table[P1_23_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_20_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 8); // return pin to general purpose I/O
|
||||
direct_table[P1_20_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_21_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
direct_table[P1_21_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_18_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
direct_table[P1_18_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P2_04_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
direct_table[P2_04_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P2_05_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
direct_table[P2_05_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (ISR_table_update) {
|
||||
ISR_table_update = false; // don't update yet - have another update to do
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
}
|
||||
else {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
}
|
||||
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) { // find slot
|
||||
if (work_table[i].pin == pin) {
|
||||
slot = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (slot == 0xFF) // return error if pin not found
|
||||
return false;
|
||||
|
||||
work_table[slot] = {0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
LPC1768_PWM_sort(); // sort table by microseconds
|
||||
ISR_table_update = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// value is 0-20,000 microseconds (0% to 100% duty cycle)
|
||||
// servo routine provides values in the 544 - 2400 range
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_23_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 = 0x2 << 14; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR4 = MAX(MIN(value, direct_table[P1_23_PWM_channel - 1].max), direct_table[P1_23_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_23_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_20_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 8; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR2 = MAX(MIN(value, direct_table[P1_20_PWM_channel - 1].max), direct_table[P1_20_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_20_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_21_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 10; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR3 = MAX(MIN(value, direct_table[P1_21_PWM_channel - 1].max), direct_table[P1_21_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_21_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_18_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 4; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR1 = MAX(MIN(value, direct_table[P1_18_PWM_channel - 1].max), direct_table[P1_18_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_18_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P2_04_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 |= 0x1 << 8; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR5 = MAX(MIN(value, direct_table[P2_04_PWM_channel - 1].max), direct_table[P2_04_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P2_04_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P2_05_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 |= 0x1 << 10; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR6 = MAX(MIN(value, direct_table[P2_05_PWM_channel - 1].max), direct_table[P2_05_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P2_05_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (!ISR_table_update) // use the most up to date table
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // find slot
|
||||
if (work_table[i].pin == pin) { slot = i; break; }
|
||||
if (slot == 0xFF) { // return error if pin not found
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
return false;
|
||||
}
|
||||
|
||||
work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);;
|
||||
work_table[slot].active_flag = true;
|
||||
|
||||
LPC1768_PWM_sort(); // sort table by microseconds
|
||||
ISR_table_update = true;
|
||||
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool useable_hardware_PWM(pin_t pin) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
bool return_flag = false;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if it's already setup
|
||||
if (active_table[i].pin == pin) return_flag = true;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if there is an empty slot
|
||||
if (!active_table[i].set_register) return_flag = true;
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return return_flag;
|
||||
}
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
#define PWM_LPC1768_ISR_SAFETY_FACTOR 5 // amount of time needed to guarantee MR1 count will be above TC
|
||||
volatile bool in_PWM_isr = false;
|
||||
|
||||
HAL_PWM_TIMER_ISR {
|
||||
bool first_active_entry = true;
|
||||
uint32_t next_MR1_val;
|
||||
|
||||
if (in_PWM_isr) goto exit_PWM_ISR; // prevent re-entering this ISR
|
||||
in_PWM_isr = true;
|
||||
|
||||
if (HAL_PWM_TIMER->IR & 0x01) { // MR0 interrupt
|
||||
next_MR1_val = first_MR1_value; // only used if have a blank ISR table
|
||||
if (ISR_table_update) { // new values have been loaded so swap tables
|
||||
temp_table = active_table;
|
||||
active_table = work_table;
|
||||
work_table = temp_table;
|
||||
ISR_table_update = false;
|
||||
}
|
||||
}
|
||||
HAL_PWM_TIMER->IR = 0x3F; // clear all interrupts
|
||||
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) {
|
||||
if (active_table[i].active_flag) {
|
||||
if (first_active_entry) {
|
||||
first_active_entry = false;
|
||||
next_MR1_val = active_table[i].microseconds;
|
||||
}
|
||||
if (HAL_PWM_TIMER->TC < active_table[i].microseconds) {
|
||||
*active_table[i].set_register = active_table[i].write_mask; // set pin high
|
||||
}
|
||||
else {
|
||||
*active_table[i].clr_register = active_table[i].write_mask; // set pin low
|
||||
next_MR1_val = (i == NUM_ISR_PWMS -1)
|
||||
? LPC_PWM1_MR0 + 1 // done with table, wait for MR0
|
||||
: active_table[i + 1].microseconds; // set next MR1 interrupt?
|
||||
}
|
||||
}
|
||||
}
|
||||
if (first_active_entry) next_MR1_val = LPC_PWM1_MR0 + 1; // empty table so disable MR1 interrupt
|
||||
HAL_PWM_TIMER->MR1 = MAX(next_MR1_val, HAL_PWM_TIMER->TC + PWM_LPC1768_ISR_SAFETY_FACTOR); // set next
|
||||
in_PWM_isr = false;
|
||||
|
||||
exit_PWM_ISR:
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
///////////////// HARDWARE FIRMWARE INTERACTION ////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
/**
|
||||
* There are two distinct systems used for PWMs:
|
||||
* directly controlled pins
|
||||
* ISR controlled pins.
|
||||
*
|
||||
* The two systems are independent of each other. The use the same counter frequency so there's no
|
||||
* translation needed when setting the time values. The init, attach, detach and write routines all
|
||||
* start with the direct pin code which is followed by the ISR pin code.
|
||||
*
|
||||
* The PMW1 module handles the directly controlled pins. Each directly controlled pin is associated
|
||||
* with a match register (MR1 - MR6). When the associated MR equals the module's TIMER/COUNTER (TC)
|
||||
* then the pins is set to low. The MR0 register controls the repetition rate. When the TC equals
|
||||
* MR0 then the TC is reset and ALL directly controlled pins are set high. The resulting pulse widths
|
||||
* are almost immune to system loading and ISRs. No PWM1 interrupts are used.
|
||||
*
|
||||
* The ISR controlled pins use the TIMER/COUNTER, MR0 and MR1 registers from one timer. MR0 controls
|
||||
* period of the controls the repetition rate. When the TC equals MR0 then the TC is reset and an
|
||||
* interrupt is generated. When the TC equals MR1 then an interrupt is generated.
|
||||
*
|
||||
* Each interrupt does the following:
|
||||
* 1) Swaps the tables if it's a MR0 interrupt and the swap flag is set. It then clears the swap flag.
|
||||
* 2) Scans the entire ISR table (it's been sorted low to high time)
|
||||
* a. If its the first active entry then it grabs the time as a tentative time for MR1
|
||||
* b. If active and TC is less than the time then it sets the pin high
|
||||
* c. If active and TC is more than the time it sets the pin high
|
||||
* d. On every entry that sets a pin low it grabs the NEXT entry's time for use as the next MR1.
|
||||
* This results in MR1 being set to the time in the first active entry that does NOT set a
|
||||
* pin low.
|
||||
* e. If it's setting the last entry's pin low then it sets MR1 to a value bigger than MR0
|
||||
* f. If no value has been grabbed for the next MR1 then it's an empty table and MR1 is set to a
|
||||
* value greater than MR0
|
||||
*/
|
|
@ -1,79 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*/
|
||||
|
||||
/**
|
||||
* This is a hybrid system.
|
||||
*
|
||||
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins. This keeps
|
||||
* the pulse width jitter to under a microsecond.
|
||||
*
|
||||
* For all other pins the PWM1 module is used to generate interrupts. The ISR
|
||||
* routine does the actual setting/clearing of pins. The upside is that any pin can
|
||||
* have a PWM channel assigned to it. The downside is that there is more pulse width
|
||||
* jitter. The jitter depends on what else is happening in the system and what ISRs
|
||||
* prempt the PWM ISR. Writing to the SD card can add 20 microseconds to the pulse
|
||||
* width.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The data structures are setup to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 2.2 - 3.7 microseconds.
|
||||
*
|
||||
* Two tables are used. active_table is used by the ISR. Changes to the table are
|
||||
* are done by copying the active_table into the work_table, updating the work_table
|
||||
* and then swapping the two tables. Swapping is done by manipulating pointers.
|
||||
*
|
||||
* Immediately after the swap the ISR uses the work_table until the start of the
|
||||
* next 20mS cycle. During this transition the "work_table" is actually the table
|
||||
* that was being used before the swap. The "active_table" contains the data that
|
||||
* will start being used at the start of the next 20mS period. This keeps the pins
|
||||
* well behaved during the transition.
|
||||
*
|
||||
* The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
|
||||
* jitter in the PWM high time.
|
||||
*
|
||||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
#ifndef _LPC1768_PWM_H_
|
||||
#define _LPC1768_PWM_H_
|
||||
|
||||
#include <pinmapping.h>
|
||||
#include <lpc17xx_clkpwr.h>
|
||||
|
||||
#define LPC_PWM1_MR0 19999 // base repetition rate minus one count - 20mS
|
||||
#define LPC_PWM1_PCLKSEL0 CLKPWR_PCLKSEL_CCLK_DIV_4 // select clock divider for prescaler - defaults to 4 on power up
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
void LPC1768_PWM_init(void);
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min=1, uint32_t max=(LPC_PWM1_MR0 - (MR0_MARGIN)), uint8_t servo_index=0xFF);
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value);
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin);
|
||||
bool useable_hardware_PWM(pin_t pin);
|
||||
|
||||
#endif // _LPC1768_PWM_H_
|
|
@ -1,163 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Based on servo.cpp - Interrupt driven Servo library for Arduino using 16 bit
|
||||
* timers- Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
*/
|
||||
|
||||
/**
|
||||
* A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
|
||||
* The servos are pulsed in the background using the value most recently written using the write() method
|
||||
*
|
||||
* Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
|
||||
* Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
|
||||
*
|
||||
* The methods are:
|
||||
*
|
||||
* Servo - Class for manipulating servo motors connected to Arduino pins.
|
||||
*
|
||||
* attach(pin) - Attach a servo motor to an i/o pin.
|
||||
* attach(pin, min, max) - Attach to a pin, setting min and max values in microseconds
|
||||
* Default min is 544, max is 2400
|
||||
*
|
||||
* write() - Set the servo angle in degrees. (Invalid angles —over MIN_PULSE_WIDTH— are treated as µs.)
|
||||
* writeMicroseconds() - Set the servo pulse width in microseconds.
|
||||
* move(pin, angle) - Sequence of attach(pin), write(angle), safe_delay(servo_delay[servoIndex]).
|
||||
* With DEACTIVATE_SERVOS_AFTER_MOVE it detaches after servo_delay[servoIndex].
|
||||
* read() - Get the last-written servo pulse width as an angle between 0 and 180.
|
||||
* readMicroseconds() - Get the last-written servo pulse width in microseconds.
|
||||
* attached() - Return true if a servo is attached.
|
||||
* detach() - Stop an attached servo from pulsing its i/o pin.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The only time that this library wants physical movement is when a WRITE
|
||||
* command is issued. Before that all the attach & detach activity is solely
|
||||
* within the data base.
|
||||
*
|
||||
* The PWM output is inactive until the first WRITE. After that it stays active
|
||||
* unless DEACTIVATE_SERVOS_AFTER_MOVE is enabled and a MOVE command was issued.
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "LPC1768_PWM.h"
|
||||
#include "LPC1768_Servo.h"
|
||||
#include "servo_private.h"
|
||||
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
|
||||
#define US_TO_PULSE_WIDTH(p) p
|
||||
#define PULSE_WIDTH_TO_US(p) p
|
||||
#define TRIM_DURATION 0
|
||||
#define SERVO_MIN() MIN_PULSE_WIDTH // minimum value in uS for this servo
|
||||
#define SERVO_MAX() MAX_PULSE_WIDTH // maximum value in uS for this servo
|
||||
|
||||
Servo::Servo() {
|
||||
if (ServoCount < MAX_SERVOS) {
|
||||
this->servoIndex = ServoCount++; // assign a servo index to this instance
|
||||
servo_info[this->servoIndex].pulse_width = US_TO_PULSE_WIDTH(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||
}
|
||||
else
|
||||
this->servoIndex = INVALID_SERVO; // too many servos
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin) {
|
||||
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin, const int min, const int max) {
|
||||
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
|
||||
if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin; // only assign a pin value if the pin info is
|
||||
// greater than zero. This way the init routine can
|
||||
// assign the pin and the MOVE command only needs the value.
|
||||
|
||||
this->min = MIN_PULSE_WIDTH; //resolution of min/max is 1 uS
|
||||
this->max = MAX_PULSE_WIDTH;
|
||||
|
||||
servo_info[this->servoIndex].Pin.isActive = true;
|
||||
|
||||
return this->servoIndex;
|
||||
}
|
||||
|
||||
void Servo::detach() {
|
||||
servo_info[this->servoIndex].Pin.isActive = false;
|
||||
}
|
||||
|
||||
void Servo::write(int value) {
|
||||
if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
|
||||
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
|
||||
// odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
|
||||
// zero degrees should be 500 microseconds and 180 should be 2500
|
||||
}
|
||||
this->writeMicroseconds(value);
|
||||
}
|
||||
|
||||
void Servo::writeMicroseconds(int value) {
|
||||
// calculate and store the values for the given channel
|
||||
byte channel = this->servoIndex;
|
||||
if (channel < MAX_SERVOS) { // ensure channel is valid
|
||||
// ensure pulse width is valid
|
||||
value = constrain(value, SERVO_MIN(), SERVO_MAX()) - (TRIM_DURATION);
|
||||
value = US_TO_PULSE_WIDTH(value); // convert to pulse_width after compensating for interrupt overhead - 12 Aug 2009
|
||||
|
||||
servo_info[channel].pulse_width = value;
|
||||
LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex);
|
||||
LPC1768_PWM_write(servo_info[this->servoIndex].Pin.nbr, value);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// return the value as degrees
|
||||
int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
|
||||
|
||||
int Servo::readMicroseconds() {
|
||||
return (this->servoIndex == INVALID_SERVO) ? 0 : PULSE_WIDTH_TO_US(servo_info[this->servoIndex].pulse_width) + TRIM_DURATION;
|
||||
}
|
||||
|
||||
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
|
||||
|
||||
void Servo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) { // notice the pin number is zero here
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
LPC1768_PWM_detach_pin(servo_info[this->servoIndex].Pin.nbr); // shut down the PWM signal
|
||||
LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex); // make sure no one else steals the slot
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_SERVOS
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,62 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* The PWM1 module is only used to generate interrups at specified times. It
|
||||
* is NOT used to directly toggle pins. The ISR writes to the pin assigned to
|
||||
* that interrupt
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef LPC1768_SERVO_H
|
||||
#define LPC1768_SERVO_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
class Servo {
|
||||
public:
|
||||
Servo();
|
||||
int8_t attach(const int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
|
||||
int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
|
||||
void detach();
|
||||
void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
|
||||
void writeMicroseconds(int value); // write pulse width in microseconds
|
||||
void move(const int value); // attach the servo, then move to value
|
||||
// if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
|
||||
// if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
|
||||
int read(); // returns current pulse width as an angle between 0 and 180 degrees
|
||||
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
|
||||
bool attached(); // return true if this servo is attached, otherwise false
|
||||
|
||||
private:
|
||||
uint8_t servoIndex; // index into the channel data for this servo
|
||||
int min;
|
||||
int max;
|
||||
};
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
#endif // LPC1768_SERVO_H
|
56
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp
Normal file
56
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp
Normal file
|
@ -0,0 +1,56 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0)
|
||||
MarlinSerial MSerial(LPC_UART0);
|
||||
extern "C" void UART0_IRQHandler(void) {
|
||||
MSerial.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 1) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 1)
|
||||
MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
|
||||
extern "C" void UART1_IRQHandler(void) {
|
||||
MSerial1.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 2) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 2)
|
||||
MarlinSerial MSerial2(LPC_UART2);
|
||||
extern "C" void UART2_IRQHandler(void) {
|
||||
MSerial2.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 3) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 3)
|
||||
MarlinSerial MSerial3(LPC_UART3);
|
||||
extern "C" void UART3_IRQHandler(void) {
|
||||
MSerial3.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TARGET_LPC1768
|
71
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h
Normal file
71
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h
Normal file
|
@ -0,0 +1,71 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef MARLINSERIAL_H
|
||||
#define MARLINSERIAL_H
|
||||
#include <HardwareSerial.h>
|
||||
#include <WString.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/emergency_parser.h"
|
||||
#endif
|
||||
|
||||
#ifndef SERIAL_PORT
|
||||
#define SERIAL_PORT 0
|
||||
#endif
|
||||
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#define TX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
class MarlinSerial : public HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE> {
|
||||
public:
|
||||
MarlinSerial(LPC_UART_TypeDef *UARTx) :
|
||||
HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE>(UARTx)
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
, emergency_state(EmergencyParser::State::EP_RESET)
|
||||
#endif
|
||||
{
|
||||
}
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
bool recv_callback(const char c) override {
|
||||
emergency_parser.update(emergency_state, c);
|
||||
return true; // do not discard character
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern MarlinSerial MSerial;
|
||||
extern MarlinSerial MSerial1;
|
||||
extern MarlinSerial MSerial2;
|
||||
extern MarlinSerial MSerial3;
|
||||
|
||||
#endif // MARLINSERIAL_H
|
|
@ -50,35 +50,25 @@
|
|||
#ifndef SERVO_PRIVATE_H
|
||||
#define SERVO_PRIVATE_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <Servo.h>
|
||||
|
||||
// Macros
|
||||
//values in microseconds
|
||||
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
|
||||
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
|
||||
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
|
||||
#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds
|
||||
class MarlinServo: public Servo {
|
||||
public:
|
||||
void move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
|
||||
#define MAX_SERVOS 4
|
||||
if (this->attach(servo_info[this->servoIndex].Pin.nbr) >= 0) { // try to reattach
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]); // delay to allow servo to reach position
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
#endif
|
||||
}
|
||||
|
||||
#define INVALID_SERVO 255 // flag indicating an invalid servo index
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
// Types
|
||||
|
||||
typedef struct {
|
||||
uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin)
|
||||
uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false
|
||||
} ServoPin_t;
|
||||
|
||||
typedef struct {
|
||||
ServoPin_t Pin;
|
||||
unsigned int pulse_width; // pulse width in microseconds
|
||||
} ServoInfo_t;
|
||||
|
||||
// Global variables
|
||||
|
||||
extern uint8_t ServoCount;
|
||||
extern ServoInfo_t servo_info[MAX_SERVOS];
|
||||
#define HAL_SERVO_LIB MarlinServo
|
||||
|
||||
#endif // SERVO_PRIVATE_H
|
|
@ -1,90 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Software SPI functions originally from Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*/
|
||||
|
||||
/**
|
||||
* For TARGET_LPC1768
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* This software SPI runs at multiple rates. The SD software provides an index
|
||||
* (spiRate) of 0-6. The mapping is:
|
||||
* 0 - about 5 MHz peak (6 MHz on LPC1769)
|
||||
* 1-2 - about 2 MHz peak
|
||||
* 3 - about 1 MHz peak
|
||||
* 4 - about 500 kHz peak
|
||||
* 5 - about 250 kHz peak
|
||||
* 6 - about 125 kHz peak
|
||||
*/
|
||||
|
||||
uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (spi_speed == 0) {
|
||||
WRITE(mosi_pin, !!(b & 0x80));
|
||||
WRITE(sck_pin, HIGH);
|
||||
b <<= 1;
|
||||
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
|
||||
WRITE(sck_pin, LOW);
|
||||
}
|
||||
else {
|
||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||
for (uint8_t j = 0; j < spi_speed; j++)
|
||||
WRITE(mosi_pin, state);
|
||||
|
||||
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
||||
WRITE(sck_pin, HIGH);
|
||||
|
||||
b <<= 1;
|
||||
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
|
||||
|
||||
for (uint8_t j = 0; j < spi_speed; j++)
|
||||
WRITE(sck_pin, LOW);
|
||||
}
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
|
||||
SET_OUTPUT(sck_pin);
|
||||
if (VALID_PIN(miso_pin)) SET_INPUT(miso_pin);
|
||||
SET_OUTPUT(mosi_pin);
|
||||
}
|
||||
|
||||
uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) {
|
||||
WRITE(mosi_pin, HIGH);
|
||||
WRITE(sck_pin, LOW);
|
||||
return (SystemCoreClock == 120000000 ? 44 : 38) / POW(2, 6 - MIN(spiRate, 6));
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,50 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef _SOFTWARE_SPI_H_
|
||||
#define _SOFTWARE_SPI_H_
|
||||
|
||||
#include <pinmapping.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* This software SPI runs at multiple rates. The SD software provides an index
|
||||
* (spiRate) of 0-6. The mapping is:
|
||||
* 0 - about 5 MHz peak (6 MHz on LPC1769)
|
||||
* 1-2 - about 2 MHz peak
|
||||
* 3 - about 1 MHz peak
|
||||
* 4 - about 500 kHz peak
|
||||
* 5 - about 250 kHz peak
|
||||
* 6 - about 125 kHz peak
|
||||
*/
|
||||
|
||||
void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
|
||||
|
||||
// Returns the spi_speed value to be passed to swSpiTransfer
|
||||
uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin);
|
||||
|
||||
uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
|
||||
|
||||
#endif // _SOFTWARE_SPI_H_
|
|
@ -1,162 +0,0 @@
|
|||
/**
|
||||
* Copyright (c) 2011-2012 Arduino. All right reserved.
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#define GNUM 31
|
||||
|
||||
typedef void (*interruptCB)(void);
|
||||
|
||||
static interruptCB callbacksP0[GNUM] = {};
|
||||
static interruptCB callbacksP2[GNUM] = {};
|
||||
|
||||
extern "C" void GpioEnableInt(const uint32_t port, const uint32_t pin, const uint32_t mode);
|
||||
extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin);
|
||||
|
||||
|
||||
static void __initialize() {
|
||||
NVIC_SetPriority(EINT3_IRQn, NVIC_EncodePriority(0, 1, 0));
|
||||
NVIC_EnableIRQ(EINT3_IRQn);
|
||||
}
|
||||
|
||||
void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode) {
|
||||
static int enabled = 0;
|
||||
|
||||
if (!INTERRUPT_PIN(pin)) return;
|
||||
|
||||
if (!enabled) {
|
||||
__initialize();
|
||||
++enabled;
|
||||
}
|
||||
|
||||
uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
if (myport == 0)
|
||||
callbacksP0[mypin] = callback;
|
||||
else
|
||||
callbacksP2[mypin] = callback;
|
||||
|
||||
// Enable interrupt
|
||||
GpioEnableInt(myport,mypin,mode);
|
||||
}
|
||||
|
||||
void detachInterrupt(const pin_t pin) {
|
||||
if (!INTERRUPT_PIN(pin)) return;
|
||||
|
||||
const uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
// Disable interrupt
|
||||
GpioDisableInt(myport, mypin);
|
||||
|
||||
// unset callback
|
||||
if (myport == 0)
|
||||
callbacksP0[mypin] = 0;
|
||||
else //if (myport == 2 )
|
||||
callbacksP2[mypin] = 0;
|
||||
}
|
||||
|
||||
|
||||
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode) {
|
||||
//pin here is the processor pin, not logical pin
|
||||
if (port == 0) {
|
||||
LPC_GPIOINT->IO0IntClr = _BV(pin);
|
||||
if (mode == RISING) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
}
|
||||
else if (mode == FALLING) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
}
|
||||
else if (mode == CHANGE) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
SBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
}
|
||||
}
|
||||
else {
|
||||
LPC_GPIOINT->IO2IntClr = _BV(pin);
|
||||
if (mode == RISING) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
}
|
||||
else if (mode == FALLING) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
}
|
||||
else if (mode == CHANGE) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
SBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin) {
|
||||
if (port == 0) {
|
||||
CBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
LPC_GPIOINT->IO0IntClr = _BV(pin);
|
||||
}
|
||||
else {
|
||||
CBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
LPC_GPIOINT->IO2IntClr = _BV(pin);
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void EINT3_IRQHandler(void) {
|
||||
// Read in all current interrupt registers. We do this once as the
|
||||
// GPIO interrupt registers are on the APB bus, and this is slow.
|
||||
uint32_t rise0 = LPC_GPIOINT->IO0IntStatR,
|
||||
fall0 = LPC_GPIOINT->IO0IntStatF,
|
||||
rise2 = LPC_GPIOINT->IO2IntStatR,
|
||||
fall2 = LPC_GPIOINT->IO2IntStatF;
|
||||
|
||||
// Clear the interrupts ASAP
|
||||
LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
|
||||
NVIC_ClearPendingIRQ(EINT3_IRQn);
|
||||
|
||||
while (rise0 > 0) { // If multiple pins changes happened continue as long as there are interrupts pending
|
||||
const uint8_t bitloc = 31 - __CLZ(rise0); // CLZ returns number of leading zeros, 31 minus that is location of first pending interrupt
|
||||
if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
|
||||
rise0 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while (fall0 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(fall0);
|
||||
if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
|
||||
fall0 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while(rise2 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(rise2);
|
||||
if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
|
||||
rise2 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while (fall2 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(fall2);
|
||||
if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
|
||||
fall2 -= _BV(bitloc);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,179 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "LPC1768_PWM.h"
|
||||
#include <lpc17xx_pinsel.h>
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
// Interrupts
|
||||
void cli(void) { __disable_irq(); } // Disable
|
||||
void sei(void) { __enable_irq(); } // Enable
|
||||
|
||||
// Time functions
|
||||
void _delay_ms(const int delay_ms) {
|
||||
delay(delay_ms);
|
||||
}
|
||||
|
||||
uint32_t millis() {
|
||||
return _millis;
|
||||
}
|
||||
|
||||
// This is required for some Arduino libraries we are using
|
||||
void delayMicroseconds(uint32_t us) {
|
||||
DELAY_US(us);
|
||||
}
|
||||
|
||||
extern "C" void delay(const int msec) {
|
||||
volatile millis_t end = _millis + msec;
|
||||
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
|
||||
// this could extend the time between systicks by upto 1ms
|
||||
while PENDING(_millis, end) __WFE();
|
||||
}
|
||||
|
||||
// IO functions
|
||||
// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
|
||||
void pinMode(const pin_t pin, const uint8_t mode) {
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
|
||||
LPC1768_PIN_PIN(pin),
|
||||
PINSEL_FUNC_0,
|
||||
PINSEL_PINMODE_TRISTATE,
|
||||
PINSEL_PINMODE_NORMAL };
|
||||
switch (mode) {
|
||||
case INPUT:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
break;
|
||||
case OUTPUT:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLUP;
|
||||
break;
|
||||
case INPUT_PULLDOWN:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLDOWN;
|
||||
break;
|
||||
default: return;
|
||||
}
|
||||
PINSEL_ConfigPin(&config);
|
||||
}
|
||||
|
||||
void digitalWrite(pin_t pin, uint8_t pin_status) {
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
if (pin_status)
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
else
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
|
||||
pinMode(pin, OUTPUT); // Set pin mode on every write (Arduino version does this)
|
||||
|
||||
/**
|
||||
* Must be done AFTER the output state is set. Doing this before will cause a
|
||||
* 2uS glitch if writing a "1".
|
||||
*
|
||||
* When the Port Direction bit is written to a "1" the output is immediately set
|
||||
* to the value of the FIOPIN bit which is "0" because of power up defaults.
|
||||
*/
|
||||
}
|
||||
|
||||
bool digitalRead(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) return false;
|
||||
|
||||
return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
|
||||
}
|
||||
|
||||
void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
static bool out_of_PWM_slots = false;
|
||||
|
||||
uint value = MAX(MIN(pwm_value, 255), 0);
|
||||
if (value == 0 || value == 255) { // treat as digital pin
|
||||
LPC1768_PWM_detach_pin(pin); // turn off PWM
|
||||
digitalWrite(pin, value);
|
||||
}
|
||||
else {
|
||||
if (LPC1768_PWM_attach_pin(pin, 1, LPC_PWM1->MR0, 0xFF))
|
||||
LPC1768_PWM_write(pin, map(value, 0, 255, 1, LPC_PWM1->MR0)); // map 1-254 onto PWM range
|
||||
else { // out of PWM channels
|
||||
if (!out_of_PWM_slots) SERIAL_ECHOPGM(".\nWARNING - OUT OF PWM CHANNELS\n.\n"); //only warn once
|
||||
out_of_PWM_slots = true;
|
||||
digitalWrite(pin, value); // treat as a digital pin if out of channels
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
extern bool HAL_adc_finished();
|
||||
|
||||
uint16_t analogRead(pin_t adc_pin) {
|
||||
HAL_adc_start_conversion(adc_pin);
|
||||
while (!HAL_adc_finished()); // Wait for conversion to finish
|
||||
return HAL_adc_get_result();
|
||||
}
|
||||
|
||||
// **************************
|
||||
// Persistent Config Storage
|
||||
// **************************
|
||||
|
||||
void eeprom_write_byte(uint8_t *pos, unsigned char value) {
|
||||
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t * pos) { return '\0'; }
|
||||
|
||||
void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
|
||||
|
||||
void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
|
||||
|
||||
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
|
||||
char format_string[20];
|
||||
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
|
||||
sprintf(__s, format_string, __val);
|
||||
return __s;
|
||||
}
|
||||
|
||||
int32_t random(int32_t max) {
|
||||
return rand() % max;
|
||||
}
|
||||
|
||||
int32_t random(int32_t min, int32_t max) {
|
||||
return min + rand() % (max - min);
|
||||
}
|
||||
|
||||
void randomSeed(uint32_t value) {
|
||||
srand(value);
|
||||
}
|
||||
|
||||
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max) {
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,21 +0,0 @@
|
|||
Import("env")
|
||||
|
||||
env.AddPostAction(
|
||||
"$BUILD_DIR/firmware.hex",
|
||||
env.VerboseAction(" ".join([
|
||||
"sed", "-i.bak",
|
||||
"s/:10040000FFFFFFFFFFFFFFFFFFFFFFFFDEF9FFFF23/:10040000FFFFFFFFFFFFFFFFFFFFFFFFFEFFFFFFFD/",
|
||||
"$BUILD_DIR/firmware.hex"
|
||||
]), "Fixing $BUILD_DIR/firmware.hex secure flash flags"))
|
||||
env.AddPreAction(
|
||||
"upload",
|
||||
env.VerboseAction(" ".join([
|
||||
"echo",
|
||||
"'h\\nloadfile $BUILD_DIR/firmware.hex\\nr\\nq\\n'",
|
||||
">$BUILD_DIR/aux.jlink"
|
||||
]), "Creating auxiliary files"))
|
||||
|
||||
env.Replace(
|
||||
UPLOADHEXCMD=
|
||||
'JLinkExe -device MK20DX256xxx7 -speed 4000 -if swd -autoconnect 1 -CommanderScript $BUILD_DIR/aux.jlink -SkipProgOnCRCMatch = 1 -VerifyDownload = 1'
|
||||
)
|
|
@ -35,27 +35,23 @@
|
|||
#ifndef _FASTIO_LPC1768_H
|
||||
#define _FASTIO_LPC1768_H
|
||||
|
||||
#include <LPC17xx.h>
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
|
||||
bool useable_hardware_PWM(pin_t pin);
|
||||
#define USEABLE_HARDWARE_PWM(pin) useable_hardware_PWM(pin)
|
||||
|
||||
#define LPC_PORT_OFFSET (0x0020)
|
||||
#define LPC_PIN(pin) (1UL << pin)
|
||||
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
|
||||
#define LPC_PIN(pin) gpio_pin(pin)
|
||||
#define LPC_GPIO(port) gpio_port(port)
|
||||
|
||||
#define SET_DIR_INPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define SET_DIR_OUTPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define SET_DIR_INPUT(IO) gpio_set_input(IO)
|
||||
#define SET_DIR_OUTPUT(IO) gpio_set_output(IO)
|
||||
|
||||
#define SET_MODE(IO, mode) (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
|
||||
#define SET_MODE(IO, mode) pinMode(IO, mode)
|
||||
|
||||
#define WRITE_PIN_SET(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define WRITE_PIN_CLR(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define WRITE_PIN_SET(IO) gpio_set(IO)
|
||||
#define WRITE_PIN_CLR(IO) gpio_clear(IO)
|
||||
|
||||
#define READ_PIN(IO) ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
|
||||
#define WRITE_PIN(IO,V) ((V) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
|
||||
#define READ_PIN(IO) gpio_get(IO)
|
||||
#define WRITE_PIN(IO,V) gpio_set(IO, V)
|
||||
|
||||
/**
|
||||
* Magic I/O routines
|
||||
|
@ -89,10 +85,10 @@ bool useable_hardware_PWM(pin_t pin);
|
|||
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
|
||||
|
||||
/// check if pin is an input
|
||||
#define _GET_INPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) != 0)
|
||||
#define _GET_INPUT(IO) (!gpio_get_dir(IO))
|
||||
|
||||
/// check if pin is an output
|
||||
#define _GET_OUTPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) == 0)
|
||||
#define _GET_OUTPUT(IO) (gpio_get_dir(IO))
|
||||
|
||||
/// check if pin is a timer
|
||||
/// all gpio pins are pwm capable, either interrupt or hardware pwm controlled
|
||||
|
|
|
@ -1,125 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ARDUINO_H__
|
||||
#define __ARDUINO_H__
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <pinmapping.h>
|
||||
|
||||
#define HIGH 0x01
|
||||
#define LOW 0x00
|
||||
|
||||
#define INPUT 0x00
|
||||
#define OUTPUT 0x01
|
||||
#define INPUT_PULLUP 0x02
|
||||
#define INPUT_PULLDOWN 0x03
|
||||
|
||||
#define LSBFIRST 0
|
||||
#define MSBFIRST 1
|
||||
|
||||
#define CHANGE 0x02
|
||||
#define FALLING 0x03
|
||||
#define RISING 0x04
|
||||
|
||||
typedef uint8_t byte;
|
||||
#define PROGMEM
|
||||
#define PSTR(v) (v)
|
||||
#define PGM_P const char *
|
||||
|
||||
// Used for libraries, preprocessor, and constants
|
||||
#define min(a,b) ((a)<(b)?(a):(b))
|
||||
#define max(a,b) ((a)>(b)?(a):(b))
|
||||
#define abs(x) ((x)>0?(x):-(x))
|
||||
|
||||
#ifndef isnan
|
||||
#define isnan std::isnan
|
||||
#endif
|
||||
#ifndef isinf
|
||||
#define isinf std::isinf
|
||||
#endif
|
||||
|
||||
#define sq(v) ((v) * (v))
|
||||
#define square(v) sq(v)
|
||||
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
|
||||
|
||||
//Interrupts
|
||||
void cli(void); // Disable
|
||||
void sei(void); // Enable
|
||||
void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode);
|
||||
void detachInterrupt(const pin_t pin);
|
||||
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
|
||||
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
|
||||
|
||||
// Program Memory
|
||||
#define pgm_read_ptr(addr) (*((void**)(addr)))
|
||||
#define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
|
||||
#define pgm_read_float_near(addr) (*((float*)(addr)))
|
||||
#define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
|
||||
#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
|
||||
#define pgm_read_byte(addr) pgm_read_byte_near(addr)
|
||||
#define pgm_read_float(addr) pgm_read_float_near(addr)
|
||||
#define pgm_read_word(addr) pgm_read_word_near(addr)
|
||||
#define pgm_read_dword(addr) pgm_read_dword_near(addr)
|
||||
|
||||
#define memcpy_P memcpy
|
||||
#define sprintf_P sprintf
|
||||
#define strstr_P strstr
|
||||
#define strncpy_P strncpy
|
||||
#define vsnprintf_P vsnprintf
|
||||
#define strcpy_P strcpy
|
||||
#define snprintf_P snprintf
|
||||
#define strlen_P strlen
|
||||
#define strchr_P strchr
|
||||
|
||||
// Time functions
|
||||
extern "C" {
|
||||
void delay(const int milis);
|
||||
}
|
||||
void _delay_ms(const int delay);
|
||||
void delayMicroseconds(unsigned long);
|
||||
uint32_t millis();
|
||||
|
||||
//IO functions
|
||||
void pinMode(const pin_t, const uint8_t);
|
||||
void digitalWrite(pin_t, uint8_t);
|
||||
bool digitalRead(pin_t);
|
||||
void analogWrite(pin_t, int);
|
||||
uint16_t analogRead(pin_t);
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(uint8_t *pos, unsigned char value);
|
||||
uint8_t eeprom_read_byte(uint8_t *pos);
|
||||
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
|
||||
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
|
||||
|
||||
int32_t random(int32_t);
|
||||
int32_t random(int32_t, int32_t);
|
||||
void randomSeed(uint32_t);
|
||||
|
||||
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
|
||||
|
||||
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);
|
||||
|
||||
#endif // __ARDUINO_DEF_H__
|
|
@ -1,335 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "HardwareSerial.h"
|
||||
|
||||
#if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
|
||||
HardwareSerial Serial = HardwareSerial(LPC_UART0);
|
||||
#elif SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
|
||||
HardwareSerial Serial1 = HardwareSerial((LPC_UART_TypeDef *) LPC_UART1);
|
||||
#elif SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
|
||||
HardwareSerial Serial2 = HardwareSerial(LPC_UART2);
|
||||
#elif SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
|
||||
HardwareSerial Serial3 = HardwareSerial(LPC_UART3);
|
||||
#endif
|
||||
|
||||
void HardwareSerial::begin(uint32_t baudrate) {
|
||||
|
||||
UART_CFG_Type UARTConfigStruct;
|
||||
PINSEL_CFG_Type PinCfg;
|
||||
UART_FIFO_CFG_Type FIFOConfig;
|
||||
|
||||
if (Baudrate == baudrate) return; // No need to re-initialize
|
||||
|
||||
if (UARTx == LPC_UART0) {
|
||||
// Initialize UART0 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 2;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 3;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
// Initialize UART1 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 15;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 16;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if (UARTx == LPC_UART2) {
|
||||
// Initialize UART2 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 10;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 11;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if (UARTx == LPC_UART3) {
|
||||
// Initialize UART2 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 0;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 1;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
}
|
||||
|
||||
/* Initialize UART Configuration parameter structure to default state:
|
||||
* Baudrate = 9600bps
|
||||
* 8 data bit
|
||||
* 1 Stop bit
|
||||
* None parity
|
||||
*/
|
||||
UART_ConfigStructInit(&UARTConfigStruct);
|
||||
|
||||
// Re-configure baudrate
|
||||
UARTConfigStruct.Baud_rate = baudrate;
|
||||
|
||||
// Initialize eripheral with given to corresponding parameter
|
||||
UART_Init(UARTx, &UARTConfigStruct);
|
||||
|
||||
// Enable and reset the TX and RX FIFOs
|
||||
UART_FIFOConfigStructInit(&FIFOConfig);
|
||||
UART_FIFOConfig(UARTx, &FIFOConfig);
|
||||
|
||||
// Enable UART Transmit
|
||||
UART_TxCmd(UARTx, ENABLE);
|
||||
|
||||
// Configure Interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RLS, ENABLE);
|
||||
|
||||
// Set proper priority and enable interrupts
|
||||
if (UARTx == LPC_UART0) {
|
||||
NVIC_SetPriority(UART0_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART0_IRQn);
|
||||
}
|
||||
else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
NVIC_SetPriority(UART1_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART1_IRQn);
|
||||
}
|
||||
else if (UARTx == LPC_UART2) {
|
||||
NVIC_SetPriority(UART2_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART2_IRQn);
|
||||
}
|
||||
else if (UARTx == LPC_UART3) {
|
||||
NVIC_SetPriority(UART3_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART3_IRQn);
|
||||
}
|
||||
|
||||
RxQueueWritePos = RxQueueReadPos = 0;
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
TxQueueWritePos = TxQueueReadPos = 0;
|
||||
#endif
|
||||
|
||||
// Save the configured baudrate
|
||||
Baudrate = baudrate;
|
||||
}
|
||||
|
||||
int16_t HardwareSerial::peek() {
|
||||
int16_t byte = -1;
|
||||
|
||||
// Temporarily lock out UART receive interrupts during this read so the UART receive
|
||||
// interrupt won't cause problems with the index values
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
|
||||
|
||||
if (RxQueueReadPos != RxQueueWritePos)
|
||||
byte = RxBuffer[RxQueueReadPos];
|
||||
|
||||
// Re-enable UART interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
|
||||
return byte;
|
||||
}
|
||||
|
||||
int16_t HardwareSerial::read() {
|
||||
int16_t byte = -1;
|
||||
|
||||
// Temporarily lock out UART receive interrupts during this read so the UART receive
|
||||
// interrupt won't cause problems with the index values
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
|
||||
|
||||
if (RxQueueReadPos != RxQueueWritePos) {
|
||||
byte = RxBuffer[RxQueueReadPos];
|
||||
RxQueueReadPos = (RxQueueReadPos + 1) % RX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
// Re-enable UART interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
|
||||
return byte;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::write(uint8_t send) {
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
size_t bytes = 0;
|
||||
uint32_t fifolvl = 0;
|
||||
|
||||
// If the Tx Buffer is full, wait for space to clear
|
||||
if ((TxQueueWritePos+1) % TX_BUFFER_SIZE == TxQueueReadPos) flushTX();
|
||||
|
||||
// Temporarily lock out UART transmit interrupts during this read so the UART transmit interrupt won't
|
||||
// cause problems with the index values
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
|
||||
// LPC17xx.h incorrectly defines FIFOLVL as a uint8_t, when it's actually a 32-bit register
|
||||
if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
fifolvl = *(reinterpret_cast<volatile uint32_t *>(&((LPC_UART1_TypeDef *) UARTx)->FIFOLVL));
|
||||
} else fifolvl = *(reinterpret_cast<volatile uint32_t *>(&UARTx->FIFOLVL));
|
||||
|
||||
// If the queue is empty and there's space in the FIFO, immediately send the byte
|
||||
if (TxQueueWritePos == TxQueueReadPos && fifolvl < UART_TX_FIFO_SIZE) {
|
||||
bytes = UART_Send(UARTx, &send, 1, BLOCKING);
|
||||
}
|
||||
// Otherwiise, write the byte to the transmit buffer
|
||||
else if ((TxQueueWritePos+1) % TX_BUFFER_SIZE != TxQueueReadPos) {
|
||||
TxBuffer[TxQueueWritePos] = send;
|
||||
TxQueueWritePos = (TxQueueWritePos+1) % TX_BUFFER_SIZE;
|
||||
bytes++;
|
||||
}
|
||||
|
||||
// Re-enable the TX Interrupt
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
|
||||
|
||||
return bytes;
|
||||
#else
|
||||
return UART_Send(UARTx, &send, 1, BLOCKING);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
void HardwareSerial::flushTX() {
|
||||
// Wait for the tx buffer and FIFO to drain
|
||||
while (TxQueueWritePos != TxQueueReadPos && UART_CheckBusy(UARTx) == SET);
|
||||
}
|
||||
#endif
|
||||
|
||||
size_t HardwareSerial::available() {
|
||||
return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
void HardwareSerial::flush() {
|
||||
RxQueueWritePos = 0;
|
||||
RxQueueReadPos = 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::printf(const char *format, ...) {
|
||||
char RxBuffer[256];
|
||||
va_list vArgs;
|
||||
va_start(vArgs, format);
|
||||
int length = vsnprintf(RxBuffer, 256, format, vArgs);
|
||||
va_end(vArgs);
|
||||
if (length > 0 && length < 256) {
|
||||
for (size_t i = 0; i < (size_t)length; ++i)
|
||||
write(RxBuffer[i]);
|
||||
}
|
||||
return length;
|
||||
}
|
||||
|
||||
void HardwareSerial::IRQHandler() {
|
||||
uint32_t IIRValue;
|
||||
uint8_t LSRValue, byte;
|
||||
|
||||
IIRValue = UART_GetIntId(UARTx);
|
||||
IIRValue &= UART_IIR_INTID_MASK; // check bit 1~3, interrupt identification
|
||||
|
||||
// Receive Line Status
|
||||
if (IIRValue == UART_IIR_INTID_RLS) {
|
||||
LSRValue = UART_GetLineStatus(UARTx);
|
||||
|
||||
// Receive Line Status
|
||||
if (LSRValue & (UART_LSR_OE | UART_LSR_PE | UART_LSR_FE | UART_LSR_RXFE | UART_LSR_BI)) {
|
||||
// There are errors or break interrupt
|
||||
// Read LSR will clear the interrupt
|
||||
Status = LSRValue;
|
||||
byte = UART_ReceiveByte(UARTx); // Dummy read on RX to clear interrupt, then bail out
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// Receive Data Available
|
||||
if (IIRValue == UART_IIR_INTID_RDA) {
|
||||
// Clear the FIFO
|
||||
while (UART_Receive(UARTx, &byte, 1, NONE_BLOCKING)) {
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
emergency_parser.update(emergency_state, byte);
|
||||
#endif
|
||||
if ((RxQueueWritePos + 1) % RX_BUFFER_SIZE != RxQueueReadPos) {
|
||||
RxBuffer[RxQueueWritePos] = byte;
|
||||
RxQueueWritePos = (RxQueueWritePos + 1) % RX_BUFFER_SIZE;
|
||||
} else
|
||||
break;
|
||||
}
|
||||
// Character timeout indicator
|
||||
} else if (IIRValue == UART_IIR_INTID_CTI) {
|
||||
// Character Time-out indicator
|
||||
Status |= 0x100; // Bit 9 as the CTI error
|
||||
}
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
if (IIRValue == UART_IIR_INTID_THRE) {
|
||||
// Disable THRE interrupt
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
|
||||
// Wait for FIFO buffer empty
|
||||
while (UART_CheckBusy(UARTx) == SET);
|
||||
|
||||
// Transfer up to UART_TX_FIFO_SIZE bytes of data
|
||||
for (int i = 0; i < UART_TX_FIFO_SIZE && TxQueueWritePos != TxQueueReadPos; i++) {
|
||||
// Move a piece of data into the transmit FIFO
|
||||
if (UART_Send(UARTx, &TxBuffer[TxQueueReadPos], 1, NONE_BLOCKING)) {
|
||||
TxQueueReadPos = (TxQueueReadPos+1) % TX_BUFFER_SIZE;
|
||||
} else break;
|
||||
}
|
||||
|
||||
// If there is no more data to send, disable the transmit interrupt - else enable it or keep it enabled
|
||||
if (TxQueueWritePos == TxQueueReadPos) {
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
} else UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
void UART0_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
|
||||
Serial.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART1_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
|
||||
Serial1.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART2_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
|
||||
Serial2.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART3_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
|
||||
Serial3.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,91 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef HARDWARE_SERIAL_H_
|
||||
#define HARDWARE_SERIAL_H_
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../../feature/emergency_parser.h"
|
||||
#endif
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <stdio.h>
|
||||
#include <Stream.h>
|
||||
|
||||
extern "C" {
|
||||
#include <lpc17xx_uart.h>
|
||||
#include "lpc17xx_pinsel.h"
|
||||
}
|
||||
|
||||
class HardwareSerial : public Stream {
|
||||
private:
|
||||
LPC_UART_TypeDef *UARTx;
|
||||
|
||||
uint32_t Baudrate;
|
||||
uint32_t Status;
|
||||
uint8_t RxBuffer[RX_BUFFER_SIZE];
|
||||
uint32_t RxQueueWritePos;
|
||||
uint32_t RxQueueReadPos;
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
uint8_t TxBuffer[TX_BUFFER_SIZE];
|
||||
uint32_t TxQueueWritePos;
|
||||
uint32_t TxQueueReadPos;
|
||||
#endif
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
#endif
|
||||
|
||||
public:
|
||||
HardwareSerial(LPC_UART_TypeDef *UARTx)
|
||||
: UARTx(UARTx)
|
||||
, Baudrate(0)
|
||||
, RxQueueWritePos(0)
|
||||
, RxQueueReadPos(0)
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
, TxQueueWritePos(0)
|
||||
, TxQueueReadPos(0)
|
||||
#endif
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
, emergency_state(EmergencyParser::State::EP_RESET)
|
||||
#endif
|
||||
{
|
||||
}
|
||||
|
||||
void begin(uint32_t baudrate);
|
||||
int16_t peek();
|
||||
int16_t read();
|
||||
size_t write(uint8_t send);
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
void flushTX();
|
||||
#endif
|
||||
size_t available();
|
||||
void flush();
|
||||
size_t printf(const char *format, ...);
|
||||
|
||||
operator bool() { return true; }
|
||||
|
||||
void IRQHandler();
|
||||
|
||||
};
|
||||
|
||||
#endif // MARLIN_SRC_HAL_HAL_SERIAL_H_
|
|
@ -1,329 +0,0 @@
|
|||
/*
|
||||
* SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
|
||||
*
|
||||
* Multi-instance software serial library for Arduino/Wiring
|
||||
* -- Interrupt-driven receive and other improvements by ladyada
|
||||
* (http://ladyada.net)
|
||||
* -- Tuning, circular buffer, derivation from class Print/Stream,
|
||||
* multi-instance support, porting to 8MHz processors,
|
||||
* various optimizations, PROGMEM delay tables, inverse logic and
|
||||
* direct port writing by Mikal Hart (http://www.arduiniana.org)
|
||||
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
|
||||
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
|
||||
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
* Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*
|
||||
* The latest version of this library can always be found at
|
||||
* http://arduiniana.org.
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
//
|
||||
// Includes
|
||||
//
|
||||
//#include <WInterrupts.h>
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
#include "../../shared/Delay.h"
|
||||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
#include "../fastio.h"
|
||||
#include "SoftwareSerial.h"
|
||||
|
||||
void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
|
||||
void GpioDisableInt(uint32_t port, uint32_t pin);
|
||||
//
|
||||
// Statics
|
||||
//
|
||||
SoftwareSerial *SoftwareSerial::active_object = 0;
|
||||
unsigned char SoftwareSerial::_receive_buffer[_SS_MAX_RX_BUFF];
|
||||
volatile uint8_t SoftwareSerial::_receive_buffer_tail = 0;
|
||||
volatile uint8_t SoftwareSerial::_receive_buffer_head = 0;
|
||||
|
||||
typedef struct _DELAY_TABLE {
|
||||
long baud;
|
||||
uint16_t rx_delay_centering;
|
||||
uint16_t rx_delay_intrabit;
|
||||
uint16_t rx_delay_stopbit;
|
||||
uint16_t tx_delay;
|
||||
} DELAY_TABLE;
|
||||
|
||||
// rough delay estimation
|
||||
static const DELAY_TABLE table[] = {
|
||||
//baud |rxcenter|rxintra |rxstop |tx { 250000, 2, 4, 4, 4, }, //Done but not good due to instruction cycle error { 115200, 4, 8, 8, 8, }, //Done but not good due to instruction cycle error
|
||||
//{ 74880, 69, 139, 62, 162, }, // estimation
|
||||
//{ 57600, 100, 185, 1, 208, }, // Done but not good due to instruction cycle error
|
||||
//{ 38400, 13, 26, 26, 26, }, // Done
|
||||
//{ 19200, 26, 52, 52, 52, }, // Done { 9600, 52, 104, 104, 104, }, // Done
|
||||
//{ 4800, 104, 208, 208, 208, },
|
||||
//{ 2400, 208, 417, 417, 417, },
|
||||
//{ 1200, 416, 833, 833, 833,},
|
||||
};
|
||||
|
||||
//
|
||||
// Private methods
|
||||
//
|
||||
|
||||
inline void SoftwareSerial::tunedDelay(const uint32_t count) {
|
||||
DELAY_US(count);
|
||||
}
|
||||
|
||||
// This function sets the current object as the "listening"
|
||||
// one and returns true if it replaces another
|
||||
bool SoftwareSerial::listen() {
|
||||
if (!_rx_delay_stopbit)
|
||||
return false;
|
||||
|
||||
if (active_object != this) {
|
||||
if (active_object)
|
||||
active_object->stopListening();
|
||||
|
||||
_buffer_overflow = false;
|
||||
_receive_buffer_head = _receive_buffer_tail = 0;
|
||||
active_object = this;
|
||||
|
||||
setRxIntMsk(true);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// Stop listening. Returns true if we were actually listening.
|
||||
bool SoftwareSerial::stopListening() {
|
||||
if (active_object == this) {
|
||||
setRxIntMsk(false);
|
||||
active_object = NULL;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
//
|
||||
// The receive routine called by the interrupt handler
|
||||
//
|
||||
void SoftwareSerial::recv() {
|
||||
uint8_t d = 0;
|
||||
|
||||
// If RX line is high, then we don't see any start bit
|
||||
// so interrupt is probably not for us
|
||||
if (_inverse_logic ? rx_pin_read() : !rx_pin_read()) {
|
||||
// Disable further interrupts during reception, this prevents
|
||||
// triggering another interrupt directly after we return, which can
|
||||
// cause problems at higher baudrates.
|
||||
setRxIntMsk(false);//__disable_irq();//
|
||||
|
||||
// Wait approximately 1/2 of a bit width to "center" the sample
|
||||
tunedDelay(_rx_delay_centering);
|
||||
// Read each of the 8 bits
|
||||
for (uint8_t i=8; i > 0; --i) {
|
||||
tunedDelay(_rx_delay_intrabit);
|
||||
d >>= 1;
|
||||
if (rx_pin_read()) d |= 0x80;
|
||||
}
|
||||
|
||||
if (_inverse_logic) d = ~d;
|
||||
|
||||
// if buffer full, set the overflow flag and return
|
||||
uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
|
||||
if (next != _receive_buffer_head) {
|
||||
// save new data in buffer: tail points to where byte goes
|
||||
_receive_buffer[_receive_buffer_tail] = d; // save new byte
|
||||
_receive_buffer_tail = next;
|
||||
}
|
||||
else {
|
||||
_buffer_overflow = true;
|
||||
}
|
||||
tunedDelay(_rx_delay_stopbit);
|
||||
// Re-enable interrupts when we're sure to be inside the stop bit
|
||||
setRxIntMsk(true); //__enable_irq();//
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t SoftwareSerial::rx_pin_read() {
|
||||
return digitalRead(_receivePin);
|
||||
}
|
||||
|
||||
//
|
||||
// Interrupt handling
|
||||
//
|
||||
|
||||
/* static */
|
||||
inline void SoftwareSerial::handle_interrupt() {
|
||||
if (active_object)
|
||||
active_object->recv();
|
||||
}
|
||||
extern "C" void intWrapper() {
|
||||
SoftwareSerial::handle_interrupt();
|
||||
}
|
||||
//
|
||||
// Constructor
|
||||
//
|
||||
SoftwareSerial::SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic /* = false */) :
|
||||
_rx_delay_centering(0),
|
||||
_rx_delay_intrabit(0),
|
||||
_rx_delay_stopbit(0),
|
||||
_tx_delay(0),
|
||||
_buffer_overflow(false),
|
||||
_inverse_logic(inverse_logic) {
|
||||
setTX(transmitPin);
|
||||
setRX(receivePin);
|
||||
}
|
||||
|
||||
//
|
||||
// Destructor
|
||||
//
|
||||
SoftwareSerial::~SoftwareSerial() {
|
||||
end();
|
||||
}
|
||||
|
||||
void SoftwareSerial::setTX(pin_t tx) {
|
||||
// First write, then set output. If we do this the other way around,
|
||||
// the pin would be output low for a short while before switching to
|
||||
// output hihg. Now, it is input with pullup for a short while, which
|
||||
// is fine. With inverse logic, either order is fine.
|
||||
|
||||
digitalWrite(tx, _inverse_logic ? LOW : HIGH);
|
||||
pinMode(tx,OUTPUT);
|
||||
_transmitPin = tx;
|
||||
}
|
||||
|
||||
void SoftwareSerial::setRX(pin_t rx) {
|
||||
pinMode(rx, INPUT_PULLUP); // pullup for normal logic!
|
||||
//if (!_inverse_logic)
|
||||
// digitalWrite(rx, HIGH);
|
||||
_receivePin = rx;
|
||||
_receivePort = LPC1768_PIN_PORT(rx);
|
||||
_receivePortPin = LPC1768_PIN_PIN(rx);
|
||||
/* GPIO_T * rxPort = digitalPinToPort(rx);
|
||||
_receivePortRegister = portInputRegister(rxPort);
|
||||
_receiveBitMask = digitalPinToBitMask(rx);*/
|
||||
}
|
||||
|
||||
//
|
||||
// Public methods
|
||||
//
|
||||
|
||||
void SoftwareSerial::begin(long speed) {
|
||||
_rx_delay_centering = _rx_delay_intrabit = _rx_delay_stopbit = _tx_delay = 0;
|
||||
|
||||
for(uint8_t i = 0; i < sizeof(table)/sizeof(table[0]); ++i) {
|
||||
long baud = table[i].baud;
|
||||
if (baud == speed) {
|
||||
_rx_delay_centering = table[i].rx_delay_centering;
|
||||
_rx_delay_intrabit = table[i].rx_delay_intrabit;
|
||||
_rx_delay_stopbit = table[i].rx_delay_stopbit;
|
||||
_tx_delay = table[i].tx_delay;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
attachInterrupt(_receivePin, intWrapper, CHANGE); //this->handle_interrupt, CHANGE);
|
||||
|
||||
listen();
|
||||
tunedDelay(_tx_delay);
|
||||
|
||||
}
|
||||
|
||||
void SoftwareSerial::setRxIntMsk(bool enable) {
|
||||
if (enable)
|
||||
GpioEnableInt(_receivePort,_receivePin,CHANGE);
|
||||
else
|
||||
GpioDisableInt(_receivePort,_receivePin);
|
||||
}
|
||||
|
||||
void SoftwareSerial::end() {
|
||||
stopListening();
|
||||
}
|
||||
|
||||
|
||||
// Read data from buffer
|
||||
int16_t SoftwareSerial::read() {
|
||||
if (!isListening()) return -1;
|
||||
|
||||
// Empty buffer?
|
||||
if (_receive_buffer_head == _receive_buffer_tail) return -1;
|
||||
|
||||
// Read from "head"
|
||||
uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
|
||||
_receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
|
||||
return d;
|
||||
}
|
||||
|
||||
size_t SoftwareSerial::available() {
|
||||
if (!isListening()) return 0;
|
||||
|
||||
return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
|
||||
}
|
||||
|
||||
size_t SoftwareSerial::write(uint8_t b) {
|
||||
// By declaring these as local variables, the compiler will put them
|
||||
// in registers _before_ disabling interrupts and entering the
|
||||
// critical timing sections below, which makes it a lot easier to
|
||||
// verify the cycle timings
|
||||
|
||||
bool inv = _inverse_logic;
|
||||
uint16_t delay = _tx_delay;
|
||||
|
||||
if (inv) b = ~b;
|
||||
|
||||
cli(); // turn off interrupts for a clean txmit
|
||||
|
||||
// Write the start bit
|
||||
digitalWrite(_transmitPin, !!inv);
|
||||
|
||||
tunedDelay(delay);
|
||||
|
||||
// Write each of the 8 bits
|
||||
for (uint8_t i = 8; i > 0; --i) {
|
||||
digitalWrite(_transmitPin, b & 1); // send 1 //(GPIO_Desc[_transmitPin].P)->DOUT |= GPIO_Desc[_transmitPin].bit;
|
||||
// send 0 //(GPIO_Desc[_transmitPin].P)->DOUT &= ~GPIO_Desc[_transmitPin].bit;
|
||||
tunedDelay(delay);
|
||||
b >>= 1;
|
||||
}
|
||||
|
||||
// restore pin to natural state
|
||||
digitalWrite(_transmitPin, !inv);
|
||||
|
||||
sei(); // turn interrupts back on
|
||||
tunedDelay(delay);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
void SoftwareSerial::flush() {
|
||||
if (!isListening()) return;
|
||||
|
||||
cli();
|
||||
_receive_buffer_head = _receive_buffer_tail = 0;
|
||||
sei();
|
||||
}
|
||||
|
||||
int16_t SoftwareSerial::peek() {
|
||||
if (!isListening())
|
||||
return -1;
|
||||
|
||||
// Empty buffer?
|
||||
if (_receive_buffer_head == _receive_buffer_tail)
|
||||
return -1;
|
||||
|
||||
// Read from "head"
|
||||
return _receive_buffer[_receive_buffer_head];
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,120 +0,0 @@
|
|||
/*
|
||||
* SoftwareSerial.h (formerly NewSoftSerial.h)
|
||||
*
|
||||
* Multi-instance software serial library for Arduino/Wiring
|
||||
* -- Interrupt-driven receive and other improvements by ladyada
|
||||
* (http://ladyada.net)
|
||||
* -- Tuning, circular buffer, derivation from class Print/Stream,
|
||||
* multi-instance support, porting to 8MHz processors,
|
||||
* various optimizations, PROGMEM delay tables, inverse logic and
|
||||
* direct port writing by Mikal Hart (http://www.arduiniana.org)
|
||||
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
|
||||
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
|
||||
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
* Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*
|
||||
* The latest version of this library can always be found at
|
||||
* http://arduiniana.org.
|
||||
*/
|
||||
|
||||
#ifndef SOFTWARESERIAL_H
|
||||
#define SOFTWARESERIAL_H
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <stdint.h>
|
||||
//#include "serial.h"
|
||||
#include <Stream.h>
|
||||
#include <Print.h>
|
||||
|
||||
/******************************************************************************
|
||||
* Definitions
|
||||
******************************************************************************/
|
||||
|
||||
#define _SS_MAX_RX_BUFF 64 // RX buffer size
|
||||
|
||||
class SoftwareSerial : public Stream
|
||||
{
|
||||
private:
|
||||
// per object data
|
||||
pin_t _receivePin;
|
||||
pin_t _transmitPin;
|
||||
// uint32_t _receiveBitMask; // for rx interrupts
|
||||
uint32_t _receivePort;
|
||||
uint32_t _receivePortPin;
|
||||
|
||||
|
||||
// Expressed as 4-cycle delays (must never be 0!)
|
||||
uint16_t _rx_delay_centering;
|
||||
uint16_t _rx_delay_intrabit;
|
||||
uint16_t _rx_delay_stopbit;
|
||||
uint16_t _tx_delay;
|
||||
|
||||
uint16_t _buffer_overflow:1;
|
||||
uint16_t _inverse_logic:1;
|
||||
|
||||
// static data
|
||||
static unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
|
||||
static volatile uint8_t _receive_buffer_tail;
|
||||
static volatile uint8_t _receive_buffer_head;
|
||||
static SoftwareSerial *active_object;
|
||||
|
||||
// private methods
|
||||
void recv();
|
||||
uint32_t rx_pin_read();
|
||||
void tx_pin_write(uint8_t pin_state);
|
||||
void setTX(pin_t transmitPin);
|
||||
void setRX(pin_t receivePin);
|
||||
void setRxIntMsk(bool enable);
|
||||
|
||||
// private static method for timing
|
||||
static inline void tunedDelay(uint32_t delay);
|
||||
|
||||
public:
|
||||
// public methods
|
||||
|
||||
SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic = false);
|
||||
~SoftwareSerial();
|
||||
void begin(long speed);
|
||||
bool listen();
|
||||
void end();
|
||||
bool isListening() { return this == active_object; }
|
||||
bool stopListening();
|
||||
bool overflow() { bool ret = _buffer_overflow; if (ret) _buffer_overflow = false; return ret; }
|
||||
int16_t peek();
|
||||
|
||||
virtual size_t write(uint8_t byte);
|
||||
virtual int16_t read();
|
||||
virtual size_t available();
|
||||
virtual void flush();
|
||||
operator bool() { return true; }
|
||||
|
||||
using Print::write;
|
||||
//using HalSerial::write;
|
||||
|
||||
// public only for easy access by interrupt handlers
|
||||
static inline void handle_interrupt() __attribute__((__always_inline__));
|
||||
};
|
||||
|
||||
// Arduino 0012 workaround
|
||||
#undef int
|
||||
#undef char
|
||||
#undef long
|
||||
#undef byte
|
||||
#undef float
|
||||
#undef abs
|
||||
#undef round
|
||||
|
||||
#endif // SOFTWARESERIAL_H
|
|
@ -1,219 +0,0 @@
|
|||
/*
|
||||
TwoWire.cpp - TWI/I2C library for Wiring & Arduino
|
||||
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
extern "C" {
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
#include <lpc17xx_i2c.h>
|
||||
#include <lpc17xx_pinsel.h>
|
||||
#include <lpc17xx_libcfg_default.h>
|
||||
}
|
||||
|
||||
#include <Wire.h>
|
||||
|
||||
#define USEDI2CDEV_M 1
|
||||
|
||||
#if (USEDI2CDEV_M == 0)
|
||||
#define I2CDEV_M LPC_I2C0
|
||||
#elif (USEDI2CDEV_M == 1)
|
||||
#define I2CDEV_M LPC_I2C1
|
||||
#elif (USEDI2CDEV_M == 2)
|
||||
#define I2CDEV_M LPC_I2C2
|
||||
#else
|
||||
#error "Master I2C device not defined!"
|
||||
#endif
|
||||
|
||||
// Initialize Class Variables //////////////////////////////////////////////////
|
||||
|
||||
uint8_t TwoWire::rxBuffer[BUFFER_LENGTH];
|
||||
uint8_t TwoWire::rxBufferIndex = 0;
|
||||
uint8_t TwoWire::rxBufferLength = 0;
|
||||
|
||||
uint8_t TwoWire::txAddress = 0;
|
||||
uint8_t TwoWire::txBuffer[BUFFER_LENGTH];
|
||||
uint8_t TwoWire::txBufferIndex = 0;
|
||||
uint8_t TwoWire::txBufferLength = 0;
|
||||
|
||||
uint8_t TwoWire::transmitting = 0;
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
|
||||
TwoWire::TwoWire() {
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
void TwoWire::begin(void) {
|
||||
rxBufferIndex = 0;
|
||||
rxBufferLength = 0;
|
||||
|
||||
txBufferIndex = 0;
|
||||
txBufferLength = 0;
|
||||
|
||||
/*
|
||||
* Init I2C pin connect
|
||||
*/
|
||||
PINSEL_CFG_Type PinCfg;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
|
||||
#if USEDI2CDEV_M == 0
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.Pinnum = 27;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg); // SDA0 / D57 AUX-1
|
||||
PinCfg.Pinnum = 28;
|
||||
PINSEL_ConfigPin(&PinCfg); // SCL0 / D58 AUX-1
|
||||
#endif
|
||||
|
||||
#if USEDI2CDEV_M == 1
|
||||
PinCfg.Funcnum = 3;
|
||||
PinCfg.Pinnum = 0;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg); // SDA1 / D20 SCA
|
||||
PinCfg.Pinnum = 1;
|
||||
PINSEL_ConfigPin(&PinCfg); // SCL1 / D21 SCL
|
||||
#endif
|
||||
|
||||
#if USEDI2CDEV_M == 2
|
||||
PinCfg.Funcnum = 2;
|
||||
PinCfg.Pinnum = 10;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg); // SDA2 / D38 X_ENABLE_PIN
|
||||
PinCfg.Pinnum = 11;
|
||||
PINSEL_ConfigPin(&PinCfg); // SCL2 / D55 X_DIR_PIN
|
||||
#endif
|
||||
|
||||
// Initialize I2C peripheral
|
||||
I2C_Init(I2CDEV_M, 100000);
|
||||
|
||||
// Enable Master I2C operation
|
||||
I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
|
||||
}
|
||||
|
||||
uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity) {
|
||||
// clamp to buffer length
|
||||
if (quantity > BUFFER_LENGTH)
|
||||
quantity = BUFFER_LENGTH;
|
||||
|
||||
// perform blocking read into buffer
|
||||
I2C_M_SETUP_Type transferMCfg;
|
||||
transferMCfg.sl_addr7bit = address >> 1; // not sure about the right shift
|
||||
transferMCfg.tx_data = NULL;
|
||||
transferMCfg.tx_length = 0;
|
||||
transferMCfg.rx_data = rxBuffer;
|
||||
transferMCfg.rx_length = quantity;
|
||||
transferMCfg.retransmissions_max = 3;
|
||||
I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
|
||||
|
||||
// set rx buffer iterator vars
|
||||
rxBufferIndex = 0;
|
||||
rxBufferLength = transferMCfg.rx_count;
|
||||
|
||||
return transferMCfg.rx_count;
|
||||
}
|
||||
|
||||
uint8_t TwoWire::requestFrom(int address, int quantity) {
|
||||
return requestFrom((uint8_t)address, (uint8_t)quantity);
|
||||
}
|
||||
|
||||
void TwoWire::beginTransmission(uint8_t address) {
|
||||
// indicate that we are transmitting
|
||||
transmitting = 1;
|
||||
// set address of targeted slave
|
||||
txAddress = address;
|
||||
// reset tx buffer iterator vars
|
||||
txBufferIndex = 0;
|
||||
txBufferLength = 0;
|
||||
}
|
||||
|
||||
void TwoWire::beginTransmission(int address) {
|
||||
beginTransmission((uint8_t)address);
|
||||
}
|
||||
|
||||
uint8_t TwoWire::endTransmission(void) {
|
||||
// transmit buffer (blocking)
|
||||
I2C_M_SETUP_Type transferMCfg;
|
||||
transferMCfg.sl_addr7bit = txAddress >> 1; // not sure about the right shift
|
||||
transferMCfg.tx_data = txBuffer;
|
||||
transferMCfg.tx_length = txBufferLength;
|
||||
transferMCfg.rx_data = NULL;
|
||||
transferMCfg.rx_length = 0;
|
||||
transferMCfg.retransmissions_max = 3;
|
||||
Status status = I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
|
||||
|
||||
// reset tx buffer iterator vars
|
||||
txBufferIndex = 0;
|
||||
txBufferLength = 0;
|
||||
|
||||
// indicate that we are done transmitting
|
||||
transmitting = 0;
|
||||
|
||||
return status == SUCCESS ? 0 : 4;
|
||||
}
|
||||
|
||||
// must be called after beginTransmission(address)
|
||||
size_t TwoWire::write(uint8_t data) {
|
||||
if (transmitting) {
|
||||
// don't bother if buffer is full
|
||||
if (txBufferLength >= BUFFER_LENGTH) return 0;
|
||||
|
||||
// put byte in tx buffer
|
||||
txBuffer[txBufferIndex++] = data;
|
||||
|
||||
// update amount in buffer
|
||||
txBufferLength = txBufferIndex;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
// must be called after beginTransmission(address)
|
||||
size_t TwoWire::write(const uint8_t *data, size_t quantity) {
|
||||
size_t sent = 0;
|
||||
if (transmitting)
|
||||
for (sent = 0; sent < quantity; ++sent)
|
||||
if (!write(data[sent])) break;
|
||||
|
||||
return sent;
|
||||
}
|
||||
|
||||
// Must be called after requestFrom(address, numBytes)
|
||||
int TwoWire::available(void) {
|
||||
return rxBufferLength - rxBufferIndex;
|
||||
}
|
||||
|
||||
// Must be called after requestFrom(address, numBytes)
|
||||
int TwoWire::read(void) {
|
||||
return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex++] : -1;
|
||||
}
|
||||
|
||||
// Must be called after requestFrom(address, numBytes)
|
||||
int TwoWire::peek(void) {
|
||||
return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex] : -1;
|
||||
}
|
||||
|
||||
// Preinstantiate Objects //////////////////////////////////////////////////////
|
||||
|
||||
TwoWire Wire = TwoWire();
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,67 +0,0 @@
|
|||
/**
|
||||
* TwoWire.h - TWI/I2C library for Arduino & Wiring
|
||||
* Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
* Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*
|
||||
* Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
|
||||
*/
|
||||
|
||||
#ifndef _TWOWIRE_H_
|
||||
#define _TWOWIRE_H_
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#define BUFFER_LENGTH 32
|
||||
|
||||
class TwoWire {
|
||||
private:
|
||||
static uint8_t rxBuffer[];
|
||||
static uint8_t rxBufferIndex;
|
||||
static uint8_t rxBufferLength;
|
||||
|
||||
static uint8_t txAddress;
|
||||
static uint8_t txBuffer[];
|
||||
static uint8_t txBufferIndex;
|
||||
static uint8_t txBufferLength;
|
||||
|
||||
static uint8_t transmitting;
|
||||
|
||||
public:
|
||||
TwoWire();
|
||||
void begin();
|
||||
void beginTransmission(uint8_t);
|
||||
void beginTransmission(int);
|
||||
uint8_t endTransmission(void);
|
||||
uint8_t endTransmission(uint8_t);
|
||||
|
||||
uint8_t requestFrom(uint8_t, uint8_t);
|
||||
uint8_t requestFrom(int, int);
|
||||
|
||||
virtual size_t write(uint8_t);
|
||||
virtual size_t write(const uint8_t *, size_t);
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual int peek(void);
|
||||
|
||||
inline size_t write(unsigned long n) { return write((uint8_t)n); }
|
||||
inline size_t write(long n) { return write((uint8_t)n); }
|
||||
inline size_t write(unsigned int n) { return write((uint8_t)n); }
|
||||
inline size_t write(int n) { return write((uint8_t)n); }
|
||||
};
|
||||
|
||||
extern TwoWire Wire;
|
||||
|
||||
#endif // _TWOWIRE_H_
|
|
@ -1,74 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include <pinmapping.h>
|
||||
|
||||
#include "../../../gcode/parser.h"
|
||||
|
||||
// Get the digital pin for an analog index
|
||||
pin_t analogInputToDigitalPin(const int8_t p) {
|
||||
return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? adc_pin_table[p] : P_NC);
|
||||
}
|
||||
|
||||
// Return the index of a pin number
|
||||
// The pin number given here is in the form ppp:nnnnn
|
||||
int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
|
||||
const uint16_t index = (LPC1768_PIN_PORT(pin) << 5) | LPC1768_PIN_PIN(pin);
|
||||
return (index < NUM_DIGITAL_PINS && pin_map[index] != P_NC) ? index : -1;
|
||||
}
|
||||
|
||||
// Test whether the pin is valid
|
||||
bool VALID_PIN(const pin_t p) {
|
||||
const int16_t ind = GET_PIN_MAP_INDEX(p);
|
||||
return ind >= 0 && pin_map[ind] >= 0;
|
||||
}
|
||||
|
||||
// Get the analog index for a digital pin
|
||||
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
|
||||
return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
|
||||
}
|
||||
|
||||
// Test whether the pin is PWM
|
||||
bool PWM_PIN(const pin_t p) {
|
||||
return VALID_PIN(p) && LPC1768_PIN_PWM(p);
|
||||
}
|
||||
|
||||
// Test whether the pin is interruptable
|
||||
bool INTERRUPT_PIN(const pin_t p) {
|
||||
return VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p);
|
||||
}
|
||||
|
||||
// Get the pin number at the given index
|
||||
pin_t GET_PIN_MAP_PIN(const int16_t ind) {
|
||||
return WITHIN(ind, 0, NUM_DIGITAL_PINS - 1) ? pin_map[ind] : P_NC;
|
||||
}
|
||||
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
|
||||
const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
|
||||
? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
|
||||
return ind > -2 ? ind : dval;
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -1,294 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef _PINMAPPING_H_
|
||||
#define _PINMAPPING_H_
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef int16_t pin_t;
|
||||
|
||||
#define PORT_0 000
|
||||
#define PORT_1 001
|
||||
#define PORT_2 010
|
||||
#define PORT_3 011
|
||||
#define PORT_4 100
|
||||
|
||||
#define PORT_(p) PORT_##p
|
||||
#define PORT(p) PORT_(p)
|
||||
|
||||
#define PIN_0 00000
|
||||
#define PIN_1 00001
|
||||
#define PIN_2 00010
|
||||
#define PIN_3 00011
|
||||
#define PIN_4 00100
|
||||
#define PIN_5 00101
|
||||
#define PIN_6 00110
|
||||
#define PIN_7 00111
|
||||
#define PIN_8 01000
|
||||
#define PIN_9 01001
|
||||
#define PIN_10 01010
|
||||
#define PIN_11 01011
|
||||
#define PIN_12 01100
|
||||
#define PIN_13 01101
|
||||
#define PIN_14 01110
|
||||
#define PIN_15 01111
|
||||
#define PIN_16 10000
|
||||
#define PIN_17 10001
|
||||
#define PIN_18 10010
|
||||
#define PIN_19 10011
|
||||
#define PIN_20 10100
|
||||
#define PIN_21 10101
|
||||
#define PIN_22 10110
|
||||
#define PIN_23 10111
|
||||
#define PIN_24 11000
|
||||
#define PIN_25 11001
|
||||
#define PIN_26 11010
|
||||
#define PIN_27 11011
|
||||
#define PIN_28 11100
|
||||
#define PIN_29 11101
|
||||
#define PIN_30 11110
|
||||
#define PIN_31 11111
|
||||
|
||||
#define PIN_(p) PIN_##p
|
||||
#define PIN(p) PIN_(p)
|
||||
|
||||
#define ADC_NONE 0000
|
||||
#define ADC_CHAN_0 0001
|
||||
#define ADC_CHAN_1 0010
|
||||
#define ADC_CHAN_2 0011
|
||||
#define ADC_CHAN_3 0100
|
||||
#define ADC_CHAN_4 0101
|
||||
#define ADC_CHAN_5 0110
|
||||
#define ADC_CHAN_6 0111
|
||||
#define ADC_CHAN_7 1000
|
||||
|
||||
#define ADC_CHAN_(c) ADC_CHAN_##c
|
||||
#define ADC_CHAN(p) ADC_CHAN_(p)
|
||||
|
||||
#define BOOL_0 0
|
||||
#define BOOL_1 1
|
||||
#define BOOL_(b) BOOL_##b
|
||||
|
||||
#define INTERRUPT(b) BOOL_(b)
|
||||
#define PWM(b) BOOL_(b)
|
||||
|
||||
// Combine elements into pin bits: 0b00AAAAWIPPPNNNNN
|
||||
#define LPC1768_PIN_(port, pin, int, pwm, adc) 0b00##adc##pwm##int##port##pin
|
||||
#define LPC1768_PIN(port, pin, int, pwm, adc) LPC1768_PIN_(port, pin, int, pwm, adc)
|
||||
|
||||
constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
|
||||
constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
|
||||
constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & 0b1) != 0); }
|
||||
constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 9) & 0b1) != 0); }
|
||||
constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 10) & 0b1111) - 1; }
|
||||
|
||||
// ******************
|
||||
// Runtime pinmapping
|
||||
// ******************
|
||||
#define P_NC -1
|
||||
|
||||
#if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
|
||||
#define P0_00 LPC1768_PIN(PORT(0), PIN( 0), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_01 LPC1768_PIN(PORT(0), PIN( 1), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#endif
|
||||
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
|
||||
#define P0_02 LPC1768_PIN(PORT(0), PIN( 2), INTERRUPT(1), PWM(0), ADC_CHAN(7))
|
||||
#define P0_03 LPC1768_PIN(PORT(0), PIN( 3), INTERRUPT(1), PWM(0), ADC_CHAN(6))
|
||||
#endif
|
||||
#define P0_04 LPC1768_PIN(PORT(0), PIN( 4), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_05 LPC1768_PIN(PORT(0), PIN( 5), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_06 LPC1768_PIN(PORT(0), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_07 LPC1768_PIN(PORT(0), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_08 LPC1768_PIN(PORT(0), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_09 LPC1768_PIN(PORT(0), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
|
||||
#define P0_10 LPC1768_PIN(PORT(0), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_11 LPC1768_PIN(PORT(0), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#endif
|
||||
#if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
|
||||
#define P0_15 LPC1768_PIN(PORT(0), PIN(15), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_16 LPC1768_PIN(PORT(0), PIN(16), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#endif
|
||||
#define P0_17 LPC1768_PIN(PORT(0), PIN(17), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_18 LPC1768_PIN(PORT(0), PIN(18), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_19 LPC1768_PIN(PORT(0), PIN(19), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_20 LPC1768_PIN(PORT(0), PIN(20), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_21 LPC1768_PIN(PORT(0), PIN(21), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_22 LPC1768_PIN(PORT(0), PIN(22), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_23 LPC1768_PIN(PORT(0), PIN(23), INTERRUPT(1), PWM(0), ADC_CHAN(0))
|
||||
#define P0_24 LPC1768_PIN(PORT(0), PIN(24), INTERRUPT(1), PWM(0), ADC_CHAN(1))
|
||||
#define P0_25 LPC1768_PIN(PORT(0), PIN(25), INTERRUPT(1), PWM(0), ADC_CHAN(2))
|
||||
#define P0_26 LPC1768_PIN(PORT(0), PIN(26), INTERRUPT(1), PWM(0), ADC_CHAN(3))
|
||||
#define P0_27 LPC1768_PIN(PORT(0), PIN(27), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_28 LPC1768_PIN(PORT(0), PIN(28), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
|
||||
#define P0_29 LPC1768_PIN(PORT(0), PIN(29), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P0_30 LPC1768_PIN(PORT(0), PIN(30), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#endif
|
||||
#define P1_00 LPC1768_PIN(PORT(1), PIN( 0), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_01 LPC1768_PIN(PORT(1), PIN( 1), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_04 LPC1768_PIN(PORT(1), PIN( 4), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_08 LPC1768_PIN(PORT(1), PIN( 8), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_09 LPC1768_PIN(PORT(1), PIN( 9), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_10 LPC1768_PIN(PORT(1), PIN(10), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_14 LPC1768_PIN(PORT(1), PIN(14), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_15 LPC1768_PIN(PORT(1), PIN(15), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_16 LPC1768_PIN(PORT(1), PIN(16), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_17 LPC1768_PIN(PORT(1), PIN(17), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_18 LPC1768_PIN(PORT(1), PIN(18), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_19 LPC1768_PIN(PORT(1), PIN(19), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_20 LPC1768_PIN(PORT(1), PIN(20), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_21 LPC1768_PIN(PORT(1), PIN(21), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_22 LPC1768_PIN(PORT(1), PIN(22), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_23 LPC1768_PIN(PORT(1), PIN(23), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_24 LPC1768_PIN(PORT(1), PIN(24), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_25 LPC1768_PIN(PORT(1), PIN(25), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_26 LPC1768_PIN(PORT(1), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P1_27 LPC1768_PIN(PORT(1), PIN(27), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_28 LPC1768_PIN(PORT(1), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_29 LPC1768_PIN(PORT(1), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P1_30 LPC1768_PIN(PORT(1), PIN(30), INTERRUPT(0), PWM(0), ADC_CHAN(4))
|
||||
#define P1_31 LPC1768_PIN(PORT(1), PIN(31), INTERRUPT(0), PWM(0), ADC_CHAN(5))
|
||||
#define P2_00 LPC1768_PIN(PORT(2), PIN( 0), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_01 LPC1768_PIN(PORT(2), PIN( 1), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_02 LPC1768_PIN(PORT(2), PIN( 2), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_03 LPC1768_PIN(PORT(2), PIN( 3), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_04 LPC1768_PIN(PORT(2), PIN( 4), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_05 LPC1768_PIN(PORT(2), PIN( 5), INTERRUPT(1), PWM(1), ADC_NONE)
|
||||
#define P2_06 LPC1768_PIN(PORT(2), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_07 LPC1768_PIN(PORT(2), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_08 LPC1768_PIN(PORT(2), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_09 LPC1768_PIN(PORT(2), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_10 LPC1768_PIN(PORT(2), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_11 LPC1768_PIN(PORT(2), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_12 LPC1768_PIN(PORT(2), PIN(12), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P2_13 LPC1768_PIN(PORT(2), PIN(13), INTERRUPT(1), PWM(0), ADC_NONE)
|
||||
#define P3_25 LPC1768_PIN(PORT(3), PIN(25), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P3_26 LPC1768_PIN(PORT(3), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
|
||||
#define P4_28 LPC1768_PIN(PORT(4), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
#define P4_29 LPC1768_PIN(PORT(4), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
|
||||
|
||||
// Pin index for M43 and M226
|
||||
constexpr pin_t pin_map[] = {
|
||||
#if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
|
||||
P0_00, P0_01,
|
||||
#else
|
||||
P_NC, P_NC,
|
||||
#endif
|
||||
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
|
||||
P0_02, P0_03,
|
||||
#else
|
||||
P_NC, P_NC,
|
||||
#endif
|
||||
P0_04, P0_05, P0_06, P0_07,
|
||||
P0_08, P0_09,
|
||||
#if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
|
||||
P0_10, P0_11,
|
||||
#else
|
||||
P_NC, P_NC,
|
||||
#endif
|
||||
P_NC, P_NC, P_NC,
|
||||
#if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
|
||||
P0_15,
|
||||
P0_16,
|
||||
#else
|
||||
P_NC,
|
||||
P_NC,
|
||||
#endif
|
||||
P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23,
|
||||
P0_24, P0_25, P0_26, P0_27, P0_28,
|
||||
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
|
||||
P0_29, P0_30,
|
||||
#else
|
||||
P_NC, P_NC,
|
||||
#endif
|
||||
P_NC,
|
||||
|
||||
P1_00, P1_01, P_NC, P_NC, P1_04, P_NC, P_NC, P_NC,
|
||||
P1_08, P1_09, P1_10, P_NC, P_NC, P_NC, P1_14, P1_15,
|
||||
P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
|
||||
P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
|
||||
|
||||
P2_00, P2_01, P2_02, P2_03, P2_04, P2_05, P2_06, P2_07,
|
||||
P2_08, P2_09, P2_10, P2_11, P2_12, P2_13, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P3_25, P3_26, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
|
||||
P_NC, P_NC, P_NC, P_NC, P4_28, P4_29, P_NC, P_NC
|
||||
};
|
||||
|
||||
constexpr uint8_t NUM_DIGITAL_PINS = COUNT(pin_map);
|
||||
|
||||
constexpr pin_t adc_pin_table[] = {
|
||||
P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
|
||||
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
|
||||
P0_03, P0_02
|
||||
#endif
|
||||
};
|
||||
|
||||
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
|
||||
#define NUM_ANALOG_INPUTS 8
|
||||
#else
|
||||
#define NUM_ANALOG_INPUTS 6
|
||||
#endif
|
||||
|
||||
// P0.6 thru P0.9 are for the onboard SD card
|
||||
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
|
||||
|
||||
// Get the digital pin for an analog index
|
||||
pin_t analogInputToDigitalPin(const int8_t p);
|
||||
#define digitalPinToInterrupt(pin) (pin)
|
||||
// Return the index of a pin number
|
||||
// The pin number given here is in the form ppp:nnnnn
|
||||
int16_t GET_PIN_MAP_INDEX(const pin_t pin);
|
||||
|
||||
// Test whether the pin is valid
|
||||
bool VALID_PIN(const pin_t p);
|
||||
|
||||
// Get the analog index for a digital pin
|
||||
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p);
|
||||
|
||||
// Test whether the pin is PWM
|
||||
bool PWM_PIN(const pin_t p);
|
||||
|
||||
// Test whether the pin is interruptable
|
||||
bool INTERRUPT_PIN(const pin_t p);
|
||||
#define LPC1768_PIN_INTERRUPT_M(pin) (((pin >> 8) & 0b1) != 0)
|
||||
|
||||
// Get the pin number at the given index
|
||||
pin_t GET_PIN_MAP_PIN(const int16_t ind);
|
||||
|
||||
// Parse a G-code word into a pin index
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
||||
|
||||
#endif // _PINMAPPING_H_
|
|
@ -1,161 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef _HAL_SERIAL_H_
|
||||
#define _HAL_SERIAL_H_
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../../feature/emergency_parser.h"
|
||||
#endif
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <stdio.h>
|
||||
#include <Print.h>
|
||||
|
||||
/**
|
||||
* Generic RingBuffer
|
||||
* T type of the buffer array
|
||||
* S size of the buffer (must be power of 2)
|
||||
*/
|
||||
|
||||
template <typename T, uint32_t S> class RingBuffer {
|
||||
public:
|
||||
RingBuffer() {index_read = index_write = 0;}
|
||||
|
||||
uint32_t available() {return mask(index_write - index_read);}
|
||||
uint32_t free() {return buffer_size - available();}
|
||||
bool empty() {return index_read == index_write;}
|
||||
bool full() {return next(index_write) == index_read;}
|
||||
void clear() {index_read = index_write = 0;}
|
||||
|
||||
bool peek(T *const value) {
|
||||
if (value == nullptr || empty()) return false;
|
||||
*value = buffer[index_read];
|
||||
return true;
|
||||
}
|
||||
|
||||
uint32_t read(T *const value) {
|
||||
if (value == nullptr || empty()) return 0;
|
||||
*value = buffer[index_read];
|
||||
index_read = next(index_read);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint32_t write(T value) {
|
||||
uint32_t next_head = next(index_write);
|
||||
if (next_head == index_read) return 0; // buffer full
|
||||
buffer[index_write] = value;
|
||||
index_write = next_head;
|
||||
return 1;
|
||||
}
|
||||
|
||||
private:
|
||||
inline uint32_t mask(uint32_t val) {
|
||||
return val & buffer_mask;
|
||||
}
|
||||
|
||||
inline uint32_t next(uint32_t val) {
|
||||
return mask(val + 1);
|
||||
}
|
||||
|
||||
static const uint32_t buffer_size = S;
|
||||
static const uint32_t buffer_mask = buffer_size - 1;
|
||||
T buffer[buffer_size];
|
||||
volatile uint32_t index_write;
|
||||
volatile uint32_t index_read;
|
||||
};
|
||||
|
||||
/**
|
||||
* Serial Interface Class
|
||||
* Data is injected directly into, and consumed from, the fifo buffers
|
||||
*/
|
||||
|
||||
class HalSerial: public Print {
|
||||
public:
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
#endif
|
||||
|
||||
HalSerial() : host_connected(false) { }
|
||||
virtual ~HalSerial() { }
|
||||
|
||||
operator bool() { return host_connected; }
|
||||
|
||||
void begin(int32_t baud) { }
|
||||
|
||||
int16_t peek() {
|
||||
uint8_t value;
|
||||
return receive_buffer.peek(&value) ? value : -1;
|
||||
}
|
||||
|
||||
int16_t read() {
|
||||
uint8_t value;
|
||||
return receive_buffer.read(&value) ? value : -1;
|
||||
}
|
||||
|
||||
size_t write(const uint8_t c) {
|
||||
if (!host_connected) return 0; // Do not fill buffer when host disconnected
|
||||
while (transmit_buffer.write(c) == 0) { // Block until there is free room in buffer
|
||||
if (!host_connected) return 0; // Break infinite loop on host disconect
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t available() {
|
||||
return (size_t)receive_buffer.available();
|
||||
}
|
||||
|
||||
void flush() {
|
||||
receive_buffer.clear();
|
||||
}
|
||||
|
||||
uint8_t availableForWrite(void) {
|
||||
return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
|
||||
}
|
||||
|
||||
void flushTX(void) {
|
||||
while (transmit_buffer.available() && host_connected) { /* nada */}
|
||||
}
|
||||
|
||||
size_t printf(const char *format, ...) {
|
||||
static char buffer[256];
|
||||
va_list vArgs;
|
||||
va_start(vArgs, format);
|
||||
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
|
||||
va_end(vArgs);
|
||||
size_t i = 0;
|
||||
if (length > 0 && length < 256) {
|
||||
while (i < (size_t)length && host_connected) {
|
||||
i += transmit_buffer.write(buffer[i]);
|
||||
}
|
||||
}
|
||||
return i;
|
||||
}
|
||||
|
||||
RingBuffer<uint8_t, 128> receive_buffer;
|
||||
RingBuffer<uint8_t, 128> transmit_buffer;
|
||||
volatile bool host_connected;
|
||||
};
|
||||
|
||||
#endif // _HAL_SERIAL_H_
|
|
@ -1,60 +0,0 @@
|
|||
from __future__ import print_function
|
||||
import sys
|
||||
|
||||
#dynamic build flags for generic compile options
|
||||
if __name__ == "__main__":
|
||||
args = " ".join([ "-std=gnu11",
|
||||
"-std=gnu++11",
|
||||
"-Os",
|
||||
"-mcpu=cortex-m3",
|
||||
"-mthumb",
|
||||
|
||||
"-fsigned-char",
|
||||
"-fno-move-loop-invariants",
|
||||
"-fno-strict-aliasing",
|
||||
"-fsingle-precision-constant",
|
||||
|
||||
"--specs=nano.specs",
|
||||
"--specs=nosys.specs",
|
||||
|
||||
# For external libraries
|
||||
"-IMarlin/src/HAL/HAL_LPC1768/include",
|
||||
|
||||
# For MarlinFirmware/U8glib-HAL
|
||||
"-IMarlin/src/HAL/HAL_LPC1768/u8g",
|
||||
"-DU8G_HAL_LINKS",
|
||||
|
||||
"-MMD",
|
||||
"-MP",
|
||||
"-DTARGET_LPC1768"
|
||||
])
|
||||
|
||||
for i in range(1, len(sys.argv)):
|
||||
args += " " + sys.argv[i]
|
||||
|
||||
print(args)
|
||||
|
||||
# extra script for linker options
|
||||
else:
|
||||
from SCons.Script import DefaultEnvironment
|
||||
env = DefaultEnvironment()
|
||||
env.Append(
|
||||
ARFLAGS=["rcs"],
|
||||
|
||||
ASFLAGS=["-x", "assembler-with-cpp"],
|
||||
|
||||
CXXFLAGS=[
|
||||
"-fabi-version=0",
|
||||
"-fno-use-cxa-atexit",
|
||||
"-fno-threadsafe-statics"
|
||||
],
|
||||
LINKFLAGS=[
|
||||
"-Wl,-Tframeworks/CMSIS/LPC1768/system/LPC1768.ld,--gc-sections",
|
||||
"-Os",
|
||||
"-mcpu=cortex-m3",
|
||||
"-mthumb",
|
||||
"--specs=nano.specs",
|
||||
"--specs=nosys.specs",
|
||||
"-u_printf_float"
|
||||
],
|
||||
)
|
|
@ -1,15 +1,5 @@
|
|||
#ifdef TARGET_LPC1768
|
||||
|
||||
// ---------------------
|
||||
// Userspace entry point
|
||||
// ---------------------
|
||||
extern void setup();
|
||||
extern void loop();
|
||||
|
||||
extern "C" {
|
||||
#include <lpc17xx_gpio.h>
|
||||
}
|
||||
|
||||
#include <usb/usb.h>
|
||||
#include <usb/usbcfg.h>
|
||||
#include <usb/usbhw.h>
|
||||
|
@ -17,52 +7,27 @@ extern "C" {
|
|||
#include <usb/cdc.h>
|
||||
#include <usb/cdcuser.h>
|
||||
#include <usb/mscuser.h>
|
||||
#include <CDCSerial.h>
|
||||
#include <usb/mscuser.h>
|
||||
|
||||
extern "C" {
|
||||
#include <debug_frmwrk.h>
|
||||
#include <chanfs/diskio.h>
|
||||
#include <chanfs/ff.h>
|
||||
}
|
||||
|
||||
#include "../../sd/cardreader.h"
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
#include "fastio.h"
|
||||
#include "HAL_timers.h"
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
#include <Arduino.h>
|
||||
#include "serial.h"
|
||||
#include "LPC1768_PWM.h"
|
||||
|
||||
static __INLINE uint32_t SysTick_Config(uint32_t ticks) {
|
||||
if (ticks > SysTick_LOAD_RELOAD_Msk) return 1;
|
||||
extern uint32_t MSC_SD_Init(uint8_t pdrv);
|
||||
extern "C" int isLPC1769();
|
||||
extern "C" void disk_timerproc(void);
|
||||
|
||||
SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; // Set reload register
|
||||
SysTick->VAL = 0; // Load the SysTick Counter Value
|
||||
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
|
||||
SysTick_CTRL_TICKINT_Msk |
|
||||
SysTick_CTRL_ENABLE_Msk; // Enable SysTick IRQ and SysTick Timer
|
||||
|
||||
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(0, 0, 0)); // Set Priority for Cortex-M3 System Interrupts
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
extern int isLPC1769();
|
||||
extern void disk_timerproc(void);
|
||||
volatile uint32_t _millis;
|
||||
|
||||
void SysTick_Handler(void) {
|
||||
++_millis;
|
||||
void SysTick_Callback() {
|
||||
disk_timerproc();
|
||||
}
|
||||
|
||||
// Runs after clock init and before global static constructors
|
||||
void SystemPostInit() {
|
||||
_millis = 0; // Initialize the millisecond counter value
|
||||
SysTick_Config(SystemCoreClock / 1000); // Start millisecond global counter
|
||||
|
||||
// Runs before setup() to configure LED_PIN and used to indicate successful bootloader execution
|
||||
void HAL_init() {
|
||||
#if PIN_EXISTS(LED)
|
||||
SET_DIR_OUTPUT(LED_PIN);
|
||||
WRITE_PIN_CLR(LED_PIN);
|
||||
|
@ -75,26 +40,34 @@ extern "C" {
|
|||
SET_DIR_OUTPUT(P1_21);
|
||||
WRITE_PIN_CLR(P1_21);
|
||||
|
||||
for (uint8_t i = 6; i--;) {
|
||||
// Flash status LED 3 times to indicate Marlin has started booting
|
||||
for (uint8_t i = 0; i < 6; ++i) {
|
||||
TOGGLE(LED_PIN);
|
||||
delay(100);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
extern uint32_t MSC_SD_Init(uint8_t pdrv);
|
||||
|
||||
int main(void) {
|
||||
|
||||
(void)MSC_SD_Init(0);
|
||||
|
||||
//debug_frmwrk_init();
|
||||
//_DBG("\n\nDebug running\n");
|
||||
// Initialise the SD card chip select pins as soon as possible
|
||||
#ifdef SS_PIN
|
||||
digitalWrite(SS_PIN, HIGH);
|
||||
pinMode(SS_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef ONBOARD_SD_CS
|
||||
digitalWrite(ONBOARD_SD_CS, HIGH);
|
||||
pinMode(ONBOARD_SD_CS, OUTPUT);
|
||||
#endif
|
||||
USB_Init(); // USB Initialization
|
||||
USB_Connect(TRUE); // USB Connect
|
||||
|
||||
USB_Connect(FALSE); // USB clear connection
|
||||
delay(1000); // Give OS time to notice
|
||||
USB_Connect(TRUE);
|
||||
#ifndef USB_SD_DISABLED
|
||||
MSC_SD_Init(0); // Enable USB SD card access
|
||||
#endif
|
||||
const uint32_t usb_timeout = millis() + 2000;
|
||||
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
|
||||
delay(50);
|
||||
HAL_idletask();
|
||||
#if PIN_EXISTS(LED)
|
||||
TOGGLE(LED_PIN); // Flash quickly during USB initialization
|
||||
#endif
|
||||
|
@ -110,11 +83,25 @@ int main(void) {
|
|||
#endif
|
||||
|
||||
HAL_timer_init();
|
||||
}
|
||||
|
||||
LPC1768_PWM_init();
|
||||
|
||||
setup();
|
||||
for (;;) loop();
|
||||
// HAL idle task
|
||||
void HAL_idletask(void) {
|
||||
#if ENABLED(SDSUPPORT) && defined(SHARED_SD_CARD)
|
||||
// If Marlin is using the SD card we need to lock it to prevent access from
|
||||
// a PC via USB.
|
||||
// Other HALs use IS_SD_PRINTING and IS_SD_FILE_OPEN to check for access but
|
||||
// this will not reliably detect delete operations. To be safe we will lock
|
||||
// the disk if Marlin has it mounted. Unfortuately there is currently no way
|
||||
// to unmount the disk from the LCD menu.
|
||||
// if (IS_SD_PRINTING || IS_SD_FILE_OPEN)
|
||||
if (card.cardOK)
|
||||
MSC_Aquire_Lock();
|
||||
else
|
||||
MSC_Release_Lock();
|
||||
#endif
|
||||
// Perform USB stack housekeeping
|
||||
MSC_RunDeferredCommands();
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
||||
|
|
|
@ -21,4 +21,4 @@
|
|||
*/
|
||||
#include "../shared/persistent_store_api.h"
|
||||
|
||||
//#define FLASH_EEPROM
|
||||
#define FLASH_EEPROM
|
||||
|
|
|
@ -69,20 +69,15 @@ bool PersistentStore::access_start() {
|
|||
__disable_irq();
|
||||
status = BlankCheckSector(EEPROM_SECTOR, EEPROM_SECTOR, &first_nblank_loc, &first_nblank_val);
|
||||
__enable_irq();
|
||||
SERIAL_PROTOCOLLNPAIR("Blank check status: ", status);
|
||||
|
||||
if (status == CMD_SUCCESS) {
|
||||
// sector is blank so nothing stored yet
|
||||
SERIAL_PROTOCOLLNPGM("FLASH empty");
|
||||
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE;
|
||||
current_slot = EEPROM_SLOTS;
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
// current slot is the first non blank one
|
||||
current_slot = first_nblank_loc / EEPROM_SIZE;
|
||||
SERIAL_PROTOCOLLNPAIR("Flash slot: ", current_slot);
|
||||
uint8_t *eeprom_data = SLOT_ADDRESS(EEPROM_SECTOR, current_slot);
|
||||
SERIAL_PROTOCOLLNPAIR("Address: ", (int)eeprom_data);
|
||||
|
||||
// load current settings
|
||||
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
|
||||
}
|
||||
|
@ -100,15 +95,15 @@ bool PersistentStore::access_finish() {
|
|||
PrepareSector(EEPROM_SECTOR, EEPROM_SECTOR);
|
||||
status = EraseSector(EEPROM_SECTOR, EEPROM_SECTOR);
|
||||
__enable_irq();
|
||||
SERIAL_PROTOCOLLNPAIR("Erase status: ", status);
|
||||
|
||||
current_slot = EEPROM_SLOTS - 1;
|
||||
}
|
||||
SERIAL_PROTOCOLLNPAIR("Writing data to: ", current_slot);
|
||||
|
||||
__disable_irq();
|
||||
PrepareSector(EEPROM_SECTOR, EEPROM_SECTOR);
|
||||
status = CopyRAM2Flash(SLOT_ADDRESS(EEPROM_SECTOR, current_slot), ram_eeprom, IAP_WRITE_4096);
|
||||
__enable_irq();
|
||||
SERIAL_PROTOCOLLNPAIR("CopyRAM2Flash status: ", status);
|
||||
|
||||
if (status != CMD_SUCCESS) return false;
|
||||
eeprom_dirty = false;
|
||||
}
|
||||
|
@ -116,7 +111,7 @@ bool PersistentStore::access_finish() {
|
|||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
for (int i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
|
||||
for (size_t i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
|
||||
eeprom_dirty = true;
|
||||
crc16(crc, value, size);
|
||||
pos += size;
|
||||
|
@ -125,7 +120,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
|
|||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
|
||||
if (writing) for (int i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
|
||||
if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
|
||||
crc16(crc, buff, size);
|
||||
pos += size;
|
||||
return false; // return true for any error
|
||||
|
|
|
@ -50,7 +50,8 @@
|
|||
#ifndef SS_PIN
|
||||
#define SS_PIN P1_23
|
||||
#endif
|
||||
#ifndef SDSS
|
||||
#if !defined(SDSS) || SDSS == P_NC // gets defaulted in pins.h
|
||||
#undef SDSS
|
||||
#define SDSS SS_PIN
|
||||
#endif
|
||||
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
|
@ -77,7 +77,7 @@
|
|||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
|
@ -55,13 +55,13 @@
|
|||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
||||
//#include <inttypes.h>
|
||||
#include <U8glib.h>
|
||||
#include "../shared/Delay.h"
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#define SPI_FULL_SPEED 0
|
||||
#define SPI_HALF_SPEED 1
|
|
@ -55,14 +55,15 @@
|
|||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
||||
#include <U8glib.h>
|
||||
#include "SoftwareSPI.h"
|
||||
#include "../shared/Delay.h"
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#undef SPI_SPEED
|
||||
#define SPI_SPEED 3 // About 1 MHz
|
||||
|
||||
static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL;
|
|
@ -55,13 +55,14 @@
|
|||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
||||
#include <U8glib.h>
|
||||
#include "SoftwareSPI.h"
|
||||
|
||||
#undef SPI_SPEED
|
||||
#define SPI_SPEED 2 // About 2 MHz
|
||||
|
||||
static uint8_t SPI_speed = 0;
|
13
Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp
Normal file
13
Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp
Normal file
|
@ -0,0 +1,13 @@
|
|||
#ifdef TARGET_LPC1768
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/emergency_parser.h"
|
||||
EmergencyParser::State emergency_state;
|
||||
bool CDC_RecvCallback(const char buffer) {
|
||||
emergency_parser.update(emergency_state, buffer);
|
||||
return true;
|
||||
}
|
||||
#endif // ENABLED(EMERGENCY_PARSER)
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -30,7 +30,29 @@
|
|||
#include "watchdog.h"
|
||||
|
||||
void watchdog_init(void) {
|
||||
#if ENABLED(WATCHDOG_RESET_MANUAL)
|
||||
// We enable the watchdog timer, but only for the interrupt.
|
||||
|
||||
// Configure WDT to only trigger an interrupt
|
||||
// Disable WDT interrupt (just in case, to avoid triggering it!)
|
||||
NVIC_DisableIRQ(WDT_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
// Configure WDT to only trigger an interrupt
|
||||
// Initialize WDT with the given parameters
|
||||
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY);
|
||||
|
||||
// Configure and enable WDT interrupt.
|
||||
NVIC_ClearPendingIRQ(WDT_IRQn);
|
||||
NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
|
||||
NVIC_EnableIRQ(WDT_IRQn);
|
||||
#else
|
||||
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
|
||||
#endif
|
||||
WDT_Start(WDT_TIMEOUT);
|
||||
}
|
||||
|
||||
|
|
|
@ -73,7 +73,7 @@
|
|||
#elif IS_TEENSY35 || IS_TEENSY36
|
||||
#include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
|
||||
#elif defined(TARGET_LPC1768)
|
||||
#include "../HAL_LPC1768/LPC1768_Servo.h"
|
||||
#include "../HAL_LPC1768/MarlinServo.h"
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#include "../HAL_STM32F1/HAL_Servo_STM32F1.h"
|
||||
#elif defined(STM32GENERIC) && defined(STM32F4)
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
#ifndef _SERVO_H_
|
||||
#define _SERVO_H_
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
#include "../HAL/shared/servo.h"
|
||||
|
||||
extern HAL_SERVO_LIB servo[NUM_SERVOS];
|
||||
|
@ -35,8 +36,6 @@ extern void servo_init();
|
|||
|
||||
#define MOVE_SERVO(I, P) servo[I].move(P)
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_Z_SERVO_PROBE
|
||||
#define DEPLOY_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][0])
|
||||
#define STOW_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][1])
|
||||
|
|
|
@ -299,19 +299,19 @@
|
|||
#elif MB(AZSMZ_MINI)
|
||||
#include "pins_AZSMZ_MINI.h" // LPC1768 env:LPC1768
|
||||
#elif MB(AZTEEG_X5_GT)
|
||||
#include "pins_AZTEEG_X5_GT.h" // LPC1769 env:LPC1768
|
||||
#include "pins_AZTEEG_X5_GT.h" // LPC1769 env:LPC1769
|
||||
#elif MB(AZTEEG_X5_MINI_WIFI)
|
||||
#include "pins_AZTEEG_X5_MINI_WIFI.h" // LPC1769 env:LPC1768
|
||||
#include "pins_AZTEEG_X5_MINI_WIFI.h" // LPC1769 env:LPC1769
|
||||
#elif MB(BIQU_BQ111_A4)
|
||||
#include "pins_BIQU_BQ111_A4.h" // LPC1768 env:LPC1768
|
||||
#elif MB(SELENA_COMPACT)
|
||||
#include "pins_SELENA_COMPACT.h" // LPC1768 env:LPC1768
|
||||
#elif MB(COHESION3D_REMIX)
|
||||
#include "pins_COHESION3D_REMIX.h" // LPC1769 env:LPC1768
|
||||
#include "pins_COHESION3D_REMIX.h" // LPC1769 env:LPC1769
|
||||
#elif MB(COHESION3D_MINI)
|
||||
#include "pins_COHESION3D_MINI.h" // LPC1769 env:LPC1768
|
||||
#include "pins_COHESION3D_MINI.h" // LPC1769 env:LPC1769
|
||||
#elif MB(SMOOTHIEBOARD)
|
||||
#include "pins_SMOOTHIEBOARD.h" // LPC1769 env:LPC1768
|
||||
#include "pins_SMOOTHIEBOARD.h" // LPC1769 env:LPC1769
|
||||
|
||||
//
|
||||
// Other 32-bit Boards
|
||||
|
|
|
@ -141,8 +141,6 @@
|
|||
// Misc. Functions
|
||||
//
|
||||
#define PS_ON_PIN P0_25 //TH3 Connector
|
||||
#define LPC_SOFTWARE_SPI // MKS_SBASE needs a software SPI because the
|
||||
// selected pins are not on a hardware SPI controller
|
||||
|
||||
/**
|
||||
* Smart LCD adapter
|
||||
|
@ -185,14 +183,76 @@
|
|||
#define ENET_TXD0 P1_00 // J12-11
|
||||
#define ENET_TXD1 P1_01 // J12-12
|
||||
|
||||
// A custom cable is needed. See the README file in the
|
||||
// Marlin\src\config\examples\Mks\Sbase directory
|
||||
|
||||
/*
|
||||
* The SBase can share the on-board SD card with a PC via USB the following
|
||||
* definitions control this feature:
|
||||
*/
|
||||
//#define USB_SD_DISABLED
|
||||
#define USB_SD_ONBOARD // Provide the onboard SD card to the host as a USB mass storage device
|
||||
|
||||
/*
|
||||
* There are a number of configurations available for the SBase SD card reader.
|
||||
* A custom cable can be used to allow access to the LCD based SD card.
|
||||
* A standard cable can be used for access to the LCD SD card (but no SD detect).
|
||||
* The onboard SD card can be used and optionally shared with a PC via USB.
|
||||
*/
|
||||
|
||||
//#define LPC_SD_CUSTOM_CABLE // Use a custom cable to access the SD
|
||||
//#define LPC_SD_LCD // Marlin uses the SD drive attached to the LCD
|
||||
#define LPC_SD_ONBOARD // Marlin uses the SD drive attached to the control board
|
||||
|
||||
#ifdef LPC_SD_CUSTOM_CABLE
|
||||
/**
|
||||
* A custom cable is needed. See the README file in the
|
||||
* Marlin\src\config\examples\Mks\Sbase directory
|
||||
* P0.27 is on EXP2 and the on-board SD card's socket. That means it can't be
|
||||
* used as the SD_DETECT for the LCD's SD card.
|
||||
*
|
||||
* The best solution is to use the custom cable to connect the LCD's SD_DETECT
|
||||
* to a pin NOT on EXP2.
|
||||
*
|
||||
* If you can't find a pin to use for the LCD's SD_DETECT then comment out
|
||||
* SD_DETECT_PIN entirely and remove that wire from the the custom cable.
|
||||
*/
|
||||
#define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27)
|
||||
#define SCK_PIN P1_22 // J8-2 (moved from EXP2 P0.7)
|
||||
#define MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8)
|
||||
#define MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.5)
|
||||
#define SS_PIN P0_28
|
||||
#define SDSS P0_06
|
||||
#define MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9)
|
||||
#define SS_PIN P0_28 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
#define LPC_SOFTWARE_SPI // With a custom cable we need software SPI because the
|
||||
// selected pins are not on a hardware SPI controller
|
||||
#endif
|
||||
|
||||
#ifdef LPC_SD_LCD
|
||||
// use standard cable and header, SPI and SD detect sre shared with on-board SD card
|
||||
// hardware SPI is used for both SD cards. The detect pin is shred between the
|
||||
// LCD and onboard SD readers so we disable it.
|
||||
#undef SD_DETECT_PIN
|
||||
#define SCK_PIN P0_07
|
||||
#define MISO_PIN P0_08
|
||||
#define MOSI_PIN P0_09
|
||||
#define SS_PIN P0_28 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
#endif
|
||||
|
||||
#ifdef LPC_SD_ONBOARD
|
||||
// The external SD card is not used. Hardware SPI is used to access the card.
|
||||
#ifdef USB_SD_ONBOARD
|
||||
// When sharing the SD card with a PC we want the menu options to
|
||||
// mount/unmount the card and refresh it. So we disable card detect.
|
||||
#define SHARED_SD_CARD
|
||||
#undef SD_DETECT_PIN
|
||||
#else
|
||||
#define SD_DETECT_PIN P0_27
|
||||
#endif
|
||||
#define SCK_PIN P0_07
|
||||
#define MISO_PIN P0_08
|
||||
#define MOSI_PIN P0_09
|
||||
#define SS_PIN P0_06 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Example for trinamic drivers using the J8 connector on MKs Sbase.
|
||||
|
@ -237,18 +297,6 @@
|
|||
#define E0_SERIAL_RX_PIN P0_26 // TH4
|
||||
#endif
|
||||
|
||||
/**
|
||||
* P0.27 is on EXP2 and the on-board SD card's socket. That means it can't be
|
||||
* used as the SD_DETECT for the LCD's SD card.
|
||||
*
|
||||
* The best solution is to use the custom cable to connect the LCD's SD_DETECT
|
||||
* to a pin NOT on EXP2.
|
||||
*
|
||||
* If you can't find a pin to use for the LCD's SD_DETECT then comment out
|
||||
* SD_DETECT_PIN entirely and remove that wire from the the custom cable.
|
||||
*/
|
||||
#define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27)
|
||||
|
||||
/**
|
||||
* PWMs
|
||||
*
|
||||
|
|
|
@ -198,7 +198,6 @@
|
|||
// Misc. Functions
|
||||
//
|
||||
#define LED_PIN P4_28 // (13)
|
||||
#define SDSS P1_23 // (53)
|
||||
|
||||
// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
|
||||
#ifndef FIL_RUNOUT_PIN
|
||||
|
@ -364,6 +363,35 @@
|
|||
#define ENET_TXD0 P1_00 // (78) J12-11
|
||||
#define ENET_TXD1 P1_01 // (79) J12-12
|
||||
|
||||
|
||||
//#define USB_SD_DISABLED
|
||||
#define USB_SD_ONBOARD // Provide the onboard SD card to the host as a USB mass storage device
|
||||
|
||||
//#define LPC_SD_LCD // Marlin uses the SD drive attached to the LCD
|
||||
#define LPC_SD_ONBOARD // Marlin uses the SD drive on the control board
|
||||
|
||||
#ifdef LPC_SD_LCD
|
||||
#define SCK_PIN P0_15
|
||||
#define MISO_PIN P0_17
|
||||
#define MOSI_PIN P0_18
|
||||
#define SS_PIN P1_23 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
#endif
|
||||
|
||||
#ifdef LPC_SD_ONBOARD
|
||||
#ifdef USB_SD_ONBOARD
|
||||
// When sharing the SD card with a PC we want the menu options to
|
||||
// mount/unmount the card and refresh it. So we disable card detect.
|
||||
#define SHARED_SD_CARD
|
||||
#undef SD_DETECT_PIN // there is also no detect pin for the onboard card
|
||||
#endif
|
||||
#define SCK_PIN P0_07
|
||||
#define MISO_PIN P0_08
|
||||
#define MOSI_PIN P0_09
|
||||
#define SS_PIN P0_06 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Fast PWMS
|
||||
*
|
||||
|
|
|
@ -1,306 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ debug_frmwrk.c 2010-05-21
|
||||
*
|
||||
* @file debug_frmwrk.c
|
||||
* @brief Contains some utilities that used for debugging through UART
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
#include "debug_frmwrk.h"
|
||||
#include "lpc17xx_pinsel.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif
|
||||
|
||||
#ifdef _DBGFWK
|
||||
|
||||
/* Debug framework */
|
||||
static Bool debug_frmwrk_initialized = FALSE;
|
||||
|
||||
void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts;
|
||||
void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts_;
|
||||
void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch) = UARTPutChar;
|
||||
void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn) = UARTPutHex;
|
||||
void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn) = UARTPutHex16;
|
||||
void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn) = UARTPutHex32;
|
||||
void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn) = UARTPutDec;
|
||||
void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn) = UARTPutDec16;
|
||||
void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn) = UARTPutDec32;
|
||||
uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx) = UARTGetChar;
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a character to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] ch Character to put
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutChar(LPC_UART_TypeDef *UARTx, uint8_t ch) {
|
||||
if (debug_frmwrk_initialized)
|
||||
UART_Send(UARTx, &ch, 1, BLOCKING);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get a character to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @return character value that returned
|
||||
**********************************************************************/
|
||||
uint8_t UARTGetChar(LPC_UART_TypeDef *UARTx) {
|
||||
uint8_t tmp = 0;
|
||||
|
||||
if (debug_frmwrk_initialized)
|
||||
UART_Receive(UARTx, &tmp, 1, BLOCKING);
|
||||
|
||||
return(tmp);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a string to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] str string to put
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
uint8_t *s = (uint8_t*)str;
|
||||
while (*s) UARTPutChar(UARTx, *s++);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a string to UART port and print new line
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] str String to put
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
UARTPuts (UARTx, str);
|
||||
UARTPuts (UARTx, "\n\r");
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a decimal number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] decnum Decimal number (8-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
uint8_t c1 = decnum%10;
|
||||
uint8_t c2 = (decnum / 10) % 10;
|
||||
uint8_t c3 = (decnum / 100) % 10;
|
||||
UARTPutChar(UARTx, '0'+c3);
|
||||
UARTPutChar(UARTx, '0'+c2);
|
||||
UARTPutChar(UARTx, '0'+c1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a decimal number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] decnum Decimal number (8-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
uint8_t c1 = decnum%10;
|
||||
uint8_t c2 = (decnum / 10) % 10;
|
||||
uint8_t c3 = (decnum / 100) % 10;
|
||||
uint8_t c4 = (decnum / 1000) % 10;
|
||||
uint8_t c5 = (decnum / 10000) % 10;
|
||||
UARTPutChar(UARTx, '0'+c5);
|
||||
UARTPutChar(UARTx, '0'+c4);
|
||||
UARTPutChar(UARTx, '0'+c3);
|
||||
UARTPutChar(UARTx, '0'+c2);
|
||||
UARTPutChar(UARTx, '0'+c1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a decimal number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] decnum Decimal number (8-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
const uint8_t c1 = decnum % 10,
|
||||
c2 = (decnum / 10) % 10,
|
||||
c3 = (decnum / 100) % 10,
|
||||
c4 = (decnum / 1000) % 10,
|
||||
c5 = (decnum / 10000) % 10,
|
||||
c6 = (decnum / 100000) % 10,
|
||||
c7 = (decnum / 1000000) % 10,
|
||||
c8 = (decnum / 10000000) % 10,
|
||||
c9 = (decnum / 100000000) % 10,
|
||||
c10 = (decnum / 1000000000) % 10;
|
||||
UARTPutChar(UARTx, '0' + c10);
|
||||
UARTPutChar(UARTx, '0' + c9);
|
||||
UARTPutChar(UARTx, '0' + c8);
|
||||
UARTPutChar(UARTx, '0' + c7);
|
||||
UARTPutChar(UARTx, '0' + c6);
|
||||
UARTPutChar(UARTx, '0' + c5);
|
||||
UARTPutChar(UARTx, '0' + c4);
|
||||
UARTPutChar(UARTx, '0' + c3);
|
||||
UARTPutChar(UARTx, '0' + c2);
|
||||
UARTPutChar(UARTx, '0' + c1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a hex number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] hexnum Hex number (8-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutHex(LPC_UART_TypeDef *UARTx, uint8_t hexnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
UARTPuts(UARTx, "0x");
|
||||
uint8_t nibble, i = 1;
|
||||
do {
|
||||
nibble = (hexnum >> (4 * i)) & 0x0F;
|
||||
UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
|
||||
} while (i--);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a hex number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] hexnum Hex number (16-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutHex16(LPC_UART_TypeDef *UARTx, uint16_t hexnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
UARTPuts(UARTx, "0x");
|
||||
uint8_t nibble, i = 3;
|
||||
do {
|
||||
nibble = (hexnum >> (4 * i)) & 0x0F;
|
||||
UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
|
||||
} while (i--);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Puts a hex number to UART port
|
||||
* @param[in] UARTx Pointer to UART peripheral
|
||||
* @param[in] hexnum Hex number (32-bit long)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void UARTPutHex32(LPC_UART_TypeDef *UARTx, uint32_t hexnum) {
|
||||
if (!debug_frmwrk_initialized) return;
|
||||
|
||||
UARTPuts(UARTx, "0x");
|
||||
uint8_t nibble, i = 7;
|
||||
do {
|
||||
nibble = (hexnum >> (4 * i)) & 0x0F;
|
||||
UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
|
||||
} while (i--);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief print function that supports format as same as printf()
|
||||
* function of <stdio.h> library
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
//void _printf (const char *format, ...) {
|
||||
// static char buffer[512 + 1];
|
||||
// va_list vArgs;
|
||||
// char *tmp;
|
||||
// va_start(vArgs, format);
|
||||
// vsprintf((char *)buffer, (char const *)format, vArgs);
|
||||
// va_end(vArgs);
|
||||
//
|
||||
// _DBG(buffer);
|
||||
//}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initialize Debug frame work through initializing UART port
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void debug_frmwrk_init(void) {
|
||||
UART_CFG_Type UARTConfigStruct;
|
||||
PINSEL_CFG_Type PinCfg;
|
||||
|
||||
#if (USED_UART_DEBUG_PORT==0)
|
||||
/*
|
||||
* Initialize UART0 pin connect
|
||||
*/
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 2;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 3;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
|
||||
#elif (USED_UART_DEBUG_PORT==1)
|
||||
/*
|
||||
* Initialize UART1 pin connect
|
||||
*/
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 15;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 16;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
#endif
|
||||
|
||||
/* Initialize UART Configuration parameter structure to default state:
|
||||
* Baudrate = 9600bps
|
||||
* 8 data bit
|
||||
* 1 Stop bit
|
||||
* None parity
|
||||
*/
|
||||
UART_ConfigStructInit(&UARTConfigStruct);
|
||||
|
||||
// Re-configure baudrate to 115200bps
|
||||
UARTConfigStruct.Baud_rate = 115200;
|
||||
|
||||
// Initialize DEBUG_UART_PORT peripheral with given to corresponding parameter
|
||||
UART_Init((LPC_UART_TypeDef *)DEBUG_UART_PORT, &UARTConfigStruct);
|
||||
|
||||
// Enable UART Transmit
|
||||
UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE);
|
||||
|
||||
debug_frmwrk_initialized = TRUE;
|
||||
}
|
||||
|
||||
#endif // _DBGFWK
|
|
@ -1,358 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_adc.c 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_adc.c
|
||||
* @brief Contains all functions support for ADC firmware library on LPC17xx
|
||||
* @version 3.1
|
||||
* @date 26. July. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup ADC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_adc.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _ADC
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup ADC_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial for ADC
|
||||
* + Set bit PCADC
|
||||
* + Set clock for ADC
|
||||
* + Set Clock Frequency
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] rate ADC conversion rate, should be <=200KHz
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_Init(LPC_ADC_TypeDef *ADCx, uint32_t rate)
|
||||
{
|
||||
uint32_t ADCPClk, temp, tmp;
|
||||
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_RATE(rate));
|
||||
|
||||
// Turn on power and clock
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCAD, ENABLE);
|
||||
|
||||
ADCx->ADCR = 0;
|
||||
|
||||
//Enable PDN bit
|
||||
tmp = ADC_CR_PDN;
|
||||
// Set clock frequency
|
||||
ADCPClk = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_ADC);
|
||||
/* The APB clock (PCLK_ADC0) is divided by (CLKDIV+1) to produce the clock for
|
||||
* A/D converter, which should be less than or equal to 13MHz.
|
||||
* A fully conversion requires 65 of these clocks.
|
||||
* ADC clock = PCLK_ADC0 / (CLKDIV + 1);
|
||||
* ADC rate = ADC clock / 65;
|
||||
*/
|
||||
temp = rate * 65;
|
||||
temp = (ADCPClk * 2 + temp)/(2 * temp) - 1; //get the round value by fomular: (2*A + B)/(2*B)
|
||||
tmp |= ADC_CR_CLKDIV(temp);
|
||||
|
||||
ADCx->ADCR = tmp;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Close ADC
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_DeInit(LPC_ADC_TypeDef *ADCx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
if (ADCx->ADCR & ADC_CR_START_MASK) //need to stop START bits before DeInit
|
||||
ADCx->ADCR &= ~ADC_CR_START_MASK;
|
||||
// Clear SEL bits
|
||||
ADCx->ADCR &= ~0xFF;
|
||||
// Clear PDN bit
|
||||
ADCx->ADCR &= ~ADC_CR_PDN;
|
||||
// Turn on power and clock
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCAD, DISABLE);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get Result conversion from A/D data register
|
||||
* @param[in] channel number which want to read back the result
|
||||
* @return Result of conversion
|
||||
*********************************************************************/
|
||||
uint32_t ADC_GetData(uint32_t channel)
|
||||
{
|
||||
uint32_t adc_value;
|
||||
|
||||
CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
|
||||
|
||||
adc_value = *(uint32_t *)((&LPC_ADC->ADDR0) + channel);
|
||||
return ADC_GDR_RESULT(adc_value);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set start mode for ADC
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] start_mode Start mode choose one of modes in
|
||||
* 'ADC_START_OPT' enumeration type definition, should be:
|
||||
* - ADC_START_CONTINUOUS
|
||||
* - ADC_START_NOW
|
||||
* - ADC_START_ON_EINT0
|
||||
* - ADC_START_ON_CAP01
|
||||
* - ADC_START_ON_MAT01
|
||||
* - ADC_START_ON_MAT03
|
||||
* - ADC_START_ON_MAT10
|
||||
* - ADC_START_ON_MAT11
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void ADC_StartCmd(LPC_ADC_TypeDef *ADCx, uint8_t start_mode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_START_OPT(start_mode));
|
||||
|
||||
ADCx->ADCR &= ~ADC_CR_START_MASK;
|
||||
ADCx->ADCR |=ADC_CR_START_MODE_SEL((uint32_t)start_mode);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief ADC Burst mode setting
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] NewState
|
||||
* - 1: Set Burst mode
|
||||
* - 0: reset Burst mode
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_BurstCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
|
||||
ADCx->ADCR &= ~ADC_CR_BURST;
|
||||
if (NewState){
|
||||
ADCx->ADCR |= ADC_CR_BURST;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set AD conversion in power mode
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] NewState
|
||||
* - 1: AD converter is optional
|
||||
* - 0: AD Converter is in power down mode
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_PowerdownCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
|
||||
ADCx->ADCR &= ~ADC_CR_PDN;
|
||||
if (NewState){
|
||||
ADCx->ADCR |= ADC_CR_PDN;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Edge start configuration
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] EdgeOption is ADC_START_ON_RISING and ADC_START_ON_FALLING
|
||||
* 0:ADC_START_ON_RISING
|
||||
* 1:ADC_START_ON_FALLING
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_EdgeStartConfig(LPC_ADC_TypeDef *ADCx, uint8_t EdgeOption)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_START_ON_EDGE_OPT(EdgeOption));
|
||||
|
||||
ADCx->ADCR &= ~ADC_CR_EDGE;
|
||||
if (EdgeOption){
|
||||
ADCx->ADCR |= ADC_CR_EDGE;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief ADC interrupt configuration
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] IntType: type of interrupt, should be:
|
||||
* - ADC_ADINTEN0: Interrupt channel 0
|
||||
* - ADC_ADINTEN1: Interrupt channel 1
|
||||
* ...
|
||||
* - ADC_ADINTEN7: Interrupt channel 7
|
||||
* - ADC_ADGINTEN: Individual channel/global flag done generate an interrupt
|
||||
* @param[in] NewState:
|
||||
* - SET : enable ADC interrupt
|
||||
* - RESET: disable ADC interrupt
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_IntConfig (LPC_ADC_TypeDef *ADCx, ADC_TYPE_INT_OPT IntType, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_TYPE_INT_OPT(IntType));
|
||||
|
||||
ADCx->ADINTEN &= ~ADC_INTEN_CH(IntType);
|
||||
if (NewState){
|
||||
ADCx->ADINTEN |= ADC_INTEN_CH(IntType);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable ADC channel number
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] Channel channel number
|
||||
* @param[in] NewState Enable or Disable
|
||||
*
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void ADC_ChannelCmd (LPC_ADC_TypeDef *ADCx, uint8_t Channel, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(Channel));
|
||||
|
||||
if (NewState == ENABLE) {
|
||||
ADCx->ADCR |= ADC_CR_CH_SEL(Channel);
|
||||
} else {
|
||||
if (ADCx->ADCR & ADC_CR_START_MASK) //need to stop START bits before disable channel
|
||||
ADCx->ADCR &= ~ADC_CR_START_MASK;
|
||||
ADCx->ADCR &= ~ADC_CR_CH_SEL(Channel);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get ADC result
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] channel: channel number, should be 0...7
|
||||
* @return Data conversion
|
||||
**********************************************************************/
|
||||
uint16_t ADC_ChannelGetData(LPC_ADC_TypeDef *ADCx, uint8_t channel)
|
||||
{
|
||||
uint32_t adc_value;
|
||||
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
|
||||
|
||||
adc_value = *(uint32_t *) ((&ADCx->ADDR0) + channel);
|
||||
return ADC_DR_RESULT(adc_value);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get ADC Chanel status from ADC data register
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] channel: channel number, should be 0..7
|
||||
* @param[in] StatusType
|
||||
* 0:Burst status
|
||||
* 1:Done status
|
||||
* @return SET / RESET
|
||||
**********************************************************************/
|
||||
FlagStatus ADC_ChannelGetStatus(LPC_ADC_TypeDef *ADCx, uint8_t channel, uint32_t StatusType)
|
||||
{
|
||||
uint32_t temp;
|
||||
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
|
||||
CHECK_PARAM(PARAM_ADC_DATA_STATUS(StatusType));
|
||||
|
||||
temp = *(uint32_t *) ((&ADCx->ADDR0) + channel);
|
||||
if (StatusType) {
|
||||
temp &= ADC_DR_DONE_FLAG;
|
||||
}else{
|
||||
temp &= ADC_DR_OVERRUN_FLAG;
|
||||
}
|
||||
if (temp) {
|
||||
return SET;
|
||||
} else {
|
||||
return RESET;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get ADC Data from AD Global register
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @return Result of conversion
|
||||
**********************************************************************/
|
||||
uint32_t ADC_GlobalGetData(LPC_ADC_TypeDef *ADCx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
|
||||
return ((uint32_t)(ADCx->ADGDR));
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get ADC Chanel status from AD global data register
|
||||
* @param[in] ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
|
||||
* @param[in] StatusType
|
||||
* 0:Burst status
|
||||
* 1:Done status
|
||||
* @return SET / RESET
|
||||
**********************************************************************/
|
||||
FlagStatus ADC_GlobalGetStatus(LPC_ADC_TypeDef *ADCx, uint32_t StatusType)
|
||||
{
|
||||
uint32_t temp;
|
||||
|
||||
CHECK_PARAM(PARAM_ADCx(ADCx));
|
||||
CHECK_PARAM(PARAM_ADC_DATA_STATUS(StatusType));
|
||||
|
||||
temp = ADCx->ADGDR;
|
||||
if (StatusType){
|
||||
temp &= ADC_DR_DONE_FLAG;
|
||||
}else{
|
||||
temp &= ADC_DR_OVERRUN_FLAG;
|
||||
}
|
||||
if (temp){
|
||||
return SET;
|
||||
}else{
|
||||
return RESET;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _ADC */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
File diff suppressed because it is too large
Load diff
|
@ -1,350 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_clkpwr.c 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_clkpwr.c
|
||||
* @brief Contains all functions support for Clock and Power Control
|
||||
* firmware library on LPC17xx
|
||||
* @version 3.0
|
||||
* @date 18. June. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup CLKPWR
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup CLKPWR_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set value of each Peripheral Clock Selection
|
||||
* @param[in] ClkType Peripheral Clock Selection of each type,
|
||||
* should be one of the following:
|
||||
* - CLKPWR_PCLKSEL_WDT : WDT
|
||||
- CLKPWR_PCLKSEL_TIMER0 : Timer 0
|
||||
- CLKPWR_PCLKSEL_TIMER1 : Timer 1
|
||||
- CLKPWR_PCLKSEL_UART0 : UART 0
|
||||
- CLKPWR_PCLKSEL_UART1 : UART 1
|
||||
- CLKPWR_PCLKSEL_PWM1 : PWM 1
|
||||
- CLKPWR_PCLKSEL_I2C0 : I2C 0
|
||||
- CLKPWR_PCLKSEL_SPI : SPI
|
||||
- CLKPWR_PCLKSEL_SSP1 : SSP 1
|
||||
- CLKPWR_PCLKSEL_DAC : DAC
|
||||
- CLKPWR_PCLKSEL_ADC : ADC
|
||||
- CLKPWR_PCLKSEL_CAN1 : CAN 1
|
||||
- CLKPWR_PCLKSEL_CAN2 : CAN 2
|
||||
- CLKPWR_PCLKSEL_ACF : ACF
|
||||
- CLKPWR_PCLKSEL_QEI : QEI
|
||||
- CLKPWR_PCLKSEL_PCB : PCB
|
||||
- CLKPWR_PCLKSEL_I2C1 : I2C 1
|
||||
- CLKPWR_PCLKSEL_SSP0 : SSP 0
|
||||
- CLKPWR_PCLKSEL_TIMER2 : Timer 2
|
||||
- CLKPWR_PCLKSEL_TIMER3 : Timer 3
|
||||
- CLKPWR_PCLKSEL_UART2 : UART 2
|
||||
- CLKPWR_PCLKSEL_UART3 : UART 3
|
||||
- CLKPWR_PCLKSEL_I2C2 : I2C 2
|
||||
- CLKPWR_PCLKSEL_I2S : I2S
|
||||
- CLKPWR_PCLKSEL_RIT : RIT
|
||||
- CLKPWR_PCLKSEL_SYSCON : SYSCON
|
||||
- CLKPWR_PCLKSEL_MC : MC
|
||||
|
||||
* @param[in] DivVal Value of divider, should be:
|
||||
* - CLKPWR_PCLKSEL_CCLK_DIV_4 : PCLK_peripheral = CCLK/4
|
||||
* - CLKPWR_PCLKSEL_CCLK_DIV_1 : PCLK_peripheral = CCLK/1
|
||||
* - CLKPWR_PCLKSEL_CCLK_DIV_2 : PCLK_peripheral = CCLK/2
|
||||
*
|
||||
* @return none
|
||||
**********************************************************************/
|
||||
void CLKPWR_SetPCLKDiv (uint32_t ClkType, uint32_t DivVal)
|
||||
{
|
||||
uint32_t bitpos;
|
||||
|
||||
bitpos = (ClkType < 32) ? (ClkType) : (ClkType - 32);
|
||||
|
||||
/* PCLKSEL0 selected */
|
||||
if (ClkType < 32)
|
||||
{
|
||||
/* Clear two bit at bit position */
|
||||
LPC_SC->PCLKSEL0 &= (~(CLKPWR_PCLKSEL_BITMASK(bitpos)));
|
||||
|
||||
/* Set two selected bit */
|
||||
LPC_SC->PCLKSEL0 |= (CLKPWR_PCLKSEL_SET(bitpos, DivVal));
|
||||
}
|
||||
/* PCLKSEL1 selected */
|
||||
else
|
||||
{
|
||||
/* Clear two bit at bit position */
|
||||
LPC_SC->PCLKSEL1 &= ~(CLKPWR_PCLKSEL_BITMASK(bitpos));
|
||||
|
||||
/* Set two selected bit */
|
||||
LPC_SC->PCLKSEL1 |= (CLKPWR_PCLKSEL_SET(bitpos, DivVal));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current value of each Peripheral Clock Selection
|
||||
* @param[in] ClkType Peripheral Clock Selection of each type,
|
||||
* should be one of the following:
|
||||
* - CLKPWR_PCLKSEL_WDT : WDT
|
||||
- CLKPWR_PCLKSEL_TIMER0 : Timer 0
|
||||
- CLKPWR_PCLKSEL_TIMER1 : Timer 1
|
||||
- CLKPWR_PCLKSEL_UART0 : UART 0
|
||||
- CLKPWR_PCLKSEL_UART1 : UART 1
|
||||
- CLKPWR_PCLKSEL_PWM1 : PWM 1
|
||||
- CLKPWR_PCLKSEL_I2C0 : I2C 0
|
||||
- CLKPWR_PCLKSEL_SPI : SPI
|
||||
- CLKPWR_PCLKSEL_SSP1 : SSP 1
|
||||
- CLKPWR_PCLKSEL_DAC : DAC
|
||||
- CLKPWR_PCLKSEL_ADC : ADC
|
||||
- CLKPWR_PCLKSEL_CAN1 : CAN 1
|
||||
- CLKPWR_PCLKSEL_CAN2 : CAN 2
|
||||
- CLKPWR_PCLKSEL_ACF : ACF
|
||||
- CLKPWR_PCLKSEL_QEI : QEI
|
||||
- CLKPWR_PCLKSEL_PCB : PCB
|
||||
- CLKPWR_PCLKSEL_I2C1 : I2C 1
|
||||
- CLKPWR_PCLKSEL_SSP0 : SSP 0
|
||||
- CLKPWR_PCLKSEL_TIMER2 : Timer 2
|
||||
- CLKPWR_PCLKSEL_TIMER3 : Timer 3
|
||||
- CLKPWR_PCLKSEL_UART2 : UART 2
|
||||
- CLKPWR_PCLKSEL_UART3 : UART 3
|
||||
- CLKPWR_PCLKSEL_I2C2 : I2C 2
|
||||
- CLKPWR_PCLKSEL_I2S : I2S
|
||||
- CLKPWR_PCLKSEL_RIT : RIT
|
||||
- CLKPWR_PCLKSEL_SYSCON : SYSCON
|
||||
- CLKPWR_PCLKSEL_MC : MC
|
||||
|
||||
* @return Value of Selected Peripheral Clock Selection
|
||||
**********************************************************************/
|
||||
uint32_t CLKPWR_GetPCLKSEL (uint32_t ClkType)
|
||||
{
|
||||
uint32_t bitpos, retval;
|
||||
|
||||
if (ClkType < 32)
|
||||
{
|
||||
bitpos = ClkType;
|
||||
retval = LPC_SC->PCLKSEL0;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitpos = ClkType - 32;
|
||||
retval = LPC_SC->PCLKSEL1;
|
||||
}
|
||||
|
||||
retval = CLKPWR_PCLKSEL_GET(bitpos, retval);
|
||||
return retval;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current value of each Peripheral Clock
|
||||
* @param[in] ClkType Peripheral Clock Selection of each type,
|
||||
* should be one of the following:
|
||||
* - CLKPWR_PCLKSEL_WDT : WDT
|
||||
- CLKPWR_PCLKSEL_TIMER0 : Timer 0
|
||||
- CLKPWR_PCLKSEL_TIMER1 : Timer 1
|
||||
- CLKPWR_PCLKSEL_UART0 : UART 0
|
||||
- CLKPWR_PCLKSEL_UART1 : UART 1
|
||||
- CLKPWR_PCLKSEL_PWM1 : PWM 1
|
||||
- CLKPWR_PCLKSEL_I2C0 : I2C 0
|
||||
- CLKPWR_PCLKSEL_SPI : SPI
|
||||
- CLKPWR_PCLKSEL_SSP1 : SSP 1
|
||||
- CLKPWR_PCLKSEL_DAC : DAC
|
||||
- CLKPWR_PCLKSEL_ADC : ADC
|
||||
- CLKPWR_PCLKSEL_CAN1 : CAN 1
|
||||
- CLKPWR_PCLKSEL_CAN2 : CAN 2
|
||||
- CLKPWR_PCLKSEL_ACF : ACF
|
||||
- CLKPWR_PCLKSEL_QEI : QEI
|
||||
- CLKPWR_PCLKSEL_PCB : PCB
|
||||
- CLKPWR_PCLKSEL_I2C1 : I2C 1
|
||||
- CLKPWR_PCLKSEL_SSP0 : SSP 0
|
||||
- CLKPWR_PCLKSEL_TIMER2 : Timer 2
|
||||
- CLKPWR_PCLKSEL_TIMER3 : Timer 3
|
||||
- CLKPWR_PCLKSEL_UART2 : UART 2
|
||||
- CLKPWR_PCLKSEL_UART3 : UART 3
|
||||
- CLKPWR_PCLKSEL_I2C2 : I2C 2
|
||||
- CLKPWR_PCLKSEL_I2S : I2S
|
||||
- CLKPWR_PCLKSEL_RIT : RIT
|
||||
- CLKPWR_PCLKSEL_SYSCON : SYSCON
|
||||
- CLKPWR_PCLKSEL_MC : MC
|
||||
|
||||
* @return Value of Selected Peripheral Clock
|
||||
**********************************************************************/
|
||||
uint32_t CLKPWR_GetPCLK (uint32_t ClkType)
|
||||
{
|
||||
uint32_t retval, div;
|
||||
|
||||
retval = SystemCoreClock;
|
||||
div = CLKPWR_GetPCLKSEL(ClkType);
|
||||
|
||||
switch (div)
|
||||
{
|
||||
case 0:
|
||||
div = 4;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
div = 1;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
div = 2;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
div = 8;
|
||||
break;
|
||||
}
|
||||
retval /= div;
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configure power supply for each peripheral according to NewState
|
||||
* @param[in] PPType Type of peripheral used to enable power,
|
||||
* should be one of the following:
|
||||
* - CLKPWR_PCONP_PCTIM0 : Timer 0
|
||||
- CLKPWR_PCONP_PCTIM1 : Timer 1
|
||||
- CLKPWR_PCONP_PCUART0 : UART 0
|
||||
- CLKPWR_PCONP_PCUART1 : UART 1
|
||||
- CLKPWR_PCONP_PCPWM1 : PWM 1
|
||||
- CLKPWR_PCONP_PCI2C0 : I2C 0
|
||||
- CLKPWR_PCONP_PCSPI : SPI
|
||||
- CLKPWR_PCONP_PCRTC : RTC
|
||||
- CLKPWR_PCONP_PCSSP1 : SSP 1
|
||||
- CLKPWR_PCONP_PCAD : ADC
|
||||
- CLKPWR_PCONP_PCAN1 : CAN 1
|
||||
- CLKPWR_PCONP_PCAN2 : CAN 2
|
||||
- CLKPWR_PCONP_PCGPIO : GPIO
|
||||
- CLKPWR_PCONP_PCRIT : RIT
|
||||
- CLKPWR_PCONP_PCMC : MC
|
||||
- CLKPWR_PCONP_PCQEI : QEI
|
||||
- CLKPWR_PCONP_PCI2C1 : I2C 1
|
||||
- CLKPWR_PCONP_PCSSP0 : SSP 0
|
||||
- CLKPWR_PCONP_PCTIM2 : Timer 2
|
||||
- CLKPWR_PCONP_PCTIM3 : Timer 3
|
||||
- CLKPWR_PCONP_PCUART2 : UART 2
|
||||
- CLKPWR_PCONP_PCUART3 : UART 3
|
||||
- CLKPWR_PCONP_PCI2C2 : I2C 2
|
||||
- CLKPWR_PCONP_PCI2S : I2S
|
||||
- CLKPWR_PCONP_PCGPDMA : GPDMA
|
||||
- CLKPWR_PCONP_PCENET : Ethernet
|
||||
- CLKPWR_PCONP_PCUSB : USB
|
||||
*
|
||||
* @param[in] NewState New state of Peripheral Power, should be:
|
||||
* - ENABLE : Enable power for this peripheral
|
||||
* - DISABLE : Disable power for this peripheral
|
||||
*
|
||||
* @return none
|
||||
**********************************************************************/
|
||||
void CLKPWR_ConfigPPWR (uint32_t PPType, FunctionalState NewState)
|
||||
{
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
LPC_SC->PCONP |= PPType & CLKPWR_PCONP_BITMASK;
|
||||
}
|
||||
else if (NewState == DISABLE)
|
||||
{
|
||||
LPC_SC->PCONP &= (~PPType) & CLKPWR_PCONP_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enter Sleep mode with co-operated instruction by the Cortex-M3.
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void CLKPWR_Sleep(void)
|
||||
{
|
||||
LPC_SC->PCON = 0x00;
|
||||
/* Sleep Mode*/
|
||||
__WFI();
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enter Deep Sleep mode with co-operated instruction by the Cortex-M3.
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void CLKPWR_DeepSleep(void)
|
||||
{
|
||||
/* Deep-Sleep Mode, set SLEEPDEEP bit */
|
||||
SCB->SCR = 0x4;
|
||||
LPC_SC->PCON = 0x00;
|
||||
/* Deep Sleep Mode*/
|
||||
__WFI();
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enter Power Down mode with co-operated instruction by the Cortex-M3.
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void CLKPWR_PowerDown(void)
|
||||
{
|
||||
/* Deep-Sleep Mode, set SLEEPDEEP bit */
|
||||
SCB->SCR = 0x4;
|
||||
LPC_SC->PCON = 0x01;
|
||||
/* Power Down Mode*/
|
||||
__WFI();
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enter Deep Power Down mode with co-operated instruction by the Cortex-M3.
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void CLKPWR_DeepPowerDown(void)
|
||||
{
|
||||
/* Deep-Sleep Mode, set SLEEPDEEP bit */
|
||||
SCB->SCR = 0x4;
|
||||
LPC_SC->PCON = 0x03;
|
||||
/* Deep Power Down Mode*/
|
||||
__WFI();
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,151 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_dac.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_dac.c
|
||||
* @brief Contains all functions support for DAC firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup DAC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_dac.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _DAC
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup DAC_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial ADC configuration
|
||||
* - Maximum current is 700 uA
|
||||
* - Value to AOUT is 0
|
||||
* @param[in] DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void DAC_Init(LPC_DAC_TypeDef *DACx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_DACx(DACx));
|
||||
/* Set default clock divider for DAC */
|
||||
// CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_DAC, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
//Set maximum current output
|
||||
DAC_SetBias(LPC_DAC,DAC_MAX_CURRENT_700uA);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Update value to DAC
|
||||
* @param[in] DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
|
||||
* @param[in] dac_value : value 10 bit to be converted to output
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void DAC_UpdateValue (LPC_DAC_TypeDef *DACx,uint32_t dac_value)
|
||||
{
|
||||
uint32_t tmp;
|
||||
CHECK_PARAM(PARAM_DACx(DACx));
|
||||
tmp = DACx->DACR & DAC_BIAS_EN;
|
||||
tmp |= DAC_VALUE(dac_value);
|
||||
// Update value
|
||||
DACx->DACR = tmp;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Maximum current for DAC
|
||||
* @param[in] DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
|
||||
* @param[in] bias : 0 is 700 uA
|
||||
* 1 350 uA
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void DAC_SetBias (LPC_DAC_TypeDef *DACx,uint32_t bias)
|
||||
{
|
||||
CHECK_PARAM(PARAM_DAC_CURRENT_OPT(bias));
|
||||
DACx->DACR &=~DAC_BIAS_EN;
|
||||
if (bias == DAC_MAX_CURRENT_350uA)
|
||||
{
|
||||
DACx->DACR |= DAC_BIAS_EN;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief To enable the DMA operation and control DMA timer
|
||||
* @param[in] DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
|
||||
* @param[in] DAC_ConverterConfigStruct pointer to DAC_CONVERTER_CFG_Type
|
||||
* - DBLBUF_ENA : enable/disable DACR double buffering feature
|
||||
* - CNT_ENA : enable/disable timer out counter
|
||||
* - DMA_ENA : enable/disable DMA access
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void DAC_ConfigDAConverterControl (LPC_DAC_TypeDef *DACx,DAC_CONVERTER_CFG_Type *DAC_ConverterConfigStruct)
|
||||
{
|
||||
CHECK_PARAM(PARAM_DACx(DACx));
|
||||
DACx->DACCTRL &= ~DAC_DACCTRL_MASK;
|
||||
if (DAC_ConverterConfigStruct->DBLBUF_ENA)
|
||||
DACx->DACCTRL |= DAC_DBLBUF_ENA;
|
||||
if (DAC_ConverterConfigStruct->CNT_ENA)
|
||||
DACx->DACCTRL |= DAC_CNT_ENA;
|
||||
if (DAC_ConverterConfigStruct->DMA_ENA)
|
||||
DACx->DACCTRL |= DAC_DMA_ENA;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set reload value for interrupt/DMA counter
|
||||
* @param[in] DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
|
||||
* @param[in] time_out time out to reload for interrupt/DMA counter
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void DAC_SetDMATimeOut(LPC_DAC_TypeDef *DACx, uint32_t time_out)
|
||||
{
|
||||
CHECK_PARAM(PARAM_DACx(DACx));
|
||||
DACx->DACCNTVAL = DAC_CCNT_VALUE(time_out);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _DAC */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,963 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_emac.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_emac.c
|
||||
* @brief Contains all functions support for Ethernet MAC firmware
|
||||
* library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup EMAC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_emac.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _EMAC
|
||||
|
||||
/* Private Variables ---------------------------------------------------------- */
|
||||
/** @defgroup EMAC_Private_Variables EMAC Private Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* MII Mgmt Configuration register - Clock divider setting */
|
||||
const uint8_t EMAC_clkdiv[] = { 4, 6, 8, 10, 14, 20, 28, 36, 40, 44, 48, 52, 56, 60, 64};
|
||||
|
||||
/* EMAC local DMA Descriptors */
|
||||
|
||||
/** Rx Descriptor data array */
|
||||
static RX_Desc Rx_Desc[EMAC_NUM_RX_FRAG];
|
||||
|
||||
/** Rx Status data array - Must be 8-Byte aligned */
|
||||
#if defined ( __CC_ARM )
|
||||
static __align(8) RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
|
||||
#elif defined ( __ICCARM__ )
|
||||
#pragma data_alignment=8
|
||||
static RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
|
||||
#elif defined ( __GNUC__ )
|
||||
static __attribute__ ((aligned (8))) RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
|
||||
#endif
|
||||
|
||||
/** Tx Descriptor data array */
|
||||
static TX_Desc Tx_Desc[EMAC_NUM_TX_FRAG];
|
||||
/** Tx Status data array */
|
||||
static TX_Stat Tx_Stat[EMAC_NUM_TX_FRAG];
|
||||
|
||||
/* EMAC local DMA buffers */
|
||||
/** Rx buffer data */
|
||||
static uint32_t rx_buf[EMAC_NUM_RX_FRAG][EMAC_ETH_MAX_FLEN>>2];
|
||||
/** Tx buffer data */
|
||||
static uint32_t tx_buf[EMAC_NUM_TX_FRAG][EMAC_ETH_MAX_FLEN>>2];
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Functions ---------------------------------------------------------- */
|
||||
static void rx_descr_init (void);
|
||||
static void tx_descr_init (void);
|
||||
static int32_t write_PHY (uint32_t PhyReg, uint16_t Value);
|
||||
static int32_t read_PHY (uint32_t PhyReg);
|
||||
|
||||
static void setEmacAddr(uint8_t abStationAddr[]);
|
||||
static int32_t emac_CRCCalc(uint8_t frame_no_fcs[], int32_t frame_len);
|
||||
|
||||
|
||||
/*--------------------------- rx_descr_init ---------------------------------*/
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes RX Descriptor
|
||||
* @param[in] None
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
static void rx_descr_init (void)
|
||||
{
|
||||
/* Initialize Receive Descriptor and Status array. */
|
||||
uint32_t i;
|
||||
|
||||
for (i = 0; i < EMAC_NUM_RX_FRAG; i++) {
|
||||
Rx_Desc[i].Packet = (uint32_t)&rx_buf[i];
|
||||
Rx_Desc[i].Ctrl = EMAC_RCTRL_INT | (EMAC_ETH_MAX_FLEN - 1);
|
||||
Rx_Stat[i].Info = 0;
|
||||
Rx_Stat[i].HashCRC = 0;
|
||||
}
|
||||
|
||||
/* Set EMAC Receive Descriptor Registers. */
|
||||
LPC_EMAC->RxDescriptor = (uint32_t)&Rx_Desc[0];
|
||||
LPC_EMAC->RxStatus = (uint32_t)&Rx_Stat[0];
|
||||
LPC_EMAC->RxDescriptorNumber = EMAC_NUM_RX_FRAG - 1;
|
||||
|
||||
/* Rx Descriptors Point to 0 */
|
||||
LPC_EMAC->RxConsumeIndex = 0;
|
||||
}
|
||||
|
||||
|
||||
/*--------------------------- tx_descr_init ---- ----------------------------*/
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes TX Descriptor
|
||||
* @param[in] None
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
static void tx_descr_init (void) {
|
||||
/* Initialize Transmit Descriptor and Status array. */
|
||||
uint32_t i;
|
||||
|
||||
for (i = 0; i < EMAC_NUM_TX_FRAG; i++) {
|
||||
Tx_Desc[i].Packet = (uint32_t)&tx_buf[i];
|
||||
Tx_Desc[i].Ctrl = 0;
|
||||
Tx_Stat[i].Info = 0;
|
||||
}
|
||||
|
||||
/* Set EMAC Transmit Descriptor Registers. */
|
||||
LPC_EMAC->TxDescriptor = (uint32_t)&Tx_Desc[0];
|
||||
LPC_EMAC->TxStatus = (uint32_t)&Tx_Stat[0];
|
||||
LPC_EMAC->TxDescriptorNumber = EMAC_NUM_TX_FRAG - 1;
|
||||
|
||||
/* Tx Descriptors Point to 0 */
|
||||
LPC_EMAC->TxProduceIndex = 0;
|
||||
}
|
||||
|
||||
|
||||
/*--------------------------- write_PHY -------------------------------------*/
|
||||
/*********************************************************************//**
|
||||
* @brief Write value to PHY device
|
||||
* @param[in] PhyReg: PHY Register address
|
||||
* @param[in] Value: Value to write
|
||||
* @return 0 - if success
|
||||
* 1 - if fail
|
||||
***********************************************************************/
|
||||
static int32_t write_PHY (uint32_t PhyReg, uint16_t Value)
|
||||
{
|
||||
/* Write a data 'Value' to PHY register 'PhyReg'. */
|
||||
uint32_t tout;
|
||||
|
||||
LPC_EMAC->MADR = EMAC_DEF_ADR | PhyReg;
|
||||
LPC_EMAC->MWTD = Value;
|
||||
|
||||
/* Wait until operation completed */
|
||||
tout = 0;
|
||||
for (tout = 0; tout < EMAC_MII_WR_TOUT; tout++) {
|
||||
if ((LPC_EMAC->MIND & EMAC_MIND_BUSY) == 0) {
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
// Time out!
|
||||
return (-1);
|
||||
}
|
||||
|
||||
|
||||
/*--------------------------- read_PHY --------------------------------------*/
|
||||
/*********************************************************************//**
|
||||
* @brief Read value from PHY device
|
||||
* @param[in] PhyReg: PHY Register address
|
||||
* @return 0 - if success
|
||||
* 1 - if fail
|
||||
***********************************************************************/
|
||||
static int32_t read_PHY (uint32_t PhyReg)
|
||||
{
|
||||
/* Read a PHY register 'PhyReg'. */
|
||||
uint32_t tout;
|
||||
|
||||
LPC_EMAC->MADR = EMAC_DEF_ADR | PhyReg;
|
||||
LPC_EMAC->MCMD = EMAC_MCMD_READ;
|
||||
|
||||
/* Wait until operation completed */
|
||||
tout = 0;
|
||||
for (tout = 0; tout < EMAC_MII_RD_TOUT; tout++) {
|
||||
if ((LPC_EMAC->MIND & EMAC_MIND_BUSY) == 0) {
|
||||
LPC_EMAC->MCMD = 0;
|
||||
return (LPC_EMAC->MRDD);
|
||||
}
|
||||
}
|
||||
// Time out!
|
||||
return (-1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Station MAC address for EMAC module
|
||||
* @param[in] abStationAddr Pointer to Station address that contains 6-bytes
|
||||
* of MAC address (should be in order from MAC Address 1 to MAC Address 6)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
static void setEmacAddr(uint8_t abStationAddr[])
|
||||
{
|
||||
/* Set the Ethernet MAC Address registers */
|
||||
LPC_EMAC->SA0 = ((uint32_t)abStationAddr[5] << 8) | (uint32_t)abStationAddr[4];
|
||||
LPC_EMAC->SA1 = ((uint32_t)abStationAddr[3] << 8) | (uint32_t)abStationAddr[2];
|
||||
LPC_EMAC->SA2 = ((uint32_t)abStationAddr[1] << 8) | (uint32_t)abStationAddr[0];
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Calculates CRC code for number of bytes in the frame
|
||||
* @param[in] frame_no_fcs Pointer to the first byte of the frame
|
||||
* @param[in] frame_len length of the frame without the FCS
|
||||
* @return the CRC as a 32 bit integer
|
||||
**********************************************************************/
|
||||
static int32_t emac_CRCCalc(uint8_t frame_no_fcs[], int32_t frame_len)
|
||||
{
|
||||
int i; // iterator
|
||||
int j; // another iterator
|
||||
char byte; // current byte
|
||||
int crc; // CRC result
|
||||
int q0, q1, q2, q3; // temporary variables
|
||||
crc = 0xFFFFFFFF;
|
||||
for (i = 0; i < frame_len; i++) {
|
||||
byte = *frame_no_fcs++;
|
||||
for (j = 0; j < 2; j++) {
|
||||
if (((crc >> 28) ^ (byte >> 3)) & 0x00000001) {
|
||||
q3 = 0x04C11DB7;
|
||||
} else {
|
||||
q3 = 0x00000000;
|
||||
}
|
||||
if (((crc >> 29) ^ (byte >> 2)) & 0x00000001) {
|
||||
q2 = 0x09823B6E;
|
||||
} else {
|
||||
q2 = 0x00000000;
|
||||
}
|
||||
if (((crc >> 30) ^ (byte >> 1)) & 0x00000001) {
|
||||
q1 = 0x130476DC;
|
||||
} else {
|
||||
q1 = 0x00000000;
|
||||
}
|
||||
if (((crc >> 31) ^ (byte >> 0)) & 0x00000001) {
|
||||
q0 = 0x2608EDB8;
|
||||
} else {
|
||||
q0 = 0x00000000;
|
||||
}
|
||||
crc = (crc << 4) ^ q3 ^ q2 ^ q1 ^ q0;
|
||||
byte >>= 4;
|
||||
}
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
/* End of Private Functions --------------------------------------------------- */
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup EMAC_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes the EMAC peripheral according to the specified
|
||||
* parameters in the EMAC_ConfigStruct.
|
||||
* @param[in] EMAC_ConfigStruct Pointer to a EMAC_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified EMAC peripheral.
|
||||
* @return None
|
||||
*
|
||||
* Note: This function will initialize EMAC module according to procedure below:
|
||||
* - Remove the soft reset condition from the MAC
|
||||
* - Configure the PHY via the MIIM interface of the MAC
|
||||
* - Select RMII mode
|
||||
* - Configure the transmit and receive DMA engines, including the descriptor arrays
|
||||
* - Configure the host registers (MAC1,MAC2 etc.) in the MAC
|
||||
* - Enable the receive and transmit data paths
|
||||
* In default state after initializing, only Rx Done and Tx Done interrupt are enabled,
|
||||
* all remain interrupts are disabled
|
||||
* (Ref. from LPC17xx UM)
|
||||
**********************************************************************/
|
||||
Status EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct)
|
||||
{
|
||||
/* Initialize the EMAC Ethernet controller. */
|
||||
int32_t regv,tout, tmp;
|
||||
|
||||
/* Set up clock and power for Ethernet module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCENET, ENABLE);
|
||||
|
||||
/* Reset all EMAC internal modules */
|
||||
LPC_EMAC->MAC1 = EMAC_MAC1_RES_TX | EMAC_MAC1_RES_MCS_TX | EMAC_MAC1_RES_RX |
|
||||
EMAC_MAC1_RES_MCS_RX | EMAC_MAC1_SIM_RES | EMAC_MAC1_SOFT_RES;
|
||||
|
||||
LPC_EMAC->Command = EMAC_CR_REG_RES | EMAC_CR_TX_RES | EMAC_CR_RX_RES | EMAC_CR_PASS_RUNT_FRM;
|
||||
|
||||
/* A short delay after reset. */
|
||||
for (tout = 100; tout; tout--);
|
||||
|
||||
/* Initialize MAC control registers. */
|
||||
LPC_EMAC->MAC1 = EMAC_MAC1_PASS_ALL;
|
||||
LPC_EMAC->MAC2 = EMAC_MAC2_CRC_EN | EMAC_MAC2_PAD_EN;
|
||||
LPC_EMAC->MAXF = EMAC_ETH_MAX_FLEN;
|
||||
/*
|
||||
* Find the clock that close to desired target clock
|
||||
*/
|
||||
tmp = SystemCoreClock / EMAC_MCFG_MII_MAXCLK;
|
||||
for (tout = 0; tout < sizeof (EMAC_clkdiv); tout++){
|
||||
if (EMAC_clkdiv[tout] >= tmp) break;
|
||||
}
|
||||
tout++;
|
||||
// Write to MAC configuration register and reset
|
||||
LPC_EMAC->MCFG = EMAC_MCFG_CLK_SEL(tout) | EMAC_MCFG_RES_MII;
|
||||
// release reset
|
||||
LPC_EMAC->MCFG &= ~(EMAC_MCFG_RES_MII);
|
||||
LPC_EMAC->CLRT = EMAC_CLRT_DEF;
|
||||
LPC_EMAC->IPGR = EMAC_IPGR_P2_DEF;
|
||||
|
||||
/* Enable Reduced MII interface. */
|
||||
LPC_EMAC->Command = EMAC_CR_RMII | EMAC_CR_PASS_RUNT_FRM;
|
||||
|
||||
/* Reset Reduced MII Logic. */
|
||||
// LPC_EMAC->SUPP = EMAC_SUPP_RES_RMII;
|
||||
|
||||
for (tout = 100; tout; tout--);
|
||||
LPC_EMAC->SUPP = 0;
|
||||
|
||||
/* Put the DP83848C in reset mode */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_BMCR_RESET);
|
||||
|
||||
/* Wait for hardware reset to end. */
|
||||
for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
|
||||
regv = read_PHY (EMAC_PHY_REG_BMCR);
|
||||
if (!(regv & (EMAC_PHY_BMCR_RESET | EMAC_PHY_BMCR_POWERDOWN))) {
|
||||
/* Reset complete, device not Power Down. */
|
||||
break;
|
||||
}
|
||||
if (tout == 0){
|
||||
// Time out, return ERROR
|
||||
return (ERROR);
|
||||
}
|
||||
}
|
||||
|
||||
// Set PHY mode
|
||||
if (EMAC_SetPHYMode(EMAC_ConfigStruct->Mode) < 0){
|
||||
return (ERROR);
|
||||
}
|
||||
|
||||
// Set EMAC address
|
||||
setEmacAddr(EMAC_ConfigStruct->pbEMAC_Addr);
|
||||
|
||||
/* Initialize Tx and Rx DMA Descriptors */
|
||||
rx_descr_init ();
|
||||
tx_descr_init ();
|
||||
|
||||
// Set Receive Filter register: enable broadcast and multicast
|
||||
LPC_EMAC->RxFilterCtrl = EMAC_RFC_MCAST_EN | EMAC_RFC_BCAST_EN | EMAC_RFC_PERFECT_EN;
|
||||
|
||||
/* Enable Rx Done and Tx Done interrupt for EMAC */
|
||||
LPC_EMAC->IntEnable = EMAC_INT_RX_DONE | EMAC_INT_TX_DONE;
|
||||
|
||||
/* Reset all interrupts */
|
||||
LPC_EMAC->IntClear = 0xFFFF;
|
||||
|
||||
/* Enable receive and transmit mode of MAC Ethernet core */
|
||||
LPC_EMAC->Command |= (EMAC_CR_RX_EN | EMAC_CR_TX_EN);
|
||||
LPC_EMAC->MAC1 |= EMAC_MAC1_REC_EN;
|
||||
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the EMAC peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_DeInit(void)
|
||||
{
|
||||
// Disable all interrupt
|
||||
LPC_EMAC->IntEnable = 0x00;
|
||||
// Clear all pending interrupt
|
||||
LPC_EMAC->IntClear = (0xFF) | (EMAC_INT_SOFT_INT | EMAC_INT_WAKEUP);
|
||||
|
||||
/* TurnOff clock and power for Ethernet module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCENET, DISABLE);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check specified PHY status in EMAC peripheral
|
||||
* @param[in] ulPHYState Specified PHY Status Type, should be:
|
||||
* - EMAC_PHY_STAT_LINK: Link Status
|
||||
* - EMAC_PHY_STAT_SPEED: Speed Status
|
||||
* - EMAC_PHY_STAT_DUP: Duplex Status
|
||||
* @return Status of specified PHY status (0 or 1).
|
||||
* (-1) if error.
|
||||
*
|
||||
* Note:
|
||||
* For EMAC_PHY_STAT_LINK, return value:
|
||||
* - 0: Link Down
|
||||
* - 1: Link Up
|
||||
* For EMAC_PHY_STAT_SPEED, return value:
|
||||
* - 0: 10Mbps
|
||||
* - 1: 100Mbps
|
||||
* For EMAC_PHY_STAT_DUP, return value:
|
||||
* - 0: Half-Duplex
|
||||
* - 1: Full-Duplex
|
||||
**********************************************************************/
|
||||
int32_t EMAC_CheckPHYStatus(uint32_t ulPHYState)
|
||||
{
|
||||
int32_t regv, tmp;
|
||||
#ifdef MCB_LPC_1768
|
||||
regv = read_PHY (EMAC_PHY_REG_STS);
|
||||
switch(ulPHYState){
|
||||
case EMAC_PHY_STAT_LINK:
|
||||
tmp = (regv & EMAC_PHY_SR_LINK) ? 1 : 0;
|
||||
break;
|
||||
case EMAC_PHY_STAT_SPEED:
|
||||
tmp = (regv & EMAC_PHY_SR_SPEED) ? 0 : 1;
|
||||
break;
|
||||
case EMAC_PHY_STAT_DUP:
|
||||
tmp = (regv & EMAC_PHY_SR_FULL_DUP) ? 1 : 0;
|
||||
break;
|
||||
#elif defined(IAR_LPC_1768)
|
||||
/* Use IAR_LPC_1768 board:
|
||||
* FSZ8721BL doesn't have Status Register
|
||||
* so we read Basic Mode Status Register (0x01h) instead
|
||||
*/
|
||||
regv = read_PHY (EMAC_PHY_REG_BMSR);
|
||||
switch(ulPHYState){
|
||||
case EMAC_PHY_STAT_LINK:
|
||||
tmp = (regv & EMAC_PHY_BMSR_LINK_STATUS) ? 1 : 0;
|
||||
break;
|
||||
case EMAC_PHY_STAT_SPEED:
|
||||
tmp = (regv & EMAC_PHY_SR_100_SPEED) ? 1 : 0;
|
||||
break;
|
||||
case EMAC_PHY_STAT_DUP:
|
||||
tmp = (regv & EMAC_PHY_SR_FULL_DUP) ? 1 : 0;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
tmp = -1;
|
||||
break;
|
||||
}
|
||||
return (tmp);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set specified PHY mode in EMAC peripheral
|
||||
* @param[in] ulPHYMode Specified PHY mode, should be:
|
||||
* - EMAC_MODE_AUTO
|
||||
* - EMAC_MODE_10M_FULL
|
||||
* - EMAC_MODE_10M_HALF
|
||||
* - EMAC_MODE_100M_FULL
|
||||
* - EMAC_MODE_100M_HALF
|
||||
* @return Return (0) if no error, otherwise return (-1)
|
||||
**********************************************************************/
|
||||
int32_t EMAC_SetPHYMode(uint32_t ulPHYMode)
|
||||
{
|
||||
int32_t id1, id2, tout;
|
||||
|
||||
/* Check if this is a DP83848C PHY. */
|
||||
id1 = read_PHY (EMAC_PHY_REG_IDR1);
|
||||
id2 = read_PHY (EMAC_PHY_REG_IDR2);
|
||||
|
||||
#ifdef MCB_LPC_1768
|
||||
if (((id1 << 16) | (id2 & 0xFFF0)) == EMAC_DP83848C_ID) {
|
||||
switch(ulPHYMode){
|
||||
case EMAC_MODE_AUTO:
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_AUTO_NEG);
|
||||
#elif defined(IAR_LPC_1768) /* Use IAR LPC1768 KickStart board */
|
||||
if (((id1 << 16) | id2) == EMAC_KSZ8721BL_ID) {
|
||||
/* Configure the PHY device */
|
||||
switch(ulPHYMode){
|
||||
case EMAC_MODE_AUTO:
|
||||
/* Use auto-negotiation about the link speed. */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_AUTO_NEG);
|
||||
// write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_BMCR_AN);
|
||||
#endif
|
||||
/* Wait to complete Auto_Negotiation */
|
||||
for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
|
||||
|
||||
}
|
||||
break;
|
||||
case EMAC_MODE_10M_FULL:
|
||||
/* Connect at 10MBit full-duplex */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_FULLD_10M);
|
||||
break;
|
||||
case EMAC_MODE_10M_HALF:
|
||||
/* Connect at 10MBit half-duplex */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_HALFD_10M);
|
||||
break;
|
||||
case EMAC_MODE_100M_FULL:
|
||||
/* Connect at 100MBit full-duplex */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_FULLD_100M);
|
||||
break;
|
||||
case EMAC_MODE_100M_HALF:
|
||||
/* Connect at 100MBit half-duplex */
|
||||
write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_HALFD_100M);
|
||||
break;
|
||||
default:
|
||||
// un-supported
|
||||
return (-1);
|
||||
}
|
||||
}
|
||||
// It's not correct module ID
|
||||
else {
|
||||
return (-1);
|
||||
}
|
||||
|
||||
// Update EMAC configuration with current PHY status
|
||||
if (EMAC_UpdatePHYStatus() < 0){
|
||||
return (-1);
|
||||
}
|
||||
|
||||
// Complete
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Auto-Configures value for the EMAC configuration register to
|
||||
* match with current PHY mode
|
||||
* @param[in] None
|
||||
* @return Return (0) if no error, otherwise return (-1)
|
||||
*
|
||||
* Note: The EMAC configuration will be auto-configured:
|
||||
* - Speed mode.
|
||||
* - Half/Full duplex mode
|
||||
**********************************************************************/
|
||||
int32_t EMAC_UpdatePHYStatus(void)
|
||||
{
|
||||
int32_t regv, tout;
|
||||
|
||||
/* Check the link status. */
|
||||
#ifdef MCB_LPC_1768
|
||||
for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
|
||||
regv = read_PHY (EMAC_PHY_REG_STS);
|
||||
if (regv & EMAC_PHY_SR_LINK) {
|
||||
/* Link is on. */
|
||||
break;
|
||||
}
|
||||
if (tout == 0){
|
||||
// time out
|
||||
return (-1);
|
||||
}
|
||||
}
|
||||
/* Configure Full/Half Duplex mode. */
|
||||
if (regv & EMAC_PHY_SR_DUP) {
|
||||
/* Full duplex is enabled. */
|
||||
LPC_EMAC->MAC2 |= EMAC_MAC2_FULL_DUP;
|
||||
LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
|
||||
LPC_EMAC->IPGT = EMAC_IPGT_FULL_DUP;
|
||||
} else {
|
||||
/* Half duplex mode. */
|
||||
LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
|
||||
}
|
||||
if (regv & EMAC_PHY_SR_SPEED) {
|
||||
/* 10MBit mode. */
|
||||
LPC_EMAC->SUPP = 0;
|
||||
} else {
|
||||
/* 100MBit mode. */
|
||||
LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
|
||||
}
|
||||
#elif defined(IAR_LPC_1768)
|
||||
for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
|
||||
regv = read_PHY (EMAC_PHY_REG_BMSR);
|
||||
if (regv & EMAC_PHY_BMSR_LINK_STATUS) {
|
||||
/* Link is on. */
|
||||
break;
|
||||
}
|
||||
if (tout == 0){
|
||||
// time out
|
||||
return (-1);
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure Full/Half Duplex mode. */
|
||||
if (regv & EMAC_PHY_SR_FULL_DUP) {
|
||||
/* Full duplex is enabled. */
|
||||
LPC_EMAC->MAC2 |= EMAC_MAC2_FULL_DUP;
|
||||
LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
|
||||
LPC_EMAC->IPGT = EMAC_IPGT_FULL_DUP;
|
||||
} else {
|
||||
/* Half duplex mode. */
|
||||
LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
|
||||
}
|
||||
|
||||
/* Configure 100MBit/10MBit mode. */
|
||||
if (!(regv & EMAC_PHY_SR_100_SPEED)) {
|
||||
/* 10MBit mode. */
|
||||
LPC_EMAC->SUPP = 0;
|
||||
} else {
|
||||
/* 100MBit mode. */
|
||||
LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
|
||||
}
|
||||
#endif
|
||||
// Complete
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable hash filter functionality for specified destination
|
||||
* MAC address in EMAC module
|
||||
* @param[in] dstMAC_addr Pointer to the first MAC destination address, should
|
||||
* be 6-bytes length, in order LSB to the MSB
|
||||
* @param[in] NewState New State of this command, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* The standard Ethernet cyclic redundancy check (CRC) function is calculated from
|
||||
* the 6 byte destination address in the Ethernet frame (this CRC is calculated
|
||||
* anyway as part of calculating the CRC of the whole frame), then bits [28:23] out of
|
||||
* the 32 bits CRC result are taken to form the hash. The 6 bit hash is used to access
|
||||
* the hash table: it is used as an index in the 64 bit HashFilter register that has been
|
||||
* programmed with accept values. If the selected accept value is 1, the frame is
|
||||
* accepted.
|
||||
**********************************************************************/
|
||||
void EMAC_SetHashFilter(uint8_t dstMAC_addr[], FunctionalState NewState)
|
||||
{
|
||||
uint32_t *pReg;
|
||||
uint32_t tmp;
|
||||
int32_t crc;
|
||||
|
||||
// Calculate the CRC from the destination MAC address
|
||||
crc = emac_CRCCalc(dstMAC_addr, 6);
|
||||
// Extract the value from CRC to get index value for hash filter table
|
||||
crc = (crc >> 23) & 0x3F;
|
||||
|
||||
pReg = (crc > 31) ? ((uint32_t *)&LPC_EMAC->HashFilterH) \
|
||||
: ((uint32_t *)&LPC_EMAC->HashFilterL);
|
||||
tmp = (crc > 31) ? (crc - 32) : crc;
|
||||
if (NewState == ENABLE) {
|
||||
(*pReg) |= (1UL << tmp);
|
||||
} else {
|
||||
(*pReg) &= ~(1UL << tmp);
|
||||
}
|
||||
// Enable Rx Filter
|
||||
LPC_EMAC->Command &= ~EMAC_CR_PASS_RX_FILT;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable Filter mode for each specified type EMAC peripheral
|
||||
* @param[in] ulFilterMode Filter mode, should be:
|
||||
* - EMAC_RFC_UCAST_EN: all frames of unicast types
|
||||
* will be accepted
|
||||
* - EMAC_RFC_BCAST_EN: broadcast frame will be
|
||||
* accepted
|
||||
* - EMAC_RFC_MCAST_EN: all frames of multicast
|
||||
* types will be accepted
|
||||
* - EMAC_RFC_UCAST_HASH_EN: The imperfect hash
|
||||
* filter will be applied to unicast addresses
|
||||
* - EMAC_RFC_MCAST_HASH_EN: The imperfect hash
|
||||
* filter will be applied to multicast addresses
|
||||
* - EMAC_RFC_PERFECT_EN: the destination address
|
||||
* will be compared with the 6 byte station address
|
||||
* programmed in the station address by the filter
|
||||
* - EMAC_RFC_MAGP_WOL_EN: the result of the magic
|
||||
* packet filter will generate a WoL interrupt when
|
||||
* there is a match
|
||||
* - EMAC_RFC_PFILT_WOL_EN: the result of the perfect address
|
||||
* matching filter and the imperfect hash filter will
|
||||
* generate a WoL interrupt when there is a match
|
||||
* @param[in] NewState New State of this command, should be:
|
||||
* - ENABLE
|
||||
* - DISABLE
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_SetFilterMode(uint32_t ulFilterMode, FunctionalState NewState)
|
||||
{
|
||||
if (NewState == ENABLE){
|
||||
LPC_EMAC->RxFilterCtrl |= ulFilterMode;
|
||||
} else {
|
||||
LPC_EMAC->RxFilterCtrl &= ~ulFilterMode;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get status of Wake On LAN Filter for each specified
|
||||
* type in EMAC peripheral, clear this status if it is set
|
||||
* @param[in] ulWoLMode WoL Filter mode, should be:
|
||||
* - EMAC_WOL_UCAST: unicast frames caused WoL
|
||||
* - EMAC_WOL_UCAST: broadcast frame caused WoL
|
||||
* - EMAC_WOL_MCAST: multicast frame caused WoL
|
||||
* - EMAC_WOL_UCAST_HASH: unicast frame that passes the
|
||||
* imperfect hash filter caused WoL
|
||||
* - EMAC_WOL_MCAST_HASH: multicast frame that passes the
|
||||
* imperfect hash filter caused WoL
|
||||
* - EMAC_WOL_PERFECT:perfect address matching filter
|
||||
* caused WoL
|
||||
* - EMAC_WOL_RX_FILTER: the receive filter caused WoL
|
||||
* - EMAC_WOL_MAG_PACKET: the magic packet filter caused WoL
|
||||
* @return SET/RESET
|
||||
**********************************************************************/
|
||||
FlagStatus EMAC_GetWoLStatus(uint32_t ulWoLMode)
|
||||
{
|
||||
if (LPC_EMAC->RxFilterWoLStatus & ulWoLMode) {
|
||||
LPC_EMAC->RxFilterWoLClear = ulWoLMode;
|
||||
return SET;
|
||||
} else {
|
||||
return RESET;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Write data to Tx packet data buffer at current index due to
|
||||
* TxProduceIndex
|
||||
* @param[in] pDataStruct Pointer to a EMAC_PACKETBUF_Type structure
|
||||
* data that contain specified information about
|
||||
* Packet data buffer.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_WritePacketBuffer(EMAC_PACKETBUF_Type *pDataStruct)
|
||||
{
|
||||
uint32_t idx,len;
|
||||
uint32_t *sp,*dp;
|
||||
|
||||
idx = LPC_EMAC->TxProduceIndex;
|
||||
sp = (uint32_t *)pDataStruct->pbDataBuf;
|
||||
dp = (uint32_t *)Tx_Desc[idx].Packet;
|
||||
/* Copy frame data to EMAC packet buffers. */
|
||||
for (len = (pDataStruct->ulDataLen + 3) >> 2; len; len--) {
|
||||
*dp++ = *sp++;
|
||||
}
|
||||
Tx_Desc[idx].Ctrl = (pDataStruct->ulDataLen - 1) | (EMAC_TCTRL_INT | EMAC_TCTRL_LAST);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read data from Rx packet data buffer at current index due
|
||||
* to RxConsumeIndex
|
||||
* @param[in] pDataStruct Pointer to a EMAC_PACKETBUF_Type structure
|
||||
* data that contain specified information about
|
||||
* Packet data buffer.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_ReadPacketBuffer(EMAC_PACKETBUF_Type *pDataStruct)
|
||||
{
|
||||
uint32_t idx, len;
|
||||
uint32_t *dp, *sp;
|
||||
|
||||
idx = LPC_EMAC->RxConsumeIndex;
|
||||
dp = (uint32_t *)pDataStruct->pbDataBuf;
|
||||
sp = (uint32_t *)Rx_Desc[idx].Packet;
|
||||
|
||||
if (pDataStruct->pbDataBuf != NULL) {
|
||||
for (len = (pDataStruct->ulDataLen + 3) >> 2; len; len--) {
|
||||
*dp++ = *sp++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable interrupt for each type in EMAC
|
||||
* @param[in] ulIntType Interrupt Type, should be:
|
||||
* - EMAC_INT_RX_OVERRUN: Receive Overrun
|
||||
* - EMAC_INT_RX_ERR: Receive Error
|
||||
* - EMAC_INT_RX_FIN: Receive Descriptor Finish
|
||||
* - EMAC_INT_RX_DONE: Receive Done
|
||||
* - EMAC_INT_TX_UNDERRUN: Transmit Under-run
|
||||
* - EMAC_INT_TX_ERR: Transmit Error
|
||||
* - EMAC_INT_TX_FIN: Transmit descriptor finish
|
||||
* - EMAC_INT_TX_DONE: Transmit Done
|
||||
* - EMAC_INT_SOFT_INT: Software interrupt
|
||||
* - EMAC_INT_WAKEUP: Wakeup interrupt
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_IntCmd(uint32_t ulIntType, FunctionalState NewState)
|
||||
{
|
||||
if (NewState == ENABLE) {
|
||||
LPC_EMAC->IntEnable |= ulIntType;
|
||||
} else {
|
||||
LPC_EMAC->IntEnable &= ~(ulIntType);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if specified interrupt flag is set or not
|
||||
* for each interrupt type in EMAC and clear interrupt pending
|
||||
* if it is set.
|
||||
* @param[in] ulIntType Interrupt Type, should be:
|
||||
* - EMAC_INT_RX_OVERRUN: Receive Overrun
|
||||
* - EMAC_INT_RX_ERR: Receive Error
|
||||
* - EMAC_INT_RX_FIN: Receive Descriptor Finish
|
||||
* - EMAC_INT_RX_DONE: Receive Done
|
||||
* - EMAC_INT_TX_UNDERRUN: Transmit Under-run
|
||||
* - EMAC_INT_TX_ERR: Transmit Error
|
||||
* - EMAC_INT_TX_FIN: Transmit descriptor finish
|
||||
* - EMAC_INT_TX_DONE: Transmit Done
|
||||
* - EMAC_INT_SOFT_INT: Software interrupt
|
||||
* - EMAC_INT_WAKEUP: Wakeup interrupt
|
||||
* @return New state of specified interrupt (SET or RESET)
|
||||
**********************************************************************/
|
||||
IntStatus EMAC_IntGetStatus(uint32_t ulIntType)
|
||||
{
|
||||
if (LPC_EMAC->IntStatus & ulIntType) {
|
||||
LPC_EMAC->IntClear = ulIntType;
|
||||
return SET;
|
||||
} else {
|
||||
return RESET;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if the current RxConsumeIndex is not equal to the
|
||||
* current RxProduceIndex.
|
||||
* @param[in] None
|
||||
* @return TRUE if they're not equal, otherwise return FALSE
|
||||
*
|
||||
* Note: In case the RxConsumeIndex is not equal to the RxProduceIndex,
|
||||
* it means there're available data has been received. They should be read
|
||||
* out and released the Receive Data Buffer by updating the RxConsumeIndex value.
|
||||
**********************************************************************/
|
||||
Bool EMAC_CheckReceiveIndex(void)
|
||||
{
|
||||
if (LPC_EMAC->RxConsumeIndex != LPC_EMAC->RxProduceIndex) {
|
||||
return TRUE;
|
||||
} else {
|
||||
return FALSE;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if the current TxProduceIndex is not equal to the
|
||||
* current RxProduceIndex - 1.
|
||||
* @param[in] None
|
||||
* @return TRUE if they're not equal, otherwise return FALSE
|
||||
*
|
||||
* Note: In case the RxConsumeIndex is equal to the RxProduceIndex - 1,
|
||||
* it means the transmit buffer is available and data can be written to transmit
|
||||
* buffer to be sent.
|
||||
**********************************************************************/
|
||||
Bool EMAC_CheckTransmitIndex(void)
|
||||
{
|
||||
uint32_t tmp = LPC_EMAC->TxConsumeIndex;
|
||||
if (LPC_EMAC->TxProduceIndex == ( tmp - 1 ))
|
||||
{
|
||||
return FALSE;
|
||||
}
|
||||
else if( ( tmp == 0 ) && ( LPC_EMAC->TxProduceIndex == ( EMAC_NUM_TX_FRAG - 1 ) ) )
|
||||
{
|
||||
return FALSE;
|
||||
}
|
||||
else
|
||||
{
|
||||
return TRUE;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current status value of receive data (due to RxConsumeIndex)
|
||||
* @param[in] ulRxStatType Received Status type, should be one of following:
|
||||
* - EMAC_RINFO_CTRL_FRAME: Control Frame
|
||||
* - EMAC_RINFO_VLAN: VLAN Frame
|
||||
* - EMAC_RINFO_FAIL_FILT: RX Filter Failed
|
||||
* - EMAC_RINFO_MCAST: Multicast Frame
|
||||
* - EMAC_RINFO_BCAST: Broadcast Frame
|
||||
* - EMAC_RINFO_CRC_ERR: CRC Error in Frame
|
||||
* - EMAC_RINFO_SYM_ERR: Symbol Error from PHY
|
||||
* - EMAC_RINFO_LEN_ERR: Length Error
|
||||
* - EMAC_RINFO_RANGE_ERR: Range error(exceeded max size)
|
||||
* - EMAC_RINFO_ALIGN_ERR: Alignment error
|
||||
* - EMAC_RINFO_OVERRUN: Receive overrun
|
||||
* - EMAC_RINFO_NO_DESCR: No new Descriptor available
|
||||
* - EMAC_RINFO_LAST_FLAG: last Fragment in Frame
|
||||
* - EMAC_RINFO_ERR: Error Occurred (OR of all error)
|
||||
* @return Current value of receive data (due to RxConsumeIndex)
|
||||
**********************************************************************/
|
||||
FlagStatus EMAC_CheckReceiveDataStatus(uint32_t ulRxStatType)
|
||||
{
|
||||
uint32_t idx;
|
||||
idx = LPC_EMAC->RxConsumeIndex;
|
||||
return (((Rx_Stat[idx].Info) & ulRxStatType) ? SET : RESET);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get size of current Received data in received buffer (due to
|
||||
* RxConsumeIndex)
|
||||
* @param[in] None
|
||||
* @return Size of received data
|
||||
**********************************************************************/
|
||||
uint32_t EMAC_GetReceiveDataSize(void)
|
||||
{
|
||||
uint32_t idx;
|
||||
idx =LPC_EMAC->RxConsumeIndex;
|
||||
return ((Rx_Stat[idx].Info) & EMAC_RINFO_SIZE);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Increase the RxConsumeIndex (after reading the Receive buffer
|
||||
* to release the Receive buffer) and wrap-around the index if
|
||||
* it reaches the maximum Receive Number
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_UpdateRxConsumeIndex(void)
|
||||
{
|
||||
// Get current Rx consume index
|
||||
uint32_t idx = LPC_EMAC->RxConsumeIndex;
|
||||
|
||||
/* Release frame from EMAC buffer */
|
||||
if (++idx == EMAC_NUM_RX_FRAG) idx = 0;
|
||||
LPC_EMAC->RxConsumeIndex = idx;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Increase the TxProduceIndex (after writting to the Transmit buffer
|
||||
* to enable the Transmit buffer) and wrap-around the index if
|
||||
* it reaches the maximum Transmit Number
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EMAC_UpdateTxProduceIndex(void)
|
||||
{
|
||||
// Get current Tx produce index
|
||||
uint32_t idx = LPC_EMAC->TxProduceIndex;
|
||||
|
||||
/* Start frame transmission */
|
||||
if (++idx == EMAC_NUM_TX_FRAG) idx = 0;
|
||||
LPC_EMAC->TxProduceIndex = idx;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _EMAC */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,171 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_exti.c 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_exti.c
|
||||
* @brief Contains all functions support for External interrupt firmware
|
||||
* library on LPC17xx
|
||||
* @version 3.0
|
||||
* @date 18. June. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup EXTI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_exti.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _EXTI
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup EXTI_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial for EXT
|
||||
* - Set EXTINT, EXTMODE, EXTPOLAR registers to default value
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EXTI_Init(void)
|
||||
{
|
||||
LPC_SC->EXTINT = 0xF;
|
||||
LPC_SC->EXTMODE = 0x0;
|
||||
LPC_SC->EXTPOLAR = 0x0;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Close EXT
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EXTI_DeInit(void)
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configuration for EXT
|
||||
* - Set EXTINT, EXTMODE, EXTPOLAR register
|
||||
* @param[in] EXTICfg Pointer to a EXTI_InitTypeDef structure
|
||||
* that contains the configuration information for the
|
||||
* specified external interrupt
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void EXTI_Config(EXTI_InitTypeDef *EXTICfg)
|
||||
{
|
||||
LPC_SC->EXTINT = 0x0;
|
||||
EXTI_SetMode(EXTICfg->EXTI_Line, EXTICfg->EXTI_Mode);
|
||||
EXTI_SetPolarity(EXTICfg->EXTI_Line, EXTICfg->EXTI_polarity);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set mode for EXTI pin
|
||||
* @param[in] EXTILine external interrupt line, should be:
|
||||
* - EXTI_EINT0: external interrupt line 0
|
||||
* - EXTI_EINT1: external interrupt line 1
|
||||
* - EXTI_EINT2: external interrupt line 2
|
||||
* - EXTI_EINT3: external interrupt line 3
|
||||
* @param[in] mode external mode, should be:
|
||||
* - EXTI_MODE_LEVEL_SENSITIVE
|
||||
* - EXTI_MODE_EDGE_SENSITIVE
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void EXTI_SetMode(EXTI_LINE_ENUM EXTILine, EXTI_MODE_ENUM mode)
|
||||
{
|
||||
if(mode == EXTI_MODE_EDGE_SENSITIVE)
|
||||
{
|
||||
LPC_SC->EXTMODE |= (1 << EXTILine);
|
||||
}
|
||||
else if(mode == EXTI_MODE_LEVEL_SENSITIVE)
|
||||
{
|
||||
LPC_SC->EXTMODE &= ~(1 << EXTILine);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set polarity for EXTI pin
|
||||
* @param[in] EXTILine external interrupt line, should be:
|
||||
* - EXTI_EINT0: external interrupt line 0
|
||||
* - EXTI_EINT1: external interrupt line 1
|
||||
* - EXTI_EINT2: external interrupt line 2
|
||||
* - EXTI_EINT3: external interrupt line 3
|
||||
* @param[in] polarity external polarity value, should be:
|
||||
* - EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE
|
||||
* - EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void EXTI_SetPolarity(EXTI_LINE_ENUM EXTILine, EXTI_POLARITY_ENUM polarity)
|
||||
{
|
||||
if(polarity == EXTI_POLARITY_HIGH_ACTIVE_OR_RISING_EDGE)
|
||||
{
|
||||
LPC_SC->EXTPOLAR |= (1 << EXTILine);
|
||||
}
|
||||
else if(polarity == EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE)
|
||||
{
|
||||
LPC_SC->EXTPOLAR &= ~(1 << EXTILine);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear External interrupt flag
|
||||
* @param[in] EXTILine external interrupt line, should be:
|
||||
* - EXTI_EINT0: external interrupt line 0
|
||||
* - EXTI_EINT1: external interrupt line 1
|
||||
* - EXTI_EINT2: external interrupt line 2
|
||||
* - EXTI_EINT3: external interrupt line 3
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void EXTI_ClearEXTIFlag(EXTI_LINE_ENUM EXTILine)
|
||||
{
|
||||
LPC_SC->EXTINT = (1 << EXTILine);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _EXTI */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,463 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_gpdma.c 2010-03-21
|
||||
*//**
|
||||
* @file lpc17xx_gpdma.c
|
||||
* @brief Contains all functions support for GPDMA firmware
|
||||
* library on LPC17xx
|
||||
* @version 2.1
|
||||
* @date 25. July. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup GPDMA
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_gpdma.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
#ifdef _GPDMA
|
||||
|
||||
|
||||
/* Private Variables ---------------------------------------------------------- */
|
||||
/** @defgroup GPDMA_Private_Variables GPDMA Private Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Lookup Table of Connection Type matched with
|
||||
* Peripheral Data (FIFO) register base address
|
||||
*/
|
||||
//#ifdef __IAR_SYSTEMS_ICC__
|
||||
volatile const void *GPDMA_LUTPerAddr[] = {
|
||||
(&LPC_SSP0->DR), // SSP0 Tx
|
||||
(&LPC_SSP0->DR), // SSP0 Rx
|
||||
(&LPC_SSP1->DR), // SSP1 Tx
|
||||
(&LPC_SSP1->DR), // SSP1 Rx
|
||||
(&LPC_ADC->ADGDR), // ADC
|
||||
(&LPC_I2S->I2STXFIFO), // I2S Tx
|
||||
(&LPC_I2S->I2SRXFIFO), // I2S Rx
|
||||
(&LPC_DAC->DACR), // DAC
|
||||
(&LPC_UART0->/*RBTHDLR.*/THR), // UART0 Tx
|
||||
(&LPC_UART0->/*RBTHDLR.*/RBR), // UART0 Rx
|
||||
(&LPC_UART1->/*RBTHDLR.*/THR), // UART1 Tx
|
||||
(&LPC_UART1->/*RBTHDLR.*/RBR), // UART1 Rx
|
||||
(&LPC_UART2->/*RBTHDLR.*/THR), // UART2 Tx
|
||||
(&LPC_UART2->/*RBTHDLR.*/RBR), // UART2 Rx
|
||||
(&LPC_UART3->/*RBTHDLR.*/THR), // UART3 Tx
|
||||
(&LPC_UART3->/*RBTHDLR.*/RBR), // UART3 Rx
|
||||
(&LPC_TIM0->MR0), // MAT0.0
|
||||
(&LPC_TIM0->MR1), // MAT0.1
|
||||
(&LPC_TIM1->MR0), // MAT1.0
|
||||
(&LPC_TIM1->MR1), // MAT1.1
|
||||
(&LPC_TIM2->MR0), // MAT2.0
|
||||
(&LPC_TIM2->MR1), // MAT2.1
|
||||
(&LPC_TIM3->MR0), // MAT3.0
|
||||
(&LPC_TIM3->MR1) // MAT3.1
|
||||
};
|
||||
//#else
|
||||
//const uint32_t GPDMA_LUTPerAddr[] = {
|
||||
// ((uint32_t)&LPC_SSP0->DR), // SSP0 Tx
|
||||
// ((uint32_t)&LPC_SSP0->DR), // SSP0 Rx
|
||||
// ((uint32_t)&LPC_SSP1->DR), // SSP1 Tx
|
||||
// ((uint32_t)&LPC_SSP1->DR), // SSP1 Rx
|
||||
// ((uint32_t)&LPC_ADC->ADGDR), // ADC
|
||||
// ((uint32_t)&LPC_I2S->I2STXFIFO), // I2S Tx
|
||||
// ((uint32_t)&LPC_I2S->I2SRXFIFO), // I2S Rx
|
||||
// ((uint32_t)&LPC_DAC->DACR), // DAC
|
||||
// ((uint32_t)&LPC_UART0->/*RBTHDLR.*/THR), // UART0 Tx
|
||||
// ((uint32_t)&LPC_UART0->/*RBTHDLR.*/RBR), // UART0 Rx
|
||||
// ((uint32_t)&LPC_UART1->/*RBTHDLR.*/THR), // UART1 Tx
|
||||
// ((uint32_t)&LPC_UART1->/*RBTHDLR.*/RBR), // UART1 Rx
|
||||
// ((uint32_t)&LPC_UART2->/*RBTHDLR.*/THR), // UART2 Tx
|
||||
// ((uint32_t)&LPC_UART2->/*RBTHDLR.*/RBR), // UART2 Rx
|
||||
// ((uint32_t)&LPC_UART3->/*RBTHDLR.*/THR), // UART3 Tx
|
||||
// ((uint32_t)&LPC_UART3->/*RBTHDLR.*/RBR), // UART3 Rx
|
||||
// ((uint32_t)&LPC_TIM0->MR0), // MAT0.0
|
||||
// ((uint32_t)&LPC_TIM0->MR1), // MAT0.1
|
||||
// ((uint32_t)&LPC_TIM1->MR0), // MAT1.0
|
||||
// ((uint32_t)&LPC_TIM1->MR1), // MAT1.1
|
||||
// ((uint32_t)&LPC_TIM2->MR0), // MAT2.0
|
||||
// ((uint32_t)&LPC_TIM2->MR1), // MAT2.1
|
||||
// ((uint32_t)&LPC_TIM3->MR0), // MAT3.0
|
||||
// ((uint32_t)&LPC_TIM3->MR1) // MAT3.1
|
||||
//};
|
||||
//#endif
|
||||
/**
|
||||
* @brief Lookup Table of GPDMA Channel Number matched with
|
||||
* GPDMA channel pointer
|
||||
*/
|
||||
const LPC_GPDMACH_TypeDef *pGPDMACh[8] = {
|
||||
LPC_GPDMACH0, // GPDMA Channel 0
|
||||
LPC_GPDMACH1, // GPDMA Channel 1
|
||||
LPC_GPDMACH2, // GPDMA Channel 2
|
||||
LPC_GPDMACH3, // GPDMA Channel 3
|
||||
LPC_GPDMACH4, // GPDMA Channel 4
|
||||
LPC_GPDMACH5, // GPDMA Channel 5
|
||||
LPC_GPDMACH6, // GPDMA Channel 6
|
||||
LPC_GPDMACH7 // GPDMA Channel 7
|
||||
};
|
||||
/**
|
||||
* @brief Optimized Peripheral Source and Destination burst size
|
||||
*/
|
||||
const uint8_t GPDMA_LUTPerBurst[] = {
|
||||
GPDMA_BSIZE_4, // SSP0 Tx
|
||||
GPDMA_BSIZE_4, // SSP0 Rx
|
||||
GPDMA_BSIZE_4, // SSP1 Tx
|
||||
GPDMA_BSIZE_4, // SSP1 Rx
|
||||
GPDMA_BSIZE_1, // ADC
|
||||
GPDMA_BSIZE_32, // I2S channel 0
|
||||
GPDMA_BSIZE_32, // I2S channel 1
|
||||
GPDMA_BSIZE_1, // DAC
|
||||
GPDMA_BSIZE_1, // UART0 Tx
|
||||
GPDMA_BSIZE_1, // UART0 Rx
|
||||
GPDMA_BSIZE_1, // UART1 Tx
|
||||
GPDMA_BSIZE_1, // UART1 Rx
|
||||
GPDMA_BSIZE_1, // UART2 Tx
|
||||
GPDMA_BSIZE_1, // UART2 Rx
|
||||
GPDMA_BSIZE_1, // UART3 Tx
|
||||
GPDMA_BSIZE_1, // UART3 Rx
|
||||
GPDMA_BSIZE_1, // MAT0.0
|
||||
GPDMA_BSIZE_1, // MAT0.1
|
||||
GPDMA_BSIZE_1, // MAT1.0
|
||||
GPDMA_BSIZE_1, // MAT1.1
|
||||
GPDMA_BSIZE_1, // MAT2.0
|
||||
GPDMA_BSIZE_1, // MAT2.1
|
||||
GPDMA_BSIZE_1, // MAT3.0
|
||||
GPDMA_BSIZE_1 // MAT3.1
|
||||
};
|
||||
/**
|
||||
* @brief Optimized Peripheral Source and Destination transfer width
|
||||
*/
|
||||
const uint8_t GPDMA_LUTPerWid[] = {
|
||||
GPDMA_WIDTH_BYTE, // SSP0 Tx
|
||||
GPDMA_WIDTH_BYTE, // SSP0 Rx
|
||||
GPDMA_WIDTH_BYTE, // SSP1 Tx
|
||||
GPDMA_WIDTH_BYTE, // SSP1 Rx
|
||||
GPDMA_WIDTH_WORD, // ADC
|
||||
GPDMA_WIDTH_WORD, // I2S channel 0
|
||||
GPDMA_WIDTH_WORD, // I2S channel 1
|
||||
GPDMA_WIDTH_BYTE, // DAC
|
||||
GPDMA_WIDTH_BYTE, // UART0 Tx
|
||||
GPDMA_WIDTH_BYTE, // UART0 Rx
|
||||
GPDMA_WIDTH_BYTE, // UART1 Tx
|
||||
GPDMA_WIDTH_BYTE, // UART1 Rx
|
||||
GPDMA_WIDTH_BYTE, // UART2 Tx
|
||||
GPDMA_WIDTH_BYTE, // UART2 Rx
|
||||
GPDMA_WIDTH_BYTE, // UART3 Tx
|
||||
GPDMA_WIDTH_BYTE, // UART3 Rx
|
||||
GPDMA_WIDTH_WORD, // MAT0.0
|
||||
GPDMA_WIDTH_WORD, // MAT0.1
|
||||
GPDMA_WIDTH_WORD, // MAT1.0
|
||||
GPDMA_WIDTH_WORD, // MAT1.1
|
||||
GPDMA_WIDTH_WORD, // MAT2.0
|
||||
GPDMA_WIDTH_WORD, // MAT2.1
|
||||
GPDMA_WIDTH_WORD, // MAT3.0
|
||||
GPDMA_WIDTH_WORD // MAT3.1
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup GPDMA_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Initialize GPDMA controller
|
||||
* @param None
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void GPDMA_Init(void)
|
||||
{
|
||||
/* Enable GPDMA clock */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCGPDMA, ENABLE);
|
||||
|
||||
// Reset all channel configuration register
|
||||
LPC_GPDMACH0->DMACCConfig = 0;
|
||||
LPC_GPDMACH1->DMACCConfig = 0;
|
||||
LPC_GPDMACH2->DMACCConfig = 0;
|
||||
LPC_GPDMACH3->DMACCConfig = 0;
|
||||
LPC_GPDMACH4->DMACCConfig = 0;
|
||||
LPC_GPDMACH5->DMACCConfig = 0;
|
||||
LPC_GPDMACH6->DMACCConfig = 0;
|
||||
LPC_GPDMACH7->DMACCConfig = 0;
|
||||
|
||||
/* Clear all DMA interrupt and error flag */
|
||||
LPC_GPDMA->DMACIntTCClear = 0xFF;
|
||||
LPC_GPDMA->DMACIntErrClr = 0xFF;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Setup GPDMA channel peripheral according to the specified
|
||||
* parameters in the GPDMAChannelConfig.
|
||||
* @param[in] GPDMAChannelConfig Pointer to a GPDMA_CH_CFG_Type
|
||||
* structure that contains the configuration
|
||||
* information for the specified GPDMA channel peripheral.
|
||||
* @return ERROR if selected channel is enabled before
|
||||
* or SUCCESS if channel is configured successfully
|
||||
*********************************************************************/
|
||||
Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig)
|
||||
{
|
||||
LPC_GPDMACH_TypeDef *pDMAch;
|
||||
uint32_t tmp1, tmp2;
|
||||
|
||||
if (LPC_GPDMA->DMACEnbldChns & (GPDMA_DMACEnbldChns_Ch(GPDMAChannelConfig->ChannelNum))) {
|
||||
// This channel is enabled, return ERROR, need to release this channel first
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
// Get Channel pointer
|
||||
pDMAch = (LPC_GPDMACH_TypeDef *) pGPDMACh[GPDMAChannelConfig->ChannelNum];
|
||||
|
||||
// Reset the Interrupt status
|
||||
LPC_GPDMA->DMACIntTCClear = GPDMA_DMACIntTCClear_Ch(GPDMAChannelConfig->ChannelNum);
|
||||
LPC_GPDMA->DMACIntErrClr = GPDMA_DMACIntErrClr_Ch(GPDMAChannelConfig->ChannelNum);
|
||||
|
||||
// Clear DMA configure
|
||||
pDMAch->DMACCControl = 0x00;
|
||||
pDMAch->DMACCConfig = 0x00;
|
||||
|
||||
/* Assign Linker List Item value */
|
||||
pDMAch->DMACCLLI = GPDMAChannelConfig->DMALLI;
|
||||
|
||||
/* Set value to Channel Control Registers */
|
||||
switch (GPDMAChannelConfig->TransferType)
|
||||
{
|
||||
// Memory to memory
|
||||
case GPDMA_TRANSFERTYPE_M2M:
|
||||
// Assign physical source and destination address
|
||||
pDMAch->DMACCSrcAddr = GPDMAChannelConfig->SrcMemAddr;
|
||||
pDMAch->DMACCDestAddr = GPDMAChannelConfig->DstMemAddr;
|
||||
pDMAch->DMACCControl
|
||||
= GPDMA_DMACCxControl_TransferSize(GPDMAChannelConfig->TransferSize) \
|
||||
| GPDMA_DMACCxControl_SBSize(GPDMA_BSIZE_32) \
|
||||
| GPDMA_DMACCxControl_DBSize(GPDMA_BSIZE_32) \
|
||||
| GPDMA_DMACCxControl_SWidth(GPDMAChannelConfig->TransferWidth) \
|
||||
| GPDMA_DMACCxControl_DWidth(GPDMAChannelConfig->TransferWidth) \
|
||||
| GPDMA_DMACCxControl_SI \
|
||||
| GPDMA_DMACCxControl_DI \
|
||||
| GPDMA_DMACCxControl_I;
|
||||
break;
|
||||
// Memory to peripheral
|
||||
case GPDMA_TRANSFERTYPE_M2P:
|
||||
// Assign physical source
|
||||
pDMAch->DMACCSrcAddr = GPDMAChannelConfig->SrcMemAddr;
|
||||
// Assign peripheral destination address
|
||||
pDMAch->DMACCDestAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->DstConn];
|
||||
pDMAch->DMACCControl
|
||||
= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
|
||||
| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_SI \
|
||||
| GPDMA_DMACCxControl_I;
|
||||
break;
|
||||
// Peripheral to memory
|
||||
case GPDMA_TRANSFERTYPE_P2M:
|
||||
// Assign peripheral source address
|
||||
pDMAch->DMACCSrcAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->SrcConn];
|
||||
// Assign memory destination address
|
||||
pDMAch->DMACCDestAddr = GPDMAChannelConfig->DstMemAddr;
|
||||
pDMAch->DMACCControl
|
||||
= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
|
||||
| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_DI \
|
||||
| GPDMA_DMACCxControl_I;
|
||||
break;
|
||||
// Peripheral to peripheral
|
||||
case GPDMA_TRANSFERTYPE_P2P:
|
||||
// Assign peripheral source address
|
||||
pDMAch->DMACCSrcAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->SrcConn];
|
||||
// Assign peripheral destination address
|
||||
pDMAch->DMACCDestAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->DstConn];
|
||||
pDMAch->DMACCControl
|
||||
= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
|
||||
| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
|
||||
| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
|
||||
| GPDMA_DMACCxControl_I;
|
||||
break;
|
||||
// Do not support any more transfer type, return ERROR
|
||||
default:
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Re-Configure DMA Request Select for source peripheral */
|
||||
if (GPDMAChannelConfig->SrcConn > 15)
|
||||
{
|
||||
LPC_SC->DMAREQSEL |= (1<<(GPDMAChannelConfig->SrcConn - 16));
|
||||
} else {
|
||||
LPC_SC->DMAREQSEL &= ~(1<<(GPDMAChannelConfig->SrcConn - 8));
|
||||
}
|
||||
|
||||
/* Re-Configure DMA Request Select for Destination peripheral */
|
||||
if (GPDMAChannelConfig->DstConn > 15)
|
||||
{
|
||||
LPC_SC->DMAREQSEL |= (1<<(GPDMAChannelConfig->DstConn - 16));
|
||||
} else {
|
||||
LPC_SC->DMAREQSEL &= ~(1<<(GPDMAChannelConfig->DstConn - 8));
|
||||
}
|
||||
|
||||
/* Enable DMA channels, little endian */
|
||||
LPC_GPDMA->DMACConfig = GPDMA_DMACConfig_E;
|
||||
while (!(LPC_GPDMA->DMACConfig & GPDMA_DMACConfig_E));
|
||||
|
||||
// Calculate absolute value for Connection number
|
||||
tmp1 = GPDMAChannelConfig->SrcConn;
|
||||
tmp1 = ((tmp1 > 15) ? (tmp1 - 8) : tmp1);
|
||||
tmp2 = GPDMAChannelConfig->DstConn;
|
||||
tmp2 = ((tmp2 > 15) ? (tmp2 - 8) : tmp2);
|
||||
|
||||
// Configure DMA Channel, enable Error Counter and Terminate counter
|
||||
pDMAch->DMACCConfig = GPDMA_DMACCxConfig_IE | GPDMA_DMACCxConfig_ITC /*| GPDMA_DMACCxConfig_E*/ \
|
||||
| GPDMA_DMACCxConfig_TransferType((uint32_t)GPDMAChannelConfig->TransferType) \
|
||||
| GPDMA_DMACCxConfig_SrcPeripheral(tmp1) \
|
||||
| GPDMA_DMACCxConfig_DestPeripheral(tmp2);
|
||||
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable DMA channel
|
||||
* @param[in] channelNum GPDMA channel, should be in range from 0 to 7
|
||||
* @param[in] NewState New State of this command, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void GPDMA_ChannelCmd(uint8_t channelNum, FunctionalState NewState)
|
||||
{
|
||||
LPC_GPDMACH_TypeDef *pDMAch;
|
||||
|
||||
// Get Channel pointer
|
||||
pDMAch = (LPC_GPDMACH_TypeDef *) pGPDMACh[channelNum];
|
||||
|
||||
if (NewState == ENABLE) {
|
||||
pDMAch->DMACCConfig |= GPDMA_DMACCxConfig_E;
|
||||
} else {
|
||||
pDMAch->DMACCConfig &= ~GPDMA_DMACCxConfig_E;
|
||||
}
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Check if corresponding channel does have an active interrupt
|
||||
* request or not
|
||||
* @param[in] type type of status, should be:
|
||||
* - GPDMA_STAT_INT: GPDMA Interrupt Status
|
||||
* - GPDMA_STAT_INTTC: GPDMA Interrupt Terminal Count Request Status
|
||||
* - GPDMA_STAT_INTERR: GPDMA Interrupt Error Status
|
||||
* - GPDMA_STAT_RAWINTTC: GPDMA Raw Interrupt Terminal Count Status
|
||||
* - GPDMA_STAT_RAWINTERR: GPDMA Raw Error Interrupt Status
|
||||
* - GPDMA_STAT_ENABLED_CH:GPDMA Enabled Channel Status
|
||||
* @param[in] channel GPDMA channel, should be in range from 0 to 7
|
||||
* @return IntStatus status of DMA channel interrupt after masking
|
||||
* Should be:
|
||||
* - SET: the corresponding channel has no active interrupt request
|
||||
* - RESET: the corresponding channel does have an active interrupt request
|
||||
**********************************************************************/
|
||||
IntStatus GPDMA_IntGetStatus(GPDMA_Status_Type type, uint8_t channel)
|
||||
{
|
||||
CHECK_PARAM(PARAM_GPDMA_STAT(type));
|
||||
CHECK_PARAM(PARAM_GPDMA_CHANNEL(channel));
|
||||
|
||||
switch (type)
|
||||
{
|
||||
case GPDMA_STAT_INT: //check status of DMA channel interrupts
|
||||
if (LPC_GPDMA->DMACIntStat & (GPDMA_DMACIntStat_Ch(channel)))
|
||||
return SET;
|
||||
return RESET;
|
||||
case GPDMA_STAT_INTTC: // check terminal count interrupt request status for DMA
|
||||
if (LPC_GPDMA->DMACIntTCStat & GPDMA_DMACIntTCStat_Ch(channel))
|
||||
return SET;
|
||||
return RESET;
|
||||
case GPDMA_STAT_INTERR: //check interrupt status for DMA channels
|
||||
if (LPC_GPDMA->DMACIntErrStat & GPDMA_DMACIntTCClear_Ch(channel))
|
||||
return SET;
|
||||
return RESET;
|
||||
case GPDMA_STAT_RAWINTTC: //check status of the terminal count interrupt for DMA channels
|
||||
if (LPC_GPDMA->DMACRawIntErrStat & GPDMA_DMACRawIntTCStat_Ch(channel))
|
||||
return SET;
|
||||
return RESET;
|
||||
case GPDMA_STAT_RAWINTERR: //check status of the error interrupt for DMA channels
|
||||
if (LPC_GPDMA->DMACRawIntTCStat & GPDMA_DMACRawIntErrStat_Ch(channel))
|
||||
return SET;
|
||||
return RESET;
|
||||
default: //check enable status for DMA channels
|
||||
if (LPC_GPDMA->DMACEnbldChns & GPDMA_DMACEnbldChns_Ch(channel))
|
||||
return SET;
|
||||
return RESET;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear one or more interrupt requests on DMA channels
|
||||
* @param[in] type type of interrupt request, should be:
|
||||
* - GPDMA_STATCLR_INTTC: GPDMA Interrupt Terminal Count Request Clear
|
||||
* - GPDMA_STATCLR_INTERR: GPDMA Interrupt Error Clear
|
||||
* @param[in] channel GPDMA channel, should be in range from 0 to 7
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void GPDMA_ClearIntPending(GPDMA_StateClear_Type type, uint8_t channel)
|
||||
{
|
||||
CHECK_PARAM(PARAM_GPDMA_STATCLR(type));
|
||||
CHECK_PARAM(PARAM_GPDMA_CHANNEL(channel));
|
||||
|
||||
if (type == GPDMA_STATCLR_INTTC) // clears the terminal count interrupt request on DMA channel
|
||||
LPC_GPDMA->DMACIntTCClear = GPDMA_DMACIntTCClear_Ch(channel);
|
||||
else // clear the error interrupt request
|
||||
LPC_GPDMA->DMACIntErrClr = GPDMA_DMACIntErrClr_Ch(channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _GPDMA */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,762 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_gpio.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_gpio.c
|
||||
* @brief Contains all functions support for GPIO firmware
|
||||
* library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup GPIO
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_gpio.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _GPIO
|
||||
|
||||
/* Private Functions ---------------------------------------------------------- */
|
||||
|
||||
static LPC_GPIO_TypeDef *GPIO_GetPointer(uint8_t portNum);
|
||||
static GPIO_HalfWord_TypeDef *FIO_HalfWordGetPointer(uint8_t portNum);
|
||||
static GPIO_Byte_TypeDef *FIO_ByteGetPointer(uint8_t portNum);
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get pointer to GPIO peripheral due to GPIO port
|
||||
* @param[in] portNum Port Number value, should be in range from 0 to 4.
|
||||
* @return Pointer to GPIO peripheral
|
||||
**********************************************************************/
|
||||
static LPC_GPIO_TypeDef *GPIO_GetPointer(uint8_t portNum)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pGPIO = NULL;
|
||||
|
||||
switch (portNum) {
|
||||
case 0:
|
||||
pGPIO = LPC_GPIO0;
|
||||
break;
|
||||
case 1:
|
||||
pGPIO = LPC_GPIO1;
|
||||
break;
|
||||
case 2:
|
||||
pGPIO = LPC_GPIO2;
|
||||
break;
|
||||
case 3:
|
||||
pGPIO = LPC_GPIO3;
|
||||
break;
|
||||
case 4:
|
||||
pGPIO = LPC_GPIO4;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return pGPIO;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get pointer to FIO peripheral in halfword accessible style
|
||||
* due to FIO port
|
||||
* @param[in] portNum Port Number value, should be in range from 0 to 4.
|
||||
* @return Pointer to FIO peripheral
|
||||
**********************************************************************/
|
||||
static GPIO_HalfWord_TypeDef *FIO_HalfWordGetPointer(uint8_t portNum)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = NULL;
|
||||
|
||||
switch (portNum) {
|
||||
case 0:
|
||||
pFIO = GPIO0_HalfWord;
|
||||
break;
|
||||
case 1:
|
||||
pFIO = GPIO1_HalfWord;
|
||||
break;
|
||||
case 2:
|
||||
pFIO = GPIO2_HalfWord;
|
||||
break;
|
||||
case 3:
|
||||
pFIO = GPIO3_HalfWord;
|
||||
break;
|
||||
case 4:
|
||||
pFIO = GPIO4_HalfWord;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return pFIO;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get pointer to FIO peripheral in byte accessible style
|
||||
* due to FIO port
|
||||
* @param[in] portNum Port Number value, should be in range from 0 to 4.
|
||||
* @return Pointer to FIO peripheral
|
||||
**********************************************************************/
|
||||
static GPIO_Byte_TypeDef *FIO_ByteGetPointer(uint8_t portNum)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = NULL;
|
||||
|
||||
switch (portNum) {
|
||||
case 0:
|
||||
pFIO = GPIO0_Byte;
|
||||
break;
|
||||
case 1:
|
||||
pFIO = GPIO1_Byte;
|
||||
break;
|
||||
case 2:
|
||||
pFIO = GPIO2_Byte;
|
||||
break;
|
||||
case 3:
|
||||
pFIO = GPIO3_Byte;
|
||||
break;
|
||||
case 4:
|
||||
pFIO = GPIO4_Byte;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return pFIO;
|
||||
}
|
||||
|
||||
/* End of Private Functions --------------------------------------------------- */
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup GPIO_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/* GPIO ------------------------------------------------------------------------------ */
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Direction for GPIO port.
|
||||
* @param[in] portNum Port Number value, should be in range from 0 to 4
|
||||
* @param[in] bitValue Value that contains all bits to set direction,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* example: value 0x5 to set direction for bit 0 and bit 1.
|
||||
* @param[in] dir Direction value, should be:
|
||||
* - 0: Input.
|
||||
* - 1: Output.
|
||||
* @return None
|
||||
*
|
||||
* Note: All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void GPIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
|
||||
|
||||
if (pGPIO != NULL) {
|
||||
// Enable Output
|
||||
if (dir) {
|
||||
pGPIO->FIODIR |= bitValue;
|
||||
}
|
||||
// Enable Input
|
||||
else {
|
||||
pGPIO->FIODIR &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Value for bits that have output direction on GPIO port.
|
||||
* @param[in] portNum Port number value, should be in range from 0 to 4
|
||||
* @param[in] bitValue Value that contains all bits on GPIO to set,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* example: value 0x5 to set bit 0 and bit 1.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void GPIO_SetValue(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
|
||||
|
||||
if (pGPIO != NULL) {
|
||||
pGPIO->FIOSET = bitValue;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear Value for bits that have output direction on GPIO port.
|
||||
* @param[in] portNum Port number value, should be in range from 0 to 4
|
||||
* @param[in] bitValue Value that contains all bits on GPIO to clear,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* example: value 0x5 to clear bit 0 and bit 1.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void GPIO_ClearValue(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
|
||||
|
||||
if (pGPIO != NULL) {
|
||||
pGPIO->FIOCLR = bitValue;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read Current state on port pin that have input direction of GPIO
|
||||
* @param[in] portNum Port number to read value, in range from 0 to 4
|
||||
* @return Current value of GPIO port.
|
||||
*
|
||||
* Note: Return value contain state of each port pin (bit) on that GPIO regardless
|
||||
* its direction is input or output.
|
||||
**********************************************************************/
|
||||
uint32_t GPIO_ReadValue(uint8_t portNum)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
|
||||
|
||||
if (pGPIO != NULL) {
|
||||
return pGPIO->FIOPIN;
|
||||
}
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable GPIO interrupt (just used for P0.0-P0.30, P2.0-P2.13)
|
||||
* @param[in] portNum Port number to read value, should be: 0 or 2
|
||||
* @param[in] bitValue Value that contains all bits on GPIO to enable,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* @param[in] edgeState state of edge, should be:
|
||||
* - 0: Rising edge
|
||||
* - 1: Falling edge
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void GPIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState)
|
||||
{
|
||||
if((portNum == 0)&&(edgeState == 0))
|
||||
LPC_GPIOINT->IO0IntEnR = bitValue;
|
||||
else if ((portNum == 2)&&(edgeState == 0))
|
||||
LPC_GPIOINT->IO2IntEnR = bitValue;
|
||||
else if ((portNum == 0)&&(edgeState == 1))
|
||||
LPC_GPIOINT->IO0IntEnF = bitValue;
|
||||
else if ((portNum == 2)&&(edgeState == 1))
|
||||
LPC_GPIOINT->IO2IntEnF = bitValue;
|
||||
else
|
||||
//Error
|
||||
while(1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get GPIO Interrupt Status (just used for P0.0-P0.30, P2.0-P2.13)
|
||||
* @param[in] portNum Port number to read value, should be: 0 or 2
|
||||
* @param[in] pinNum Pin number, should be: 0..30(with port 0) and 0..13
|
||||
* (with port 2)
|
||||
* @param[in] edgeState state of edge, should be:
|
||||
* - 0: Rising edge
|
||||
* - 1: Falling edge
|
||||
* @return Bool could be:
|
||||
* - ENABLE: Interrupt has been generated due to a rising
|
||||
* edge on P0.0
|
||||
* - DISABLE: A rising edge has not been detected on P0.0
|
||||
**********************************************************************/
|
||||
FunctionalState GPIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState)
|
||||
{
|
||||
if((portNum == 0) && (edgeState == 0))//Rising Edge
|
||||
return ((FunctionalState)(((LPC_GPIOINT->IO0IntStatR)>>pinNum)& 0x1));
|
||||
else if ((portNum == 2) && (edgeState == 0))
|
||||
return ((FunctionalState)(((LPC_GPIOINT->IO2IntStatR)>>pinNum)& 0x1));
|
||||
else if ((portNum == 0) && (edgeState == 1))//Falling Edge
|
||||
return ((FunctionalState)(((LPC_GPIOINT->IO0IntStatF)>>pinNum)& 0x1));
|
||||
else if ((portNum == 2) && (edgeState == 1))
|
||||
return ((FunctionalState)(((LPC_GPIOINT->IO2IntStatF)>>pinNum)& 0x1));
|
||||
else
|
||||
//Error
|
||||
while(1);
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Clear GPIO interrupt (just used for P0.0-P0.30, P2.0-P2.13)
|
||||
* @param[in] portNum Port number to read value, should be: 0 or 2
|
||||
* @param[in] bitValue Value that contains all bits on GPIO to enable,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void GPIO_ClearInt(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
if(portNum == 0)
|
||||
LPC_GPIOINT->IO0IntClr = bitValue;
|
||||
else if (portNum == 2)
|
||||
LPC_GPIOINT->IO2IntClr = bitValue;
|
||||
else
|
||||
//Invalid portNum
|
||||
while(1);
|
||||
}
|
||||
|
||||
/* FIO word accessible ----------------------------------------------------------------- */
|
||||
/* Stub function for FIO (word-accessible) style */
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_SetDir()
|
||||
*/
|
||||
void FIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir)
|
||||
{
|
||||
GPIO_SetDir(portNum, bitValue, dir);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_SetValue()
|
||||
*/
|
||||
void FIO_SetValue(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
GPIO_SetValue(portNum, bitValue);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_ClearValue()
|
||||
*/
|
||||
void FIO_ClearValue(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
GPIO_ClearValue(portNum, bitValue);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_ReadValue()
|
||||
*/
|
||||
uint32_t FIO_ReadValue(uint8_t portNum)
|
||||
{
|
||||
return (GPIO_ReadValue(portNum));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_IntCmd()
|
||||
*/
|
||||
void FIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState)
|
||||
{
|
||||
GPIO_IntCmd(portNum, bitValue, edgeState);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_GetIntStatus()
|
||||
*/
|
||||
FunctionalState FIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState)
|
||||
{
|
||||
return (GPIO_GetIntStatus(portNum, pinNum, edgeState));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief The same with GPIO_ClearInt()
|
||||
*/
|
||||
void FIO_ClearInt(uint8_t portNum, uint32_t bitValue)
|
||||
{
|
||||
GPIO_ClearInt(portNum, bitValue);
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Set mask value for bits in FIO port
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] bitValue Value that contains all bits in to set,
|
||||
* in range from 0 to 0xFFFFFFFF.
|
||||
* @param[in] maskValue Mask value contains state value for each bit:
|
||||
* - 0: not mask.
|
||||
* - 1: mask.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
* - After executing this function, in mask register, value '0' on each bit
|
||||
* enables an access to the corresponding physical pin via a read or write access,
|
||||
* while value '1' on bit (masked) that corresponding pin will not be changed
|
||||
* with write access and if read, will not be reflected in the updated pin.
|
||||
**********************************************************************/
|
||||
void FIO_SetMask(uint8_t portNum, uint32_t bitValue, uint8_t maskValue)
|
||||
{
|
||||
LPC_GPIO_TypeDef *pFIO = GPIO_GetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Mask
|
||||
if (maskValue){
|
||||
pFIO->FIOMASK |= bitValue;
|
||||
}
|
||||
// Un-mask
|
||||
else {
|
||||
pFIO->FIOMASK &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* FIO halfword accessible ------------------------------------------------------------- */
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set direction for FIO port in halfword accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] halfwordNum HalfWord part number, should be 0 (lower) or 1(upper)
|
||||
* @param[in] bitValue Value that contains all bits in to set direction,
|
||||
* in range from 0 to 0xFFFF.
|
||||
* @param[in] dir Direction value, should be:
|
||||
* - 0: Input.
|
||||
* - 1: Output.
|
||||
* @return None
|
||||
*
|
||||
* Note: All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_HalfWordSetDir(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t dir)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Output direction
|
||||
if (dir) {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIODIRU |= bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIODIRL |= bitValue;
|
||||
}
|
||||
}
|
||||
// Input direction
|
||||
else {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIODIRU &= ~bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIODIRL &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set mask value for bits in FIO port in halfword accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] halfwordNum HalfWord part number, should be 0 (lower) or 1(upper)
|
||||
* @param[in] bitValue Value that contains all bits in to set,
|
||||
* in range from 0 to 0xFFFF.
|
||||
* @param[in] maskValue Mask value contains state value for each bit:
|
||||
* - 0: not mask.
|
||||
* - 1: mask.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
* - After executing this function, in mask register, value '0' on each bit
|
||||
* enables an access to the corresponding physical pin via a read or write access,
|
||||
* while value '1' on bit (masked) that corresponding pin will not be changed
|
||||
* with write access and if read, will not be reflected in the updated pin.
|
||||
**********************************************************************/
|
||||
void FIO_HalfWordSetMask(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t maskValue)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Mask
|
||||
if (maskValue){
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIOMASKU |= bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIOMASKL |= bitValue;
|
||||
}
|
||||
}
|
||||
// Un-mask
|
||||
else {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIOMASKU &= ~bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIOMASKL &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set bits for FIO port in halfword accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] halfwordNum HalfWord part number, should be 0 (lower) or 1(upper)
|
||||
* @param[in] bitValue Value that contains all bits in to set,
|
||||
* in range from 0 to 0xFFFF.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_HalfWordSetValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIOSETU = bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIOSETL = bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear bits for FIO port in halfword accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] halfwordNum HalfWord part number, should be 0 (lower) or 1(upper)
|
||||
* @param[in] bitValue Value that contains all bits in to clear,
|
||||
* in range from 0 to 0xFFFF.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_HalfWordClearValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
pFIO->FIOCLRU = bitValue;
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
pFIO->FIOCLRL = bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read Current state on port pin that have input direction of GPIO
|
||||
* in halfword accessible style.
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] halfwordNum HalfWord part number, should be 0 (lower) or 1(upper)
|
||||
* @return Current value of FIO port pin of specified halfword.
|
||||
* Note: Return value contain state of each port pin (bit) on that FIO regardless
|
||||
* its direction is input or output.
|
||||
**********************************************************************/
|
||||
uint16_t FIO_HalfWordReadValue(uint8_t portNum, uint8_t halfwordNum)
|
||||
{
|
||||
GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Upper
|
||||
if(halfwordNum) {
|
||||
return (pFIO->FIOPINU);
|
||||
}
|
||||
// lower
|
||||
else {
|
||||
return (pFIO->FIOPINL);
|
||||
}
|
||||
}
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/* FIO Byte accessible ------------------------------------------------------------ */
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set direction for FIO port in byte accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] byteNum Byte part number, should be in range from 0 to 3
|
||||
* @param[in] bitValue Value that contains all bits in to set direction,
|
||||
* in range from 0 to 0xFF.
|
||||
* @param[in] dir Direction value, should be:
|
||||
* - 0: Input.
|
||||
* - 1: Output.
|
||||
* @return None
|
||||
*
|
||||
* Note: All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_ByteSetDir(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t dir)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Output direction
|
||||
if (dir) {
|
||||
if (byteNum <= 3) {
|
||||
pFIO->FIODIR[byteNum] |= bitValue;
|
||||
}
|
||||
}
|
||||
// Input direction
|
||||
else {
|
||||
if (byteNum <= 3) {
|
||||
pFIO->FIODIR[byteNum] &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set mask value for bits in FIO port in byte accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] byteNum Byte part number, should be in range from 0 to 3
|
||||
* @param[in] bitValue Value that contains all bits in to set mask,
|
||||
* in range from 0 to 0xFF.
|
||||
* @param[in] maskValue Mask value contains state value for each bit:
|
||||
* - 0: not mask.
|
||||
* - 1: mask.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - All remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
* - After executing this function, in mask register, value '0' on each bit
|
||||
* enables an access to the corresponding physical pin via a read or write access,
|
||||
* while value '1' on bit (masked) that corresponding pin will not be changed
|
||||
* with write access and if read, will not be reflected in the updated pin.
|
||||
**********************************************************************/
|
||||
void FIO_ByteSetMask(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t maskValue)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
|
||||
if(pFIO != NULL) {
|
||||
// Mask
|
||||
if (maskValue) {
|
||||
if (byteNum <= 3) {
|
||||
pFIO->FIOMASK[byteNum] |= bitValue;
|
||||
}
|
||||
}
|
||||
// Un-mask
|
||||
else {
|
||||
if (byteNum <= 3) {
|
||||
pFIO->FIOMASK[byteNum] &= ~bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set bits for FIO port in byte accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] byteNum Byte part number, should be in range from 0 to 3
|
||||
* @param[in] bitValue Value that contains all bits in to set,
|
||||
* in range from 0 to 0xFF.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_ByteSetValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
|
||||
if (pFIO != NULL) {
|
||||
if (byteNum <= 3){
|
||||
pFIO->FIOSET[byteNum] = bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear bits for FIO port in byte accessible style
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] byteNum Byte part number, should be in range from 0 to 3
|
||||
* @param[in] bitValue Value that contains all bits in to clear,
|
||||
* in range from 0 to 0xFF.
|
||||
* @return None
|
||||
*
|
||||
* Note:
|
||||
* - For all bits that has been set as input direction, this function will
|
||||
* not effect.
|
||||
* - For all remaining bits that are not activated in bitValue (value '0')
|
||||
* will not be effected by this function.
|
||||
**********************************************************************/
|
||||
void FIO_ByteClearValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
|
||||
if (pFIO != NULL) {
|
||||
if (byteNum <= 3){
|
||||
pFIO->FIOCLR[byteNum] = bitValue;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read Current state on port pin that have input direction of GPIO
|
||||
* in byte accessible style.
|
||||
* @param[in] portNum Port number, in range from 0 to 4
|
||||
* @param[in] byteNum Byte part number, should be in range from 0 to 3
|
||||
* @return Current value of FIO port pin of specified byte part.
|
||||
* Note: Return value contain state of each port pin (bit) on that FIO regardless
|
||||
* its direction is input or output.
|
||||
**********************************************************************/
|
||||
uint8_t FIO_ByteReadValue(uint8_t portNum, uint8_t byteNum)
|
||||
{
|
||||
GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
|
||||
if (pFIO != NULL) {
|
||||
if (byteNum <= 3){
|
||||
return (pFIO->FIOPIN[byteNum]);
|
||||
}
|
||||
}
|
||||
return (0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _GPIO */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
File diff suppressed because it is too large
Load diff
|
@ -1,663 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_i2s.c 2010-09-23
|
||||
*//**
|
||||
* @file lpc17xx_i2s.c
|
||||
* @brief Contains all functions support for I2S firmware
|
||||
* library on LPC17xx
|
||||
* @version 3.1
|
||||
* @date 23. Sep. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup I2S
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_i2s.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _I2S
|
||||
|
||||
/* Private Functions ---------------------------------------------------------- */
|
||||
|
||||
static uint8_t i2s_GetWordWidth(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
static uint8_t i2s_GetChannel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get I2S wordwidth value
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is the I2S mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return The wordwidth value, should be: 8,16 or 32
|
||||
*********************************************************************/
|
||||
static uint8_t i2s_GetWordWidth(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
|
||||
uint8_t value;
|
||||
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) {
|
||||
value = (I2Sx->I2SDAO) & 0x03; /* get wordwidth bit */
|
||||
} else {
|
||||
value = (I2Sx->I2SDAI) & 0x03; /* get wordwidth bit */
|
||||
}
|
||||
switch (value) {
|
||||
case I2S_WORDWIDTH_8:
|
||||
return 8;
|
||||
case I2S_WORDWIDTH_16:
|
||||
return 16;
|
||||
default:
|
||||
return 32;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get I2S channel value
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is the I2S mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return The channel value, should be: 1(mono) or 2(stereo)
|
||||
*********************************************************************/
|
||||
static uint8_t i2s_GetChannel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
|
||||
uint8_t value;
|
||||
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) {
|
||||
value = ((I2Sx->I2SDAO) & 0x04)>>2; /* get bit[2] */
|
||||
} else {
|
||||
value = ((I2Sx->I2SDAI) & 0x04)>>2; /* get bit[2] */
|
||||
}
|
||||
if(value == I2S_MONO) return 1;
|
||||
return 2;
|
||||
}
|
||||
|
||||
/* End of Private Functions --------------------------------------------------- */
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup I2S_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Initialize I2S
|
||||
* - Turn on power and clock
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Init(LPC_I2S_TypeDef *I2Sx) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
|
||||
// Turn on power and clock
|
||||
CLKPWR_ConfigPPWR(CLKPWR_PCONP_PCI2S, ENABLE);
|
||||
LPC_I2S->I2SDAI = LPC_I2S->I2SDAO = 0x00;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Configuration I2S, setting:
|
||||
* - master/slave mode
|
||||
* - wordwidth value
|
||||
* - channel mode
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @param[in] ConfigStruct pointer to I2S_CFG_Type structure
|
||||
* which will be initialized.
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Config(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, I2S_CFG_Type* ConfigStruct)
|
||||
{
|
||||
uint32_t bps, config;
|
||||
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
|
||||
CHECK_PARAM(PARAM_I2S_WORDWIDTH(ConfigStruct->wordwidth));
|
||||
CHECK_PARAM(PARAM_I2S_CHANNEL(ConfigStruct->mono));
|
||||
CHECK_PARAM(PARAM_I2S_STOP(ConfigStruct->stop));
|
||||
CHECK_PARAM(PARAM_I2S_RESET(ConfigStruct->reset));
|
||||
CHECK_PARAM(PARAM_I2S_WS_SEL(ConfigStruct->ws_sel));
|
||||
CHECK_PARAM(PARAM_I2S_MUTE(ConfigStruct->mute));
|
||||
|
||||
/* Setup clock */
|
||||
bps = (ConfigStruct->wordwidth +1)*8;
|
||||
|
||||
/* Calculate audio config */
|
||||
config = (bps - 1)<<6 | (ConfigStruct->ws_sel)<<5 | (ConfigStruct->reset)<<4 |
|
||||
(ConfigStruct->stop)<<3 | (ConfigStruct->mono)<<2 | (ConfigStruct->wordwidth);
|
||||
|
||||
if(TRMode == I2S_RX_MODE){
|
||||
LPC_I2S->I2SDAI = config;
|
||||
}else{
|
||||
LPC_I2S->I2SDAO = config;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief DeInitial both I2S transmit or receive
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_DeInit(LPC_I2S_TypeDef *I2Sx) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
|
||||
// Turn off power and clock
|
||||
CLKPWR_ConfigPPWR(CLKPWR_PCONP_PCI2S, DISABLE);
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get I2S Buffer Level
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode Transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return current level of Transmit/Receive Buffer
|
||||
*********************************************************************/
|
||||
uint8_t I2S_GetLevel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if(TRMode == I2S_TX_MODE)
|
||||
{
|
||||
return ((I2Sx->I2SSTATE >> 16) & 0xFF);
|
||||
}
|
||||
else
|
||||
{
|
||||
return ((I2Sx->I2SSTATE >> 8) & 0xFF);
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Start: clear all STOP,RESET and MUTE bit, ready to operate
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Start(LPC_I2S_TypeDef *I2Sx)
|
||||
{
|
||||
//Clear STOP,RESET and MUTE bit
|
||||
I2Sx->I2SDAO &= ~I2S_DAI_RESET;
|
||||
I2Sx->I2SDAI &= ~I2S_DAI_RESET;
|
||||
I2Sx->I2SDAO &= ~I2S_DAI_STOP;
|
||||
I2Sx->I2SDAI &= ~I2S_DAI_STOP;
|
||||
I2Sx->I2SDAO &= ~I2S_DAI_MUTE;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Send data
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] BufferData pointer to uint32_t is the data will be send
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Send(LPC_I2S_TypeDef *I2Sx, uint32_t BufferData) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
|
||||
I2Sx->I2STXFIFO = BufferData;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Receive Data
|
||||
* @param[in] I2Sx pointer to LPC_I2S_TypeDef
|
||||
* @return received value
|
||||
*********************************************************************/
|
||||
uint32_t I2S_Receive(LPC_I2S_TypeDef* I2Sx) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
|
||||
return (I2Sx->I2SRXFIFO);
|
||||
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Pause
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Pause(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) //Transmit mode
|
||||
{
|
||||
I2Sx->I2SDAO |= I2S_DAO_STOP;
|
||||
} else //Receive mode
|
||||
{
|
||||
I2Sx->I2SDAI |= I2S_DAI_STOP;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Mute
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Mute(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) //Transmit mode
|
||||
{
|
||||
I2Sx->I2SDAO |= I2S_DAO_MUTE;
|
||||
} else //Receive mode
|
||||
{
|
||||
I2Sx->I2SDAI |= I2S_DAI_MUTE;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S Stop
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_Stop(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) //Transmit mode
|
||||
{
|
||||
I2Sx->I2SDAO &= ~I2S_DAO_MUTE;
|
||||
I2Sx->I2SDAO |= I2S_DAO_STOP;
|
||||
I2Sx->I2SDAO |= I2S_DAO_RESET;
|
||||
} else //Receive mode
|
||||
{
|
||||
I2Sx->I2SDAI |= I2S_DAI_STOP;
|
||||
I2Sx->I2SDAI |= I2S_DAI_RESET;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Set frequency for I2S
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] Freq is the frequency for I2S will be set. It can range
|
||||
* from 16-96 kHz(16, 22.05, 32, 44.1, 48, 96kHz)
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return Status: ERROR or SUCCESS
|
||||
*********************************************************************/
|
||||
Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode) {
|
||||
|
||||
uint32_t i2s_clk;
|
||||
uint8_t channel, wordwidth;
|
||||
uint32_t x, y;
|
||||
uint64_t divider;
|
||||
uint16_t dif;
|
||||
uint16_t x_divide, y_divide;
|
||||
uint16_t err, ErrorOptimal = 0xFFFF;
|
||||
|
||||
uint32_t N;
|
||||
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PRAM_I2S_FREQ(Freq));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
//Get the frequency of PCLK_I2S
|
||||
i2s_clk = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_I2S);
|
||||
|
||||
if(TRMode == I2S_TX_MODE)
|
||||
{
|
||||
channel = i2s_GetChannel(I2Sx,I2S_TX_MODE);
|
||||
wordwidth = i2s_GetWordWidth(I2Sx,I2S_TX_MODE);
|
||||
}
|
||||
else
|
||||
{
|
||||
channel = i2s_GetChannel(I2Sx,I2S_RX_MODE);
|
||||
wordwidth = i2s_GetWordWidth(I2Sx,I2S_RX_MODE);
|
||||
}
|
||||
|
||||
/* Calculate X and Y divider
|
||||
* The MCLK rate for the I2S transmitter is determined by the value
|
||||
* in the I2STXRATE/I2SRXRATE register. The required I2STXRATE/I2SRXRATE
|
||||
* setting depends on the desired audio sample rate desired, the format
|
||||
* (stereo/mono) used, and the data size.
|
||||
* The formula is:
|
||||
* I2S_MCLK = PCLK_I2S * (X/Y) / 2
|
||||
* In that, Y must be greater than or equal to X. X should divides evenly
|
||||
* into Y.
|
||||
* We have:
|
||||
* I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1);
|
||||
* So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S
|
||||
* We use a loop function to chose the most suitable X,Y value
|
||||
*/
|
||||
|
||||
/* divider is a fixed point number with 16 fractional bits */
|
||||
divider = (((uint64_t)Freq *channel*wordwidth * 2)<<16) / i2s_clk;
|
||||
|
||||
/* find N that make x/y <= 1 -> divider <= 2^16 */
|
||||
for(N=64;N>0;N--){
|
||||
if((divider*N) < (1<<16)) break;
|
||||
}
|
||||
|
||||
if(N == 0) return ERROR;
|
||||
|
||||
divider *= N;
|
||||
|
||||
for (y = 255; y > 0; y--) {
|
||||
x = y * divider;
|
||||
if(x & (0xFF000000)) continue;
|
||||
dif = x & 0xFFFF;
|
||||
if(dif>0x8000) err = 0x10000-dif;
|
||||
else err = dif;
|
||||
if (err == 0)
|
||||
{
|
||||
y_divide = y;
|
||||
break;
|
||||
}
|
||||
else if (err < ErrorOptimal)
|
||||
{
|
||||
ErrorOptimal = err;
|
||||
y_divide = y;
|
||||
}
|
||||
}
|
||||
x_divide = ((uint64_t)y_divide * Freq *(channel*wordwidth)* N * 2)/i2s_clk;
|
||||
if(x_divide >= 256) x_divide = 0xFF;
|
||||
if(x_divide == 0) x_divide = 1;
|
||||
|
||||
if (TRMode == I2S_TX_MODE)// Transmitter
|
||||
{
|
||||
I2Sx->I2STXBITRATE = N-1;
|
||||
I2Sx->I2STXRATE = y_divide | (x_divide << 8);
|
||||
} else //Receiver
|
||||
{
|
||||
I2Sx->I2SRXBITRATE = N-1;
|
||||
I2Sx->I2STXRATE = y_divide | (x_divide << 8);
|
||||
}
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief I2S set bitrate
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] bitrate value will be set
|
||||
* bitrate value should be in range: 0 .. 63
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_SetBitRate(LPC_I2S_TypeDef *I2Sx, uint8_t bitrate, uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_BITRATE(bitrate));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if(TRMode == I2S_TX_MODE)
|
||||
{
|
||||
I2Sx->I2STXBITRATE = bitrate;
|
||||
}
|
||||
else
|
||||
{
|
||||
I2Sx->I2SRXBITRATE = bitrate;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Configuration operating mode for I2S
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] ModeConfig pointer to I2S_MODEConf_Type will be used to
|
||||
* configure
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_ModeConfig(LPC_I2S_TypeDef *I2Sx, I2S_MODEConf_Type* ModeConfig,
|
||||
uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_CLKSEL(ModeConfig->clksel));
|
||||
CHECK_PARAM(PARAM_I2S_4PIN(ModeConfig->fpin));
|
||||
CHECK_PARAM(PARAM_I2S_MCLK(ModeConfig->mcena));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_TX_MODE) {
|
||||
I2Sx->I2STXMODE &= ~0x0F; //clear bit 3:0 in I2STXMODE register
|
||||
if (ModeConfig->clksel == I2S_CLKSEL_MCLK) {
|
||||
I2Sx->I2STXMODE |= 0x02;
|
||||
}
|
||||
if (ModeConfig->fpin == I2S_4PIN_ENABLE) {
|
||||
I2Sx->I2STXMODE |= (1 << 2);
|
||||
}
|
||||
if (ModeConfig->mcena == I2S_MCLK_ENABLE) {
|
||||
I2Sx->I2STXMODE |= (1 << 3);
|
||||
}
|
||||
} else {
|
||||
I2Sx->I2SRXMODE &= ~0x0F; //clear bit 3:0 in I2STXMODE register
|
||||
if (ModeConfig->clksel == I2S_CLKSEL_MCLK) {
|
||||
I2Sx->I2SRXMODE |= 0x02;
|
||||
}
|
||||
if (ModeConfig->fpin == I2S_4PIN_ENABLE) {
|
||||
I2Sx->I2SRXMODE |= (1 << 2);
|
||||
}
|
||||
if (ModeConfig->mcena == I2S_MCLK_ENABLE) {
|
||||
I2Sx->I2SRXMODE |= (1 << 3);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Configure DMA operation for I2S
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] DMAConfig pointer to I2S_DMAConf_Type will be used to configure
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_DMAConfig(LPC_I2S_TypeDef *I2Sx, I2S_DMAConf_Type* DMAConfig,
|
||||
uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_DMA(DMAConfig->DMAIndex));
|
||||
CHECK_PARAM(PARAM_I2S_DMA_DEPTH(DMAConfig->depth));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_RX_MODE) {
|
||||
if (DMAConfig->DMAIndex == I2S_DMA_1) {
|
||||
LPC_I2S->I2SDMA1 = (DMAConfig->depth) << 8;
|
||||
} else {
|
||||
LPC_I2S->I2SDMA2 = (DMAConfig->depth) << 8;
|
||||
}
|
||||
} else {
|
||||
if (DMAConfig->DMAIndex == I2S_DMA_1) {
|
||||
LPC_I2S->I2SDMA1 = (DMAConfig->depth) << 16;
|
||||
} else {
|
||||
LPC_I2S->I2SDMA2 = (DMAConfig->depth) << 16;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Enable/Disable DMA operation for I2S
|
||||
* @param[in] I2Sx: I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] DMAIndex chose what DMA is used, should be:
|
||||
* - I2S_DMA_1 = 0: DMA1
|
||||
* - I2S_DMA_2 = 1: DMA2
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @param[in] NewState is new state of DMA operation, should be:
|
||||
* - ENABLE
|
||||
* - DISABLE
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_DMACmd(LPC_I2S_TypeDef *I2Sx, uint8_t DMAIndex, uint8_t TRMode,
|
||||
FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
CHECK_PARAM(PARAM_I2S_DMA(DMAIndex));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
|
||||
if (TRMode == I2S_RX_MODE) {
|
||||
if (DMAIndex == I2S_DMA_1) {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SDMA1 |= 0x01;
|
||||
else
|
||||
I2Sx->I2SDMA1 &= ~0x01;
|
||||
} else {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SDMA2 |= 0x01;
|
||||
else
|
||||
I2Sx->I2SDMA2 &= ~0x01;
|
||||
}
|
||||
} else {
|
||||
if (DMAIndex == I2S_DMA_1) {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SDMA1 |= 0x02;
|
||||
else
|
||||
I2Sx->I2SDMA1 &= ~0x02;
|
||||
} else {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SDMA2 |= 0x02;
|
||||
else
|
||||
I2Sx->I2SDMA2 &= ~0x02;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Configure IRQ for I2S
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @param[in] level is the FIFO level that triggers IRQ request
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_IRQConfig(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, uint8_t level) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_I2S_TRX(TRMode));
|
||||
CHECK_PARAM(PARAM_I2S_IRQ_LEVEL(level));
|
||||
|
||||
if (TRMode == I2S_RX_MODE) {
|
||||
I2Sx->I2SIRQ |= (level << 8);
|
||||
} else {
|
||||
I2Sx->I2SIRQ |= (level << 16);
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Enable/Disable IRQ for I2S
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @param[in] NewState is new state of DMA operation, should be:
|
||||
* - ENABLE
|
||||
* - DISABLE
|
||||
* @return none
|
||||
*********************************************************************/
|
||||
void I2S_IRQCmd(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, FunctionalState NewState) {
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (TRMode == I2S_RX_MODE) {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SIRQ |= 0x01;
|
||||
else
|
||||
I2Sx->I2SIRQ &= ~0x01;
|
||||
//Enable DMA
|
||||
|
||||
} else {
|
||||
if (NewState == ENABLE)
|
||||
I2Sx->I2SIRQ |= 0x02;
|
||||
else
|
||||
I2Sx->I2SIRQ &= ~0x02;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get I2S interrupt status
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return FunctionState should be:
|
||||
* - ENABLE: interrupt is enable
|
||||
* - DISABLE: interrupt is disable
|
||||
*********************************************************************/
|
||||
FunctionalState I2S_GetIRQStatus(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
if(TRMode == I2S_TX_MODE)
|
||||
return ((FunctionalState)((I2Sx->I2SIRQ >> 1)&0x01));
|
||||
else
|
||||
return ((FunctionalState)((I2Sx->I2SIRQ)&0x01));
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get I2S interrupt depth
|
||||
* @param[in] I2Sx I2S peripheral selected, should be: LPC_I2S
|
||||
* @param[in] TRMode is transmit/receive mode, should be:
|
||||
* - I2S_TX_MODE = 0: transmit mode
|
||||
* - I2S_RX_MODE = 1: receive mode
|
||||
* @return depth of FIFO level on which to create an irq request
|
||||
*********************************************************************/
|
||||
uint8_t I2S_GetIRQDepth(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_I2Sx(I2Sx));
|
||||
if(TRMode == I2S_TX_MODE)
|
||||
return (((I2Sx->I2SIRQ)>>16)&0xFF);
|
||||
else
|
||||
return (((I2Sx->I2SIRQ)>>8)&0xFF);
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _I2S */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,308 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_iap.c 2012-04-18
|
||||
*//**
|
||||
* @file lpc17xx_iap.c
|
||||
* @brief Contains all functions support for IAP on lpc17xx
|
||||
* @version 1.0
|
||||
* @date 18. April. 2012
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
#include "lpc17xx_iap.h"
|
||||
#include "system_LPC17xx.h"
|
||||
|
||||
// IAP Command
|
||||
typedef void (*IAP)(uint32_t *cmd,uint32_t *result);
|
||||
IAP iap_entry = (IAP) IAP_LOCATION;
|
||||
#define IAP_Call iap_entry
|
||||
|
||||
/** @addtogroup IAP_Public_Functions IAP Public Function
|
||||
* @ingroup IAP
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get Sector Number
|
||||
*
|
||||
* @param[in] adr Sector Address
|
||||
*
|
||||
* @return Sector Number.
|
||||
*
|
||||
**********************************************************************/
|
||||
uint32_t GetSecNum (uint32_t adr)
|
||||
{
|
||||
uint32_t n;
|
||||
|
||||
n = adr >> 12; // 4kB Sector
|
||||
if (n >= 0x10) {
|
||||
n = 0x0E + (n >> 3); // 32kB Sector
|
||||
}
|
||||
|
||||
return (n); // Sector Number
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Prepare sector(s) for write operation
|
||||
*
|
||||
* @param[in] start_sec The number of start sector
|
||||
* @param[in] end_sec The number of end sector
|
||||
*
|
||||
* @return CMD_SUCCESS/BUSY/INVALID_SECTOR.
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE PrepareSector(uint32_t start_sec, uint32_t end_sec)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_PREPARE; // Prepare Sector for Write
|
||||
command.param[0] = start_sec; // Start Sector
|
||||
command.param[1] = end_sec; // End Sector
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Copy RAM to Flash
|
||||
*
|
||||
* @param[in] dest destination buffer (in Flash memory).
|
||||
* @param[in] source source buffer (in RAM).
|
||||
* @param[in] size the write size.
|
||||
*
|
||||
* @return CMD_SUCCESS.
|
||||
* SRC_ADDR_ERROR/DST_ADDR_ERROR
|
||||
* SRC_ADDR_NOT_MAPPED/DST_ADDR_NOT_MAPPED
|
||||
* COUNT_ERROR/SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION
|
||||
* BUSY
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE CopyRAM2Flash(uint8_t * dest, uint8_t* source, IAP_WRITE_SIZE size)
|
||||
{
|
||||
uint32_t sec;
|
||||
IAP_STATUS_CODE status;
|
||||
IAP_COMMAND_Type command;
|
||||
|
||||
// Prepare sectors
|
||||
sec = GetSecNum((uint32_t)dest);
|
||||
status = PrepareSector(sec, sec);
|
||||
if(status != CMD_SUCCESS)
|
||||
return status;
|
||||
|
||||
// write
|
||||
command.cmd = IAP_COPY_RAM2FLASH; // Copy RAM to Flash
|
||||
command.param[0] = (uint32_t)dest; // Destination Flash Address
|
||||
command.param[1] = (uint32_t)source; // Source RAM Address
|
||||
command.param[2] = size; // Number of bytes
|
||||
command.param[3] = SystemCoreClock / 1000; // CCLK in kHz
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
return (IAP_STATUS_CODE)command.status; // Finished without Errors
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Erase sector(s)
|
||||
*
|
||||
* @param[in] start_sec The number of start sector
|
||||
* @param[in] end_sec The number of end sector
|
||||
*
|
||||
* @return CMD_SUCCESS.
|
||||
* INVALID_SECTOR
|
||||
* SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION
|
||||
* BUSY
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
IAP_STATUS_CODE status;
|
||||
|
||||
// Prepare sectors
|
||||
status = PrepareSector(start_sec, end_sec);
|
||||
if(status != CMD_SUCCESS)
|
||||
return status;
|
||||
|
||||
// Erase sectors
|
||||
command.cmd = IAP_ERASE; // Prepare Sector for Write
|
||||
command.param[0] = start_sec; // Start Sector
|
||||
command.param[1] = end_sec; // End Sector
|
||||
command.param[2] = SystemCoreClock / 1000; // CCLK in kHz
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Blank check sector(s)
|
||||
*
|
||||
* @param[in] start_sec The number of start sector
|
||||
* @param[in] end_sec The number of end sector
|
||||
* @param[out] first_nblank_loc The offset of the first non-blank word
|
||||
* @param[out] first_nblank_val The value of the first non-blank word
|
||||
*
|
||||
* @return CMD_SUCCESS.
|
||||
* INVALID_SECTOR
|
||||
* SECTOR_NOT_BLANK
|
||||
* BUSY
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
|
||||
uint32_t *first_nblank_loc,
|
||||
uint32_t *first_nblank_val)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
|
||||
command.cmd = IAP_BLANK_CHECK; // Prepare Sector for Write
|
||||
command.param[0] = start_sec; // Start Sector
|
||||
command.param[1] = end_sec; // End Sector
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
if(command.status == SECTOR_NOT_BLANK)
|
||||
{
|
||||
// Update out value
|
||||
if(first_nblank_loc != NULL)
|
||||
*first_nblank_loc = command.result[0];
|
||||
if(first_nblank_val != NULL)
|
||||
*first_nblank_val = command.result[1];
|
||||
}
|
||||
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read part identification number
|
||||
*
|
||||
* @param[out] partID Part ID
|
||||
*
|
||||
* @return CMD_SUCCESS
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE ReadPartID(uint32_t *partID)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_READ_PART_ID;
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
if(command.status == CMD_SUCCESS)
|
||||
{
|
||||
if(partID != NULL)
|
||||
*partID = command.result[0];
|
||||
}
|
||||
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read boot code version. The version is interpreted as <major>.<minor>.
|
||||
*
|
||||
* @param[out] major The major
|
||||
* @param[out] minor The minor
|
||||
*
|
||||
* @return CMD_SUCCESS
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE ReadBootCodeVer(uint8_t *major, uint8_t* minor)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_READ_BOOT_VER;
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
if(command.status == CMD_SUCCESS)
|
||||
{
|
||||
if(major != NULL)
|
||||
*major = (command.result[0] >> 8) & 0xFF;
|
||||
if(minor != NULL)
|
||||
*minor = (command.result[0]) & 0xFF;
|
||||
}
|
||||
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read Device serial number.
|
||||
*
|
||||
* @param[out] uid Serial number.
|
||||
*
|
||||
* @return CMD_SUCCESS
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE ReadDeviceSerialNum(uint32_t *uid)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_READ_SERIAL_NUMBER;
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
if(command.status == CMD_SUCCESS)
|
||||
{
|
||||
if(uid != NULL)
|
||||
{
|
||||
uint32_t i = 0;
|
||||
for(i = 0; i < 4; i++)
|
||||
uid[i] = command.result[i];
|
||||
}
|
||||
}
|
||||
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief compare the memory contents at two locations.
|
||||
*
|
||||
* @param[in] addr1 The address of the 1st buffer (in RAM/Flash).
|
||||
* @param[in] addr2 The address of the 2nd buffer (in RAM/Flash).
|
||||
* @param[in] size Number of bytes to be compared; should be a multiple of 4.
|
||||
*
|
||||
* @return CMD_SUCCESS
|
||||
* COMPARE_ERROR
|
||||
* COUNT_ERROR (Byte count is not a multiple of 4)
|
||||
* ADDR_ERROR
|
||||
* ADDR_NOT_MAPPED
|
||||
*
|
||||
**********************************************************************/
|
||||
IAP_STATUS_CODE Compare(uint8_t *addr1, uint8_t *addr2, uint32_t size)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_COMPARE;
|
||||
command.param[0] = (uint32_t)addr1;
|
||||
command.param[1] = (uint32_t)addr2;
|
||||
command.param[2] = size;
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
|
||||
return (IAP_STATUS_CODE)command.status;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Re-invoke ISP.
|
||||
*
|
||||
* @param[in] None.
|
||||
*
|
||||
* @return None.
|
||||
*
|
||||
**********************************************************************/
|
||||
void InvokeISP(void)
|
||||
{
|
||||
IAP_COMMAND_Type command;
|
||||
command.cmd = IAP_REINVOKE_ISP;
|
||||
IAP_Call (&command.cmd, &command.status); // Call IAP Command
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
|
@ -1,76 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_libcfg_default.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_libcfg_default.c
|
||||
* @brief Library configuration source file (default), used to build
|
||||
* library without examples
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Library group ----------------------------------------------------------- */
|
||||
/** @addtogroup LIBCFG_DEFAULT
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup LIBCFG_DEFAULT_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef __BUILD_WITH_EXAMPLE__
|
||||
|
||||
#ifdef DEBUG
|
||||
/*******************************************************************************
|
||||
* @brief Reports the name of the source file and the source line number
|
||||
* where the CHECK_PARAM error has occurred.
|
||||
* @param[in] file Pointer to the source file name
|
||||
* @param[in] line assert_param error line source number
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void check_failed(uint8_t *file, uint32_t line)
|
||||
{
|
||||
/* User can add his own implementation to report the file name and line number,
|
||||
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
|
||||
|
||||
/* Infinite loop */
|
||||
while(1);
|
||||
}
|
||||
#endif /* DEBUG */
|
||||
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,509 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_mcpwm.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_mcpwm.c
|
||||
* @brief Contains all functions support for Motor Control PWM firmware
|
||||
* library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup MCPWM
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_mcpwm.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _MCPWM
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup MCPWM_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes the MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected,
|
||||
* Should be: LPC_MCPWM
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_Init(LPC_MCPWM_TypeDef *MCPWMx)
|
||||
{
|
||||
|
||||
/* Turn On MCPWM PCLK */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCMC, ENABLE);
|
||||
/* As default, peripheral clock for MCPWM module
|
||||
* is set to FCCLK / 2 */
|
||||
// CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_MC, CLKPWR_PCLKSEL_CCLK_DIV_2);
|
||||
|
||||
MCPWMx->MCCAP_CLR = MCPWM_CAPCLR_CAP(0) | MCPWM_CAPCLR_CAP(1) | MCPWM_CAPCLR_CAP(2);
|
||||
MCPWMx->MCINTFLAG_CLR = MCPWM_INT_ILIM(0) | MCPWM_INT_ILIM(1) | MCPWM_INT_ILIM(2) \
|
||||
| MCPWM_INT_IMAT(0) | MCPWM_INT_IMAT(1) | MCPWM_INT_IMAT(2) \
|
||||
| MCPWM_INT_ICAP(0) | MCPWM_INT_ICAP(1) | MCPWM_INT_ICAP(2);
|
||||
MCPWMx->MCINTEN_CLR = MCPWM_INT_ILIM(0) | MCPWM_INT_ILIM(1) | MCPWM_INT_ILIM(2) \
|
||||
| MCPWM_INT_IMAT(0) | MCPWM_INT_IMAT(1) | MCPWM_INT_IMAT(2) \
|
||||
| MCPWM_INT_ICAP(0) | MCPWM_INT_ICAP(1) | MCPWM_INT_ICAP(2);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures each channel in MCPWM peripheral according to the
|
||||
* specified parameters in the MCPWM_CHANNEL_CFG_Type.
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* should be: LPC_MCPWM
|
||||
* @param[in] channelNum Channel number, should be: 0..2.
|
||||
* @param[in] channelSetup Pointer to a MCPWM_CHANNEL_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified MCPWM channel.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_ConfigChannel(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CHANNEL_CFG_Type * channelSetup)
|
||||
{
|
||||
if (channelNum <= 2) {
|
||||
if (channelNum == 0) {
|
||||
MCPWMx->MCTIM0 = channelSetup->channelTimercounterValue;
|
||||
MCPWMx->MCPER0 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW0 = channelSetup->channelPulsewidthValue;
|
||||
} else if (channelNum == 1) {
|
||||
MCPWMx->MCTIM1 = channelSetup->channelTimercounterValue;
|
||||
MCPWMx->MCPER1 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW1 = channelSetup->channelPulsewidthValue;
|
||||
} else if (channelNum == 2) {
|
||||
MCPWMx->MCTIM2 = channelSetup->channelTimercounterValue;
|
||||
MCPWMx->MCPER2 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW2 = channelSetup->channelPulsewidthValue;
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
if (channelSetup->channelType /* == MCPWM_CHANNEL_CENTER_MODE */){
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_CENTER(channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_CENTER(channelNum);
|
||||
}
|
||||
|
||||
if (channelSetup->channelPolarity /* == MCPWM_CHANNEL_PASSIVE_HI */){
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_POLAR(channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_POLAR(channelNum);
|
||||
}
|
||||
|
||||
if (channelSetup->channelDeadtimeEnable /* == ENABLE */){
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_DTE(channelNum);
|
||||
MCPWMx->MCDEADTIME &= ~(MCPWM_DT(channelNum, 0x3FF));
|
||||
MCPWMx->MCDEADTIME |= MCPWM_DT(channelNum, channelSetup->channelDeadtimeValue);
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_DTE(channelNum);
|
||||
}
|
||||
|
||||
if (channelSetup->channelUpdateEnable /* == ENABLE */){
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_DISUP(channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_DISUP(channelNum);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Write to MCPWM shadow registers - Update the value for period
|
||||
* and pulse width in MCPWM peripheral.
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] channelNum Channel Number, should be: 0..2.
|
||||
* @param[in] channelSetup Pointer to a MCPWM_CHANNEL_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified MCPWM channel.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_WriteToShadow(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CHANNEL_CFG_Type *channelSetup)
|
||||
{
|
||||
if (channelNum == 0){
|
||||
MCPWMx->MCPER0 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW0 = channelSetup->channelPulsewidthValue;
|
||||
} else if (channelNum == 1) {
|
||||
MCPWMx->MCPER1 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW1 = channelSetup->channelPulsewidthValue;
|
||||
} else if (channelNum == 2) {
|
||||
MCPWMx->MCPER2 = channelSetup->channelPeriodValue;
|
||||
MCPWMx->MCPW2 = channelSetup->channelPulsewidthValue;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures capture function in MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] channelNum MCI (Motor Control Input pin) number
|
||||
* Should be: 0..2
|
||||
* @param[in] captureConfig Pointer to a MCPWM_CAPTURE_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified MCPWM capture.
|
||||
* @return
|
||||
**********************************************************************/
|
||||
void MCPWM_ConfigCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CAPTURE_CFG_Type *captureConfig)
|
||||
{
|
||||
if (channelNum <= 2) {
|
||||
|
||||
if (captureConfig->captureFalling /* == ENABLE */) {
|
||||
MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_CAPMCI_FE(captureConfig->captureChannel, channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_CAPMCI_FE(captureConfig->captureChannel, channelNum);
|
||||
}
|
||||
|
||||
if (captureConfig->captureRising /* == ENABLE */) {
|
||||
MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_CAPMCI_RE(captureConfig->captureChannel, channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_CAPMCI_RE(captureConfig->captureChannel, channelNum);
|
||||
}
|
||||
|
||||
if (captureConfig->timerReset /* == ENABLE */){
|
||||
MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_RT(captureConfig->captureChannel);
|
||||
} else {
|
||||
MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_RT(captureConfig->captureChannel);
|
||||
}
|
||||
|
||||
if (captureConfig->hnfEnable /* == ENABLE */){
|
||||
MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_HNFCAP(channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_HNFCAP(channelNum);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clears current captured value in specified capture channel
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] captureChannel Capture channel number, should be: 0..2
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_ClearCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel)
|
||||
{
|
||||
MCPWMx->MCCAP_CLR = MCPWM_CAPCLR_CAP(captureChannel);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current captured value in specified capture channel
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected,
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] captureChannel Capture channel number, should be: 0..2
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
uint32_t MCPWM_GetCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel)
|
||||
{
|
||||
if (captureChannel == 0){
|
||||
return (MCPWMx->MCCR0);
|
||||
} else if (captureChannel == 1) {
|
||||
return (MCPWMx->MCCR1);
|
||||
} else if (captureChannel == 2) {
|
||||
return (MCPWMx->MCCR2);
|
||||
}
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures Count control in MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] channelNum Channel number, should be: 0..2
|
||||
* @param[in] countMode Count mode, should be:
|
||||
* - ENABLE: Enables count mode.
|
||||
* - DISABLE: Disable count mode, the channel is in timer mode.
|
||||
* @param[in] countConfig Pointer to a MCPWM_COUNT_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified MCPWM count control.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_CountConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
uint32_t countMode, MCPWM_COUNT_CFG_Type *countConfig)
|
||||
{
|
||||
if (channelNum <= 2) {
|
||||
if (countMode /* == ENABLE */){
|
||||
MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_CNTR(channelNum);
|
||||
if (countConfig->countFalling /* == ENABLE */) {
|
||||
MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_TCMCI_FE(countConfig->counterChannel,channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_TCMCI_FE(countConfig->counterChannel,channelNum);
|
||||
}
|
||||
if (countConfig->countRising /* == ENABLE */) {
|
||||
MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_TCMCI_RE(countConfig->counterChannel,channelNum);
|
||||
} else {
|
||||
MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_TCMCI_RE(countConfig->counterChannel,channelNum);
|
||||
}
|
||||
} else {
|
||||
MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_CNTR(channelNum);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Start MCPWM activity for each MCPWM channel
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] channel0 State of this command on channel 0:
|
||||
* - ENABLE: 'Start' command will effect on channel 0
|
||||
* - DISABLE: 'Start' command will not effect on channel 0
|
||||
* @param[in] channel1 State of this command on channel 1:
|
||||
* - ENABLE: 'Start' command will effect on channel 1
|
||||
* - DISABLE: 'Start' command will not effect on channel 1
|
||||
* @param[in] channel2 State of this command on channel 2:
|
||||
* - ENABLE: 'Start' command will effect on channel 2
|
||||
* - DISABLE: 'Start' command will not effect on channel 2
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_Start(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channel0,
|
||||
uint32_t channel1, uint32_t channel2)
|
||||
{
|
||||
uint32_t regVal = 0;
|
||||
regVal = (channel0 ? MCPWM_CON_RUN(0) : 0) | (channel1 ? MCPWM_CON_RUN(1) : 0) \
|
||||
| (channel2 ? MCPWM_CON_RUN(2) : 0);
|
||||
MCPWMx->MCCON_SET = regVal;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Stop MCPWM activity for each MCPWM channel
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] channel0 State of this command on channel 0:
|
||||
* - ENABLE: 'Stop' command will effect on channel 0
|
||||
* - DISABLE: 'Stop' command will not effect on channel 0
|
||||
* @param[in] channel1 State of this command on channel 1:
|
||||
* - ENABLE: 'Stop' command will effect on channel 1
|
||||
* - DISABLE: 'Stop' command will not effect on channel 1
|
||||
* @param[in] channel2 State of this command on channel 2:
|
||||
* - ENABLE: 'Stop' command will effect on channel 2
|
||||
* - DISABLE: 'Stop' command will not effect on channel 2
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_Stop(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channel0,
|
||||
uint32_t channel1, uint32_t channel2)
|
||||
{
|
||||
uint32_t regVal = 0;
|
||||
regVal = (channel0 ? MCPWM_CON_RUN(0) : 0) | (channel1 ? MCPWM_CON_RUN(1) : 0) \
|
||||
| (channel2 ? MCPWM_CON_RUN(2) : 0);
|
||||
MCPWMx->MCCON_CLR = regVal;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enables/Disables 3-phase AC motor mode on MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] acMode State of this command, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void MCPWM_ACMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t acMode)
|
||||
{
|
||||
if (acMode){
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_ACMODE;
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_ACMODE;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enables/Disables 3-phase DC motor mode on MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] dcMode State of this command, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @param[in] outputInvered Polarity of the MCOB outputs for all 3 channels,
|
||||
* should be:
|
||||
* - ENABLE: The MCOB outputs have opposite polarity
|
||||
* from the MCOA outputs.
|
||||
* - DISABLE: The MCOB outputs have the same basic
|
||||
* polarity as the MCOA outputs.
|
||||
* @param[in] outputPattern A value contains bits that enables/disables the specified
|
||||
* output pins route to the internal MCOA0 signal, should be:
|
||||
- MCPWM_PATENT_A0: MCOA0 tracks internal MCOA0
|
||||
- MCPWM_PATENT_B0: MCOB0 tracks internal MCOA0
|
||||
- MCPWM_PATENT_A1: MCOA1 tracks internal MCOA0
|
||||
- MCPWM_PATENT_B1: MCOB1 tracks internal MCOA0
|
||||
- MCPWM_PATENT_A2: MCOA2 tracks internal MCOA0
|
||||
- MCPWM_PATENT_B2: MCOB2 tracks internal MCOA0
|
||||
* @return None
|
||||
*
|
||||
* Note: all these outputPatent values above can be ORed together for using as input parameter.
|
||||
**********************************************************************/
|
||||
void MCPWM_DCMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t dcMode,
|
||||
uint32_t outputInvered, uint32_t outputPattern)
|
||||
{
|
||||
if (dcMode){
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_DCMODE;
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_DCMODE;
|
||||
}
|
||||
|
||||
if (outputInvered) {
|
||||
MCPWMx->MCCON_SET = MCPWM_CON_INVBDC;
|
||||
} else {
|
||||
MCPWMx->MCCON_CLR = MCPWM_CON_INVBDC;
|
||||
}
|
||||
|
||||
MCPWMx->MCCCP = outputPattern;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures the specified interrupt in MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be: LPC_MCPWM
|
||||
* @param[in] ulIntType Interrupt type, should be:
|
||||
* - MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_ABORT: Fast abort interrupt
|
||||
* @param[in] NewState New State of this command, should be:
|
||||
* - ENABLE.
|
||||
* - DISABLE.
|
||||
* @return None
|
||||
*
|
||||
* Note: all these ulIntType values above can be ORed together for using as input parameter.
|
||||
**********************************************************************/
|
||||
void MCPWM_IntConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType, FunctionalState NewState)
|
||||
{
|
||||
if (NewState) {
|
||||
MCPWMx->MCINTEN_SET = ulIntType;
|
||||
} else {
|
||||
MCPWMx->MCINTEN_CLR = ulIntType;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Sets/Forces the specified interrupt for MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected
|
||||
* Should be LPC_MCPWM
|
||||
* @param[in] ulIntType Interrupt type, should be:
|
||||
* - MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_ABORT: Fast abort interrupt
|
||||
* @return None
|
||||
* Note: all these ulIntType values above can be ORed together for using as input parameter.
|
||||
**********************************************************************/
|
||||
void MCPWM_IntSet(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
|
||||
{
|
||||
MCPWMx->MCINTFLAG_SET = ulIntType;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear the specified interrupt pending for MCPWM peripheral
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected,
|
||||
* should be: LPC_MCPWM
|
||||
* @param[in] ulIntType Interrupt type, should be:
|
||||
* - MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_ABORT: Fast abort interrupt
|
||||
* @return None
|
||||
* Note: all these ulIntType values above can be ORed together for using as input parameter.
|
||||
**********************************************************************/
|
||||
void MCPWM_IntClear(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
|
||||
{
|
||||
MCPWMx->MCINTFLAG_CLR = ulIntType;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if the specified interrupt in MCPWM is set or not
|
||||
* @param[in] MCPWMx Motor Control PWM peripheral selected,
|
||||
* should be: LPC_MCPWM
|
||||
* @param[in] ulIntType Interrupt type, should be:
|
||||
* - MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
|
||||
* - MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
|
||||
* - MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
|
||||
* - MCPWM_INTFLAG_ABORT: Fast abort interrupt
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
FlagStatus MCPWM_GetIntStatus(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
|
||||
{
|
||||
return ((MCPWMx->MCINTFLAG & ulIntType) ? SET : RESET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _MCPWM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,148 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_nvic.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_nvic.c
|
||||
* @brief Contains all expansion functions support for
|
||||
* NVIC firmware library on LPC17xx. The main
|
||||
* NVIC functions are defined in core_cm3.h
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup NVIC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_nvic.h"
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @addtogroup NVIC_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Vector table offset bit mask */
|
||||
#define NVIC_VTOR_MASK 0x3FFFFF80
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup NVIC_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief De-initializes the NVIC peripheral registers to their default
|
||||
* reset values.
|
||||
* @param None
|
||||
* @return None
|
||||
*
|
||||
* These following NVIC peripheral registers will be de-initialized:
|
||||
* - Disable Interrupt (32 IRQ interrupt sources that matched with LPC17xx)
|
||||
* - Clear all Pending Interrupts (32 IRQ interrupt source that matched with LPC17xx)
|
||||
* - Clear all Interrupt Priorities (32 IRQ interrupt source that matched with LPC17xx)
|
||||
*******************************************************************************/
|
||||
void NVIC_DeInit(void)
|
||||
{
|
||||
uint8_t tmp;
|
||||
|
||||
/* Disable all interrupts */
|
||||
NVIC->ICER[0] = 0xFFFFFFFF;
|
||||
NVIC->ICER[1] = 0x00000001;
|
||||
/* Clear all pending interrupts */
|
||||
NVIC->ICPR[0] = 0xFFFFFFFF;
|
||||
NVIC->ICPR[1] = 0x00000001;
|
||||
|
||||
/* Clear all interrupt priority */
|
||||
for (tmp = 0; tmp < 32; tmp++) {
|
||||
NVIC->IP[tmp] = 0x00;
|
||||
}
|
||||
}
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief De-initializes the SCB peripheral registers to their default
|
||||
* reset values.
|
||||
* @param none
|
||||
* @return none
|
||||
*
|
||||
* These following SCB NVIC peripheral registers will be de-initialized:
|
||||
* - Interrupt Control State register
|
||||
* - Interrupt Vector Table Offset register
|
||||
* - Application Interrupt/Reset Control register
|
||||
* - System Control register
|
||||
* - Configuration Control register
|
||||
* - System Handlers Priority Registers
|
||||
* - System Handler Control and State Register
|
||||
* - Configurable Fault Status Register
|
||||
* - Hard Fault Status Register
|
||||
* - Debug Fault Status Register
|
||||
*******************************************************************************/
|
||||
void NVIC_SCBDeInit(void)
|
||||
{
|
||||
uint8_t tmp;
|
||||
|
||||
SCB->ICSR = 0x0A000000;
|
||||
SCB->VTOR = 0x00000000;
|
||||
SCB->AIRCR = 0x05FA0000;
|
||||
SCB->SCR = 0x00000000;
|
||||
SCB->CCR = 0x00000000;
|
||||
|
||||
for (tmp = 0; tmp < (sizeof(SCB->SHP) / sizeof(SCB->SHP[0])); tmp++) {
|
||||
SCB->SHP[tmp] = 0x00;
|
||||
}
|
||||
|
||||
SCB->SHCSR = 0x00000000;
|
||||
SCB->CFSR = 0xFFFFFFFF;
|
||||
SCB->HFSR = 0xFFFFFFFF;
|
||||
SCB->DFSR = 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Set Vector Table Offset value
|
||||
* @param offset Offset value
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void NVIC_SetVTOR(uint32_t offset)
|
||||
{
|
||||
// SCB->VTOR = (offset & NVIC_VTOR_MASK);
|
||||
SCB->VTOR = offset;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,318 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_pinsel.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_pinsel.c
|
||||
* @brief Contains all functions support for Pin connect block firmware
|
||||
* library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup PINSEL
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_pinsel.h"
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
|
||||
static void set_PinFunc ( uint8_t portnum, uint8_t pinnum, uint8_t funcnum);
|
||||
static void set_ResistorMode ( uint8_t portnum, uint8_t pinnum, uint8_t modenum);
|
||||
static void set_OpenDrainMode( uint8_t portnum, uint8_t pinnum, uint8_t modenum);
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup the pin selection function
|
||||
* @param[in] portnum PORT number,
|
||||
* should be one of the following:
|
||||
* - PINSEL_PORT_0 : Port 0
|
||||
* - PINSEL_PORT_1 : Port 1
|
||||
* - PINSEL_PORT_2 : Port 2
|
||||
* - PINSEL_PORT_3 : Port 3
|
||||
*
|
||||
* @param[in] pinnum Pin number,
|
||||
* should be one of the following:
|
||||
- PINSEL_PIN_0 : Pin 0
|
||||
- PINSEL_PIN_1 : Pin 1
|
||||
- PINSEL_PIN_2 : Pin 2
|
||||
- PINSEL_PIN_3 : Pin 3
|
||||
- PINSEL_PIN_4 : Pin 4
|
||||
- PINSEL_PIN_5 : Pin 5
|
||||
- PINSEL_PIN_6 : Pin 6
|
||||
- PINSEL_PIN_7 : Pin 7
|
||||
- PINSEL_PIN_8 : Pin 8
|
||||
- PINSEL_PIN_9 : Pin 9
|
||||
- PINSEL_PIN_10 : Pin 10
|
||||
- PINSEL_PIN_11 : Pin 11
|
||||
- PINSEL_PIN_12 : Pin 12
|
||||
- PINSEL_PIN_13 : Pin 13
|
||||
- PINSEL_PIN_14 : Pin 14
|
||||
- PINSEL_PIN_15 : Pin 15
|
||||
- PINSEL_PIN_16 : Pin 16
|
||||
- PINSEL_PIN_17 : Pin 17
|
||||
- PINSEL_PIN_18 : Pin 18
|
||||
- PINSEL_PIN_19 : Pin 19
|
||||
- PINSEL_PIN_20 : Pin 20
|
||||
- PINSEL_PIN_21 : Pin 21
|
||||
- PINSEL_PIN_22 : Pin 22
|
||||
- PINSEL_PIN_23 : Pin 23
|
||||
- PINSEL_PIN_24 : Pin 24
|
||||
- PINSEL_PIN_25 : Pin 25
|
||||
- PINSEL_PIN_26 : Pin 26
|
||||
- PINSEL_PIN_27 : Pin 27
|
||||
- PINSEL_PIN_28 : Pin 28
|
||||
- PINSEL_PIN_29 : Pin 29
|
||||
- PINSEL_PIN_30 : Pin 30
|
||||
- PINSEL_PIN_31 : Pin 31
|
||||
|
||||
* @param[in] funcnum Function number,
|
||||
* should be one of the following:
|
||||
* - PINSEL_FUNC_0 : default function
|
||||
* - PINSEL_FUNC_1 : first alternate function
|
||||
* - PINSEL_FUNC_2 : second alternate function
|
||||
* - PINSEL_FUNC_3 : third alternate function
|
||||
*
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
static void set_PinFunc ( uint8_t portnum, uint8_t pinnum, uint8_t funcnum)
|
||||
{
|
||||
uint32_t pinnum_t = pinnum;
|
||||
uint32_t pinselreg_idx = 2 * portnum;
|
||||
uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINSEL0;
|
||||
|
||||
if (pinnum_t >= 16) {
|
||||
pinnum_t -= 16;
|
||||
pinselreg_idx++;
|
||||
}
|
||||
*(uint32_t *)(pPinCon + pinselreg_idx) &= ~(0x03UL << (pinnum_t * 2));
|
||||
*(uint32_t *)(pPinCon + pinselreg_idx) |= ((uint32_t)funcnum) << (pinnum_t * 2);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup resistor mode for each pin
|
||||
* @param[in] portnum PORT number,
|
||||
* should be one of the following:
|
||||
* - PINSEL_PORT_0 : Port 0
|
||||
* - PINSEL_PORT_1 : Port 1
|
||||
* - PINSEL_PORT_2 : Port 2
|
||||
* - PINSEL_PORT_3 : Port 3
|
||||
* @param[in] pinnum Pin number,
|
||||
* should be one of the following:
|
||||
- PINSEL_PIN_0 : Pin 0
|
||||
- PINSEL_PIN_1 : Pin 1
|
||||
- PINSEL_PIN_2 : Pin 2
|
||||
- PINSEL_PIN_3 : Pin 3
|
||||
- PINSEL_PIN_4 : Pin 4
|
||||
- PINSEL_PIN_5 : Pin 5
|
||||
- PINSEL_PIN_6 : Pin 6
|
||||
- PINSEL_PIN_7 : Pin 7
|
||||
- PINSEL_PIN_8 : Pin 8
|
||||
- PINSEL_PIN_9 : Pin 9
|
||||
- PINSEL_PIN_10 : Pin 10
|
||||
- PINSEL_PIN_11 : Pin 11
|
||||
- PINSEL_PIN_12 : Pin 12
|
||||
- PINSEL_PIN_13 : Pin 13
|
||||
- PINSEL_PIN_14 : Pin 14
|
||||
- PINSEL_PIN_15 : Pin 15
|
||||
- PINSEL_PIN_16 : Pin 16
|
||||
- PINSEL_PIN_17 : Pin 17
|
||||
- PINSEL_PIN_18 : Pin 18
|
||||
- PINSEL_PIN_19 : Pin 19
|
||||
- PINSEL_PIN_20 : Pin 20
|
||||
- PINSEL_PIN_21 : Pin 21
|
||||
- PINSEL_PIN_22 : Pin 22
|
||||
- PINSEL_PIN_23 : Pin 23
|
||||
- PINSEL_PIN_24 : Pin 24
|
||||
- PINSEL_PIN_25 : Pin 25
|
||||
- PINSEL_PIN_26 : Pin 26
|
||||
- PINSEL_PIN_27 : Pin 27
|
||||
- PINSEL_PIN_28 : Pin 28
|
||||
- PINSEL_PIN_29 : Pin 29
|
||||
- PINSEL_PIN_30 : Pin 30
|
||||
- PINSEL_PIN_31 : Pin 31
|
||||
|
||||
* @param[in] modenum: Mode number,
|
||||
* should be one of the following:
|
||||
- PINSEL_PINMODE_PULLUP : Internal pull-up resistor
|
||||
- PINSEL_PINMODE_TRISTATE : Tri-state
|
||||
- PINSEL_PINMODE_PULLDOWN : Internal pull-down resistor
|
||||
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void set_ResistorMode ( uint8_t portnum, uint8_t pinnum, uint8_t modenum)
|
||||
{
|
||||
uint32_t pinnum_t = pinnum;
|
||||
uint32_t pinmodereg_idx = 2 * portnum;
|
||||
uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINMODE0;
|
||||
|
||||
if (pinnum_t >= 16) {
|
||||
pinnum_t -= 16;
|
||||
pinmodereg_idx++ ;
|
||||
}
|
||||
|
||||
*(uint32_t *)(pPinCon + pinmodereg_idx) &= ~(0x03UL << (pinnum_t * 2));
|
||||
*(uint32_t *)(pPinCon + pinmodereg_idx) |= ((uint32_t)modenum) << (pinnum_t * 2);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup Open drain mode for each pin
|
||||
* @param[in] portnum PORT number,
|
||||
* should be one of the following:
|
||||
* - PINSEL_PORT_0 : Port 0
|
||||
* - PINSEL_PORT_1 : Port 1
|
||||
* - PINSEL_PORT_2 : Port 2
|
||||
* - PINSEL_PORT_3 : Port 3
|
||||
*
|
||||
* @param[in] pinnum Pin number,
|
||||
* should be one of the following:
|
||||
- PINSEL_PIN_0 : Pin 0
|
||||
- PINSEL_PIN_1 : Pin 1
|
||||
- PINSEL_PIN_2 : Pin 2
|
||||
- PINSEL_PIN_3 : Pin 3
|
||||
- PINSEL_PIN_4 : Pin 4
|
||||
- PINSEL_PIN_5 : Pin 5
|
||||
- PINSEL_PIN_6 : Pin 6
|
||||
- PINSEL_PIN_7 : Pin 7
|
||||
- PINSEL_PIN_8 : Pin 8
|
||||
- PINSEL_PIN_9 : Pin 9
|
||||
- PINSEL_PIN_10 : Pin 10
|
||||
- PINSEL_PIN_11 : Pin 11
|
||||
- PINSEL_PIN_12 : Pin 12
|
||||
- PINSEL_PIN_13 : Pin 13
|
||||
- PINSEL_PIN_14 : Pin 14
|
||||
- PINSEL_PIN_15 : Pin 15
|
||||
- PINSEL_PIN_16 : Pin 16
|
||||
- PINSEL_PIN_17 : Pin 17
|
||||
- PINSEL_PIN_18 : Pin 18
|
||||
- PINSEL_PIN_19 : Pin 19
|
||||
- PINSEL_PIN_20 : Pin 20
|
||||
- PINSEL_PIN_21 : Pin 21
|
||||
- PINSEL_PIN_22 : Pin 22
|
||||
- PINSEL_PIN_23 : Pin 23
|
||||
- PINSEL_PIN_24 : Pin 24
|
||||
- PINSEL_PIN_25 : Pin 25
|
||||
- PINSEL_PIN_26 : Pin 26
|
||||
- PINSEL_PIN_27 : Pin 27
|
||||
- PINSEL_PIN_28 : Pin 28
|
||||
- PINSEL_PIN_29 : Pin 29
|
||||
- PINSEL_PIN_30 : Pin 30
|
||||
- PINSEL_PIN_31 : Pin 31
|
||||
|
||||
* @param[in] modenum Open drain mode number,
|
||||
* should be one of the following:
|
||||
* - PINSEL_PINMODE_NORMAL : Pin is in the normal (not open drain) mode
|
||||
* - PINSEL_PINMODE_OPENDRAIN : Pin is in the open drain mode
|
||||
*
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void set_OpenDrainMode( uint8_t portnum, uint8_t pinnum, uint8_t modenum)
|
||||
{
|
||||
uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINMODE_OD0;
|
||||
|
||||
if (modenum == PINSEL_PINMODE_OPENDRAIN){
|
||||
*(uint32_t *)(pPinCon + portnum) |= (0x01UL << pinnum);
|
||||
} else {
|
||||
*(uint32_t *)(pPinCon + portnum) &= ~(0x01UL << pinnum);
|
||||
}
|
||||
}
|
||||
|
||||
/* End of Public Functions ---------------------------------------------------- */
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup PINSEL_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
/*********************************************************************//**
|
||||
* @brief Configure trace function
|
||||
* @param[in] NewState State of the Trace function configuration,
|
||||
* should be one of the following:
|
||||
* - ENABLE : Enable Trace Function
|
||||
* - DISABLE : Disable Trace Function
|
||||
*
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PINSEL_ConfigTraceFunc(FunctionalState NewState)
|
||||
{
|
||||
if (NewState == ENABLE) {
|
||||
LPC_PINCON->PINSEL10 |= (0x01UL << 3);
|
||||
} else if (NewState == DISABLE) {
|
||||
LPC_PINCON->PINSEL10 &= ~(0x01UL << 3);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup I2C0 pins
|
||||
* @param[in] i2cPinMode I2C pin mode,
|
||||
* should be one of the following:
|
||||
* - PINSEL_I2C_Normal_Mode : The standard drive mode
|
||||
* - PINSEL_I2C_Fast_Mode : Fast Mode Plus drive mode
|
||||
*
|
||||
* @param[in] filterSlewRateEnable should be:
|
||||
* - ENABLE: Enable filter and slew rate.
|
||||
* - DISABLE: Disable filter and slew rate.
|
||||
*
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PINSEL_SetI2C0Pins(uint8_t i2cPinMode, FunctionalState filterSlewRateEnable)
|
||||
{
|
||||
uint32_t regVal;
|
||||
|
||||
if (i2cPinMode == PINSEL_I2C_Fast_Mode){
|
||||
regVal = PINSEL_I2CPADCFG_SCLDRV0 | PINSEL_I2CPADCFG_SDADRV0;
|
||||
}
|
||||
|
||||
if (filterSlewRateEnable == DISABLE){
|
||||
regVal = PINSEL_I2CPADCFG_SCLI2C0 | PINSEL_I2CPADCFG_SDAI2C0;
|
||||
}
|
||||
LPC_PINCON->I2CPADCFG = regVal;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configure Pin corresponding to specified parameters passed
|
||||
* in the PinCfg
|
||||
* @param[in] PinCfg Pointer to a PINSEL_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified pin.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PINSEL_ConfigPin(PINSEL_CFG_Type *PinCfg)
|
||||
{
|
||||
set_PinFunc(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->Funcnum);
|
||||
set_ResistorMode(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->Pinmode);
|
||||
set_OpenDrainMode(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->OpenDrain);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,588 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_pwm.c 2011-03-31
|
||||
*//**
|
||||
* @file lpc17xx_pwm.c
|
||||
* @brief Contains all functions support for PWM firmware library on LPC17xx
|
||||
* @version 2.1
|
||||
* @date 31. Mar. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup PWM
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_pwm.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _PWM
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup PWM_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether specified interrupt flag in PWM is set or not
|
||||
* @param[in] PWMx: PWM peripheral, should be LPC_PWM1
|
||||
* @param[in] IntFlag: PWM interrupt flag, should be:
|
||||
* - PWM_INTSTAT_MR0: Interrupt flag for PWM match channel 0
|
||||
* - PWM_INTSTAT_MR1: Interrupt flag for PWM match channel 1
|
||||
* - PWM_INTSTAT_MR2: Interrupt flag for PWM match channel 2
|
||||
* - PWM_INTSTAT_MR3: Interrupt flag for PWM match channel 3
|
||||
* - PWM_INTSTAT_MR4: Interrupt flag for PWM match channel 4
|
||||
* - PWM_INTSTAT_MR5: Interrupt flag for PWM match channel 5
|
||||
* - PWM_INTSTAT_MR6: Interrupt flag for PWM match channel 6
|
||||
* - PWM_INTSTAT_CAP0: Interrupt flag for capture input 0
|
||||
* - PWM_INTSTAT_CAP1: Interrupt flag for capture input 1
|
||||
* @return New State of PWM interrupt flag (SET or RESET)
|
||||
**********************************************************************/
|
||||
IntStatus PWM_GetIntStatus(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM_INTSTAT(IntFlag));
|
||||
|
||||
return ((PWMx->IR & IntFlag) ? SET : RESET);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear specified PWM Interrupt pending
|
||||
* @param[in] PWMx: PWM peripheral, should be LPC_PWM1
|
||||
* @param[in] IntFlag: PWM interrupt flag, should be:
|
||||
* - PWM_INTSTAT_MR0: Interrupt flag for PWM match channel 0
|
||||
* - PWM_INTSTAT_MR1: Interrupt flag for PWM match channel 1
|
||||
* - PWM_INTSTAT_MR2: Interrupt flag for PWM match channel 2
|
||||
* - PWM_INTSTAT_MR3: Interrupt flag for PWM match channel 3
|
||||
* - PWM_INTSTAT_MR4: Interrupt flag for PWM match channel 4
|
||||
* - PWM_INTSTAT_MR5: Interrupt flag for PWM match channel 5
|
||||
* - PWM_INTSTAT_MR6: Interrupt flag for PWM match channel 6
|
||||
* - PWM_INTSTAT_CAP0: Interrupt flag for capture input 0
|
||||
* - PWM_INTSTAT_CAP1: Interrupt flag for capture input 1
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_ClearIntPending(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM_INTSTAT(IntFlag));
|
||||
PWMx->IR = IntFlag;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Fills each PWM_InitStruct member with its default value:
|
||||
* - If PWMCounterMode = PWM_MODE_TIMER:
|
||||
* + PrescaleOption = PWM_TIMER_PRESCALE_USVAL
|
||||
* + PrescaleValue = 1
|
||||
* - If PWMCounterMode = PWM_MODE_COUNTER:
|
||||
* + CountInputSelect = PWM_COUNTER_PCAP1_0
|
||||
* + CounterOption = PWM_COUNTER_RISING
|
||||
* @param[in] PWMTimerCounterMode Timer or Counter mode, should be:
|
||||
* - PWM_MODE_TIMER: Counter of PWM peripheral is in Timer mode
|
||||
* - PWM_MODE_COUNTER: Counter of PWM peripheral is in Counter mode
|
||||
* @param[in] PWM_InitStruct Pointer to structure (PWM_TIMERCFG_Type or
|
||||
* PWM_COUNTERCFG_Type) which will be initialized.
|
||||
* @return None
|
||||
* Note: PWM_InitStruct pointer will be assigned to corresponding structure
|
||||
* (PWM_TIMERCFG_Type or PWM_COUNTERCFG_Type) due to PWMTimerCounterMode.
|
||||
*******************************************************************************/
|
||||
void PWM_ConfigStructInit(uint8_t PWMTimerCounterMode, void *PWM_InitStruct)
|
||||
{
|
||||
PWM_TIMERCFG_Type *pTimeCfg;
|
||||
PWM_COUNTERCFG_Type *pCounterCfg;
|
||||
CHECK_PARAM(PARAM_PWM_TC_MODE(PWMTimerCounterMode));
|
||||
|
||||
pTimeCfg = (PWM_TIMERCFG_Type *) PWM_InitStruct;
|
||||
pCounterCfg = (PWM_COUNTERCFG_Type *) PWM_InitStruct;
|
||||
|
||||
if (PWMTimerCounterMode == PWM_MODE_TIMER )
|
||||
{
|
||||
pTimeCfg->PrescaleOption = PWM_TIMER_PRESCALE_USVAL;
|
||||
pTimeCfg->PrescaleValue = 1;
|
||||
}
|
||||
else if (PWMTimerCounterMode == PWM_MODE_COUNTER)
|
||||
{
|
||||
pCounterCfg->CountInputSelect = PWM_COUNTER_PCAP1_0;
|
||||
pCounterCfg->CounterOption = PWM_COUNTER_RISING;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes the PWMx peripheral corresponding to the specified
|
||||
* parameters in the PWM_ConfigStruct.
|
||||
* @param[in] PWMx PWM peripheral, should be LPC_PWM1
|
||||
* @param[in] PWMTimerCounterMode Timer or Counter mode, should be:
|
||||
* - PWM_MODE_TIMER: Counter of PWM peripheral is in Timer mode
|
||||
* - PWM_MODE_COUNTER: Counter of PWM peripheral is in Counter mode
|
||||
* @param[in] PWM_ConfigStruct Pointer to structure (PWM_TIMERCFG_Type or
|
||||
* PWM_COUNTERCFG_Type) which will be initialized.
|
||||
* @return None
|
||||
* Note: PWM_ConfigStruct pointer will be assigned to corresponding structure
|
||||
* (PWM_TIMERCFG_Type or PWM_COUNTERCFG_Type) due to PWMTimerCounterMode.
|
||||
**********************************************************************/
|
||||
void PWM_Init(LPC_PWM_TypeDef *PWMx, uint32_t PWMTimerCounterMode, void *PWM_ConfigStruct)
|
||||
{
|
||||
PWM_TIMERCFG_Type *pTimeCfg;
|
||||
PWM_COUNTERCFG_Type *pCounterCfg;
|
||||
uint64_t clkdlycnt;
|
||||
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM_TC_MODE(PWMTimerCounterMode));
|
||||
|
||||
pTimeCfg = (PWM_TIMERCFG_Type *)PWM_ConfigStruct;
|
||||
pCounterCfg = (PWM_COUNTERCFG_Type *)PWM_ConfigStruct;
|
||||
|
||||
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCPWM1, ENABLE);
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_PWM1, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
// Get peripheral clock of PWM1
|
||||
clkdlycnt = (uint64_t) CLKPWR_GetPCLK (CLKPWR_PCLKSEL_PWM1);
|
||||
|
||||
|
||||
// Clear all interrupts pending
|
||||
PWMx->IR = 0xFF & PWM_IR_BITMASK;
|
||||
PWMx->TCR = 0x00;
|
||||
PWMx->CTCR = 0x00;
|
||||
PWMx->MCR = 0x00;
|
||||
PWMx->CCR = 0x00;
|
||||
PWMx->PCR = 0x00;
|
||||
PWMx->LER = 0x00;
|
||||
|
||||
if (PWMTimerCounterMode == PWM_MODE_TIMER)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWM_TIMER_PRESCALE(pTimeCfg->PrescaleOption));
|
||||
|
||||
/* Absolute prescale value */
|
||||
if (pTimeCfg->PrescaleOption == PWM_TIMER_PRESCALE_TICKVAL)
|
||||
{
|
||||
PWMx->PR = pTimeCfg->PrescaleValue - 1;
|
||||
}
|
||||
/* uSecond prescale value */
|
||||
else
|
||||
{
|
||||
clkdlycnt = (clkdlycnt * pTimeCfg->PrescaleValue) / 1000000;
|
||||
PWMx->PR = ((uint32_t) clkdlycnt) - 1;
|
||||
}
|
||||
|
||||
}
|
||||
else if (PWMTimerCounterMode == PWM_MODE_COUNTER)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWM_COUNTER_INPUTSEL(pCounterCfg->CountInputSelect));
|
||||
CHECK_PARAM(PARAM_PWM_COUNTER_EDGE(pCounterCfg->CounterOption));
|
||||
|
||||
PWMx->CTCR |= (PWM_CTCR_MODE((uint32_t)pCounterCfg->CounterOption)) \
|
||||
| (PWM_CTCR_SELECT_INPUT((uint32_t)pCounterCfg->CountInputSelect));
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the PWM peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_DeInit (LPC_PWM_TypeDef *PWMx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
|
||||
// Disable PWM control (timer, counter and PWM)
|
||||
PWMx->TCR = 0x00;
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCPWM1, DISABLE);
|
||||
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: Enable PWM peripheral
|
||||
* - DISABLE: Disable PWM peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_Cmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
PWMx->TCR |= PWM_TCR_PWM_ENABLE;
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->TCR &= (~PWM_TCR_PWM_ENABLE) & PWM_TCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable Counter in PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: Enable Counter in PWM peripheral
|
||||
* - DISABLE: Disable Counter in PWM peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_CounterCmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
PWMx->TCR |= PWM_TCR_COUNTER_ENABLE;
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->TCR &= (~PWM_TCR_COUNTER_ENABLE) & PWM_TCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Reset Counter in PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_ResetCounter(LPC_PWM_TypeDef *PWMx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
PWMx->TCR |= PWM_TCR_COUNTER_RESET;
|
||||
PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures match for PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] PWM_MatchConfigStruct Pointer to a PWM_MATCHCFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified PWM match function.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_ConfigMatch(LPC_PWM_TypeDef *PWMx, PWM_MATCHCFG_Type *PWM_MatchConfigStruct)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_MATCH_CHANNEL(PWM_MatchConfigStruct->MatchChannel));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->IntOnMatch));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->ResetOnMatch));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->StopOnMatch));
|
||||
|
||||
//interrupt on MRn
|
||||
if (PWM_MatchConfigStruct->IntOnMatch == ENABLE)
|
||||
{
|
||||
PWMx->MCR |= PWM_MCR_INT_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->MCR &= (~PWM_MCR_INT_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
|
||||
& PWM_MCR_BITMASK;
|
||||
}
|
||||
|
||||
//reset on MRn
|
||||
if (PWM_MatchConfigStruct->ResetOnMatch == ENABLE)
|
||||
{
|
||||
PWMx->MCR |= PWM_MCR_RESET_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->MCR &= (~PWM_MCR_RESET_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
|
||||
& PWM_MCR_BITMASK;
|
||||
}
|
||||
|
||||
//stop on MRn
|
||||
if (PWM_MatchConfigStruct->StopOnMatch == ENABLE)
|
||||
{
|
||||
PWMx->MCR |= PWM_MCR_STOP_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->MCR &= (~PWM_MCR_STOP_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
|
||||
& PWM_MCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures capture input for PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] PWM_CaptureConfigStruct Pointer to a PWM_CAPTURECFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified PWM capture input function.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void PWM_ConfigCapture(LPC_PWM_TypeDef *PWMx, PWM_CAPTURECFG_Type *PWM_CaptureConfigStruct)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_CAPTURE_CHANNEL(PWM_CaptureConfigStruct->CaptureChannel));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->FallingEdge));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->IntOnCaption));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->RisingEdge));
|
||||
|
||||
if (PWM_CaptureConfigStruct->RisingEdge == ENABLE)
|
||||
{
|
||||
PWMx->CCR |= PWM_CCR_CAP_RISING(PWM_CaptureConfigStruct->CaptureChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->CCR &= (~PWM_CCR_CAP_RISING(PWM_CaptureConfigStruct->CaptureChannel)) \
|
||||
& PWM_CCR_BITMASK;
|
||||
}
|
||||
|
||||
if (PWM_CaptureConfigStruct->FallingEdge == ENABLE)
|
||||
{
|
||||
PWMx->CCR |= PWM_CCR_CAP_FALLING(PWM_CaptureConfigStruct->CaptureChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->CCR &= (~PWM_CCR_CAP_FALLING(PWM_CaptureConfigStruct->CaptureChannel)) \
|
||||
& PWM_CCR_BITMASK;
|
||||
}
|
||||
|
||||
if (PWM_CaptureConfigStruct->IntOnCaption == ENABLE)
|
||||
{
|
||||
PWMx->CCR |= PWM_CCR_INT_ON_CAP(PWM_CaptureConfigStruct->CaptureChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->CCR &= (~PWM_CCR_INT_ON_CAP(PWM_CaptureConfigStruct->CaptureChannel)) \
|
||||
& PWM_CCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read value of capture register PWM peripheral
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] CaptureChannel: capture channel number, should be in
|
||||
* range 0 to 1
|
||||
* @return Value of capture register
|
||||
**********************************************************************/
|
||||
uint32_t PWM_GetCaptureValue(LPC_PWM_TypeDef *PWMx, uint8_t CaptureChannel)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_CAPTURE_CHANNEL(CaptureChannel));
|
||||
|
||||
switch (CaptureChannel)
|
||||
{
|
||||
case 0:
|
||||
return PWMx->CR0;
|
||||
|
||||
case 1:
|
||||
return PWMx->CR1;
|
||||
|
||||
default:
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Update value for each PWM channel with update type option
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] MatchChannel Match channel
|
||||
* @param[in] MatchValue Match value
|
||||
* @param[in] UpdateType Type of Update, should be:
|
||||
* - PWM_MATCH_UPDATE_NOW: The update value will be updated for
|
||||
* this channel immediately
|
||||
* - PWM_MATCH_UPDATE_NEXT_RST: The update value will be updated for
|
||||
* this channel on next reset by a PWM Match event.
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void PWM_MatchUpdate(LPC_PWM_TypeDef *PWMx, uint8_t MatchChannel, \
|
||||
uint32_t MatchValue, uint8_t UpdateType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_MATCH_CHANNEL(MatchChannel));
|
||||
CHECK_PARAM(PARAM_PWM_MATCH_UPDATE(UpdateType));
|
||||
|
||||
switch (MatchChannel)
|
||||
{
|
||||
case 0:
|
||||
PWMx->MR0 = MatchValue;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
PWMx->MR1 = MatchValue;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
PWMx->MR2 = MatchValue;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
PWMx->MR3 = MatchValue;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
PWMx->MR4 = MatchValue;
|
||||
break;
|
||||
|
||||
case 5:
|
||||
PWMx->MR5 = MatchValue;
|
||||
break;
|
||||
|
||||
case 6:
|
||||
PWMx->MR6 = MatchValue;
|
||||
break;
|
||||
}
|
||||
|
||||
// Write Latch register
|
||||
PWMx->LER |= PWM_LER_EN_MATCHn_LATCH(MatchChannel);
|
||||
|
||||
// In case of update now
|
||||
if (UpdateType == PWM_MATCH_UPDATE_NOW)
|
||||
{
|
||||
PWMx->TCR |= PWM_TCR_COUNTER_RESET;
|
||||
PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Update value for multi PWM channel with update type option
|
||||
* at the same time
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] MatchStruct Structure that contents match value of 7 pwm channels
|
||||
* @param[in] UpdateType Type of Update, should be:
|
||||
* - PWM_MATCH_UPDATE_NOW: The update value will be updated for
|
||||
* this channel immediately
|
||||
* - PWM_MATCH_UPDATE_NEXT_RST: The update value will be updated for
|
||||
* this channel on next reset by a PWM Match event.
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void PWM_MultiMatchUpdate(LPC_PWM_TypeDef *PWMx, PWM_Match_T *MatchStruct , uint8_t UpdateType)
|
||||
{
|
||||
uint8_t LatchValue = 0;
|
||||
uint8_t i;
|
||||
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM_MATCH_UPDATE(UpdateType));
|
||||
|
||||
//Update match value
|
||||
for(i=0;i<7;i++)
|
||||
{
|
||||
if(MatchStruct[i].Status == SET)
|
||||
{
|
||||
if(i<4)
|
||||
*((volatile unsigned int *)(&(PWMx->MR0) + i)) = MatchStruct[i].Matchvalue;
|
||||
else
|
||||
{
|
||||
*((volatile unsigned int *)(&(PWMx->MR4) + (i-4))) = MatchStruct[i].Matchvalue;
|
||||
}
|
||||
LatchValue |=(1<<i);
|
||||
}
|
||||
}
|
||||
//set update for multi-channel at the same time
|
||||
PWMx->LER = LatchValue;
|
||||
|
||||
// In case of update now
|
||||
if (UpdateType == PWM_MATCH_UPDATE_NOW)
|
||||
{
|
||||
PWMx->TCR |= PWM_TCR_COUNTER_RESET;
|
||||
PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
|
||||
}
|
||||
}
|
||||
/********************************************************************//**
|
||||
* @brief Configure Edge mode for each PWM channel
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] PWMChannel PWM channel, should be in range from 2 to 6
|
||||
* @param[in] ModeOption PWM mode option, should be:
|
||||
* - PWM_CHANNEL_SINGLE_EDGE: Single Edge mode
|
||||
* - PWM_CHANNEL_DUAL_EDGE: Dual Edge mode
|
||||
* @return None
|
||||
* Note: PWM Channel 1 can not be selected for mode option
|
||||
*********************************************************************/
|
||||
void PWM_ChannelConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, uint8_t ModeOption)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_EDGE_MODE_CHANNEL(PWMChannel));
|
||||
CHECK_PARAM(PARAM_PWM_CHANNEL_EDGE(ModeOption));
|
||||
|
||||
// Single edge mode
|
||||
if (ModeOption == PWM_CHANNEL_SINGLE_EDGE)
|
||||
{
|
||||
PWMx->PCR &= (~PWM_PCR_PWMSELn(PWMChannel)) & PWM_PCR_BITMASK;
|
||||
}
|
||||
// Double edge mode
|
||||
else if (PWM_CHANNEL_DUAL_EDGE)
|
||||
{
|
||||
PWMx->PCR |= PWM_PCR_PWMSELn(PWMChannel);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Enable/Disable PWM channel output
|
||||
* @param[in] PWMx PWM peripheral selected, should be LPC_PWM1
|
||||
* @param[in] PWMChannel PWM channel, should be in range from 1 to 6
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: Enable this PWM channel output
|
||||
* - DISABLE: Disable this PWM channel output
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void PWM_ChannelCmd(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_PWMx(PWMx));
|
||||
CHECK_PARAM(PARAM_PWM1_CHANNEL(PWMChannel));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
PWMx->PCR |= PWM_PCR_PWMENAn(PWMChannel);
|
||||
}
|
||||
else
|
||||
{
|
||||
PWMx->PCR &= (~PWM_PCR_PWMENAn(PWMChannel)) & PWM_PCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _PWM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,514 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_qei.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_qei.c
|
||||
* @brief Contains all functions support for QEI firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup QEI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_qei.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _QEI
|
||||
|
||||
/* Private Types -------------------------------------------------------------- */
|
||||
/** @defgroup QEI_Private_Types QEI Private Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief QEI configuration union type definition
|
||||
*/
|
||||
typedef union {
|
||||
QEI_CFG_Type bmQEIConfig;
|
||||
uint32_t ulQEIConfig;
|
||||
} QEI_CFGOPT_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup QEI_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Resets value for each type of QEI value, such as velocity,
|
||||
* counter, position, etc..
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulResetType QEI Reset Type, should be one of the following:
|
||||
* - QEI_RESET_POS: Reset Position Counter
|
||||
* - QEI_RESET_POSOnIDX: Reset Position Counter on Index signal
|
||||
* - QEI_RESET_VEL: Reset Velocity
|
||||
* - QEI_RESET_IDX: Reset Index Counter
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_Reset(LPC_QEI_TypeDef *QEIx, uint32_t ulResetType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_RESET(ulResetType));
|
||||
|
||||
QEIx->QEICON = ulResetType;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initializes the QEI peripheral according to the specified
|
||||
* parameters in the QEI_ConfigStruct.
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] QEI_ConfigStruct Pointer to a QEI_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified QEI peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_Init(LPC_QEI_TypeDef *QEIx, QEI_CFG_Type *QEI_ConfigStruct)
|
||||
{
|
||||
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_DIRINV(QEI_ConfigStruct->DirectionInvert));
|
||||
CHECK_PARAM(PARAM_QEI_SIGNALMODE(QEI_ConfigStruct->SignalMode));
|
||||
CHECK_PARAM(PARAM_QEI_CAPMODE(QEI_ConfigStruct->CaptureMode));
|
||||
CHECK_PARAM(PARAM_QEI_INVINX(QEI_ConfigStruct->InvertIndex));
|
||||
|
||||
/* Set up clock and power for QEI module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCQEI, ENABLE);
|
||||
|
||||
/* As default, peripheral clock for QEI module
|
||||
* is set to FCCLK / 2 */
|
||||
CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_QEI, CLKPWR_PCLKSEL_CCLK_DIV_1);
|
||||
|
||||
// Reset all remaining value in QEI peripheral
|
||||
QEIx->QEICON = QEI_CON_RESP | QEI_CON_RESV | QEI_CON_RESI;
|
||||
QEIx->QEIMAXPOS = 0x00;
|
||||
QEIx->CMPOS0 = 0x00;
|
||||
QEIx->CMPOS1 = 0x00;
|
||||
QEIx->CMPOS2 = 0x00;
|
||||
QEIx->INXCMP = 0x00;
|
||||
QEIx->QEILOAD = 0x00;
|
||||
QEIx->VELCOMP = 0x00;
|
||||
QEIx->FILTER = 0x00;
|
||||
// Disable all Interrupt
|
||||
QEIx->QEIIEC = QEI_IECLR_BITMASK;
|
||||
// Clear all Interrupt pending
|
||||
QEIx->QEICLR = QEI_INTCLR_BITMASK;
|
||||
// Set QEI configuration value corresponding to its setting up value
|
||||
QEIx->QEICONF = ((QEI_CFGOPT_Type *)QEI_ConfigStruct)->ulQEIConfig;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the QEI peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_DeInit(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
|
||||
/* Turn off clock and power for QEI module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCQEI, DISABLE);
|
||||
}
|
||||
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Fills each QIE_InitStruct member with its default value:
|
||||
* - DirectionInvert = QEI_DIRINV_NONE
|
||||
* - SignalMode = QEI_SIGNALMODE_QUAD
|
||||
* - CaptureMode = QEI_CAPMODE_4X
|
||||
* - InvertIndex = QEI_INVINX_NONE
|
||||
* @param[in] QIE_InitStruct Pointer to a QEI_CFG_Type structure
|
||||
* which will be initialized.
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void QEI_ConfigStructInit(QEI_CFG_Type *QIE_InitStruct)
|
||||
{
|
||||
QIE_InitStruct->CaptureMode = QEI_CAPMODE_4X;
|
||||
QIE_InitStruct->DirectionInvert = QEI_DIRINV_NONE;
|
||||
QIE_InitStruct->InvertIndex = QEI_INVINX_NONE;
|
||||
QIE_InitStruct->SignalMode = QEI_SIGNALMODE_QUAD;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if specified flag status is set or not
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulFlagType Status Flag Type, should be one of the following:
|
||||
* - QEI_STATUS_DIR: Direction Status
|
||||
* @return New Status of this status flag (SET or RESET)
|
||||
**********************************************************************/
|
||||
FlagStatus QEI_GetStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulFlagType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_STATUS(ulFlagType));
|
||||
return ((QEIx->QEISTAT & ulFlagType) ? SET : RESET);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current position value in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return Current position value of QEI peripheral
|
||||
**********************************************************************/
|
||||
uint32_t QEI_GetPosition(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
return (QEIx->QEIPOS);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set max position value for QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulMaxPos Max position value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetMaxPosition(LPC_QEI_TypeDef *QEIx, uint32_t ulMaxPos)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
QEIx->QEIMAXPOS = ulMaxPos;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set position compare value for QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] bPosCompCh Compare Position channel, should be:
|
||||
* - QEI_COMPPOS_CH_0: QEI compare position channel 0
|
||||
* - QEI_COMPPOS_CH_1: QEI compare position channel 1
|
||||
* - QEI_COMPPOS_CH_2: QEI compare position channel 2
|
||||
* @param[in] ulPosComp Compare Position value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetPositionComp(LPC_QEI_TypeDef *QEIx, uint8_t bPosCompCh, uint32_t ulPosComp)
|
||||
{
|
||||
uint32_t *tmp;
|
||||
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_COMPPOS_CH(bPosCompCh));
|
||||
tmp = (uint32_t *) (&(QEIx->CMPOS0) + bPosCompCh * 4);
|
||||
*tmp = ulPosComp;
|
||||
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current index counter of QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return Current value of QEI index counter
|
||||
**********************************************************************/
|
||||
uint32_t QEI_GetIndex(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
return (QEIx->INXCNT);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set value for index compare in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulIndexComp Compare Index Value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetIndexComp(LPC_QEI_TypeDef *QEIx, uint32_t ulIndexComp)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
QEIx->INXCMP = ulIndexComp;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set timer reload value for QEI peripheral. When the velocity timer is
|
||||
* over-flow, the value that set for Timer Reload register will be loaded
|
||||
* into the velocity timer for next period. The calculated velocity in RPM
|
||||
* therefore will be affect by this value.
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] QEIReloadStruct QEI reload structure
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetTimerReload(LPC_QEI_TypeDef *QEIx, QEI_RELOADCFG_Type *QEIReloadStruct)
|
||||
{
|
||||
uint64_t pclk;
|
||||
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_TIMERRELOAD(QEIReloadStruct->ReloadOption));
|
||||
|
||||
if (QEIReloadStruct->ReloadOption == QEI_TIMERRELOAD_TICKVAL) {
|
||||
QEIx->QEILOAD = QEIReloadStruct->ReloadValue - 1;
|
||||
} else {
|
||||
pclk = (uint64_t)CLKPWR_GetPCLK(CLKPWR_PCLKSEL_QEI);
|
||||
pclk = (pclk /(1000000/QEIReloadStruct->ReloadValue)) - 1;
|
||||
QEIx->QEILOAD = (uint32_t)pclk;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current timer counter in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return Current timer counter in QEI peripheral
|
||||
**********************************************************************/
|
||||
uint32_t QEI_GetTimer(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
return (QEIx->QEITIME);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current velocity pulse counter in current time period
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return Current velocity pulse counter value
|
||||
**********************************************************************/
|
||||
uint32_t QEI_GetVelocity(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
return (QEIx->QEIVEL);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get the most recently measured velocity of the QEI. When
|
||||
* the Velocity timer in QEI is over-flow, the current velocity
|
||||
* value will be loaded into Velocity Capture register.
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @return The most recently measured velocity value
|
||||
**********************************************************************/
|
||||
uint32_t QEI_GetVelocityCap(LPC_QEI_TypeDef *QEIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
return (QEIx->QEICAP);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set Velocity Compare value for QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulVelComp Compare Velocity value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetVelocityComp(LPC_QEI_TypeDef *QEIx, uint32_t ulVelComp)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
QEIx->VELCOMP = ulVelComp;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set value of sampling count for the digital filter in
|
||||
* QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulSamplingPulse Value of sampling count to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_SetDigiFilter(LPC_QEI_TypeDef *QEIx, uint32_t ulSamplingPulse)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
QEIx->FILTER = ulSamplingPulse;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if specified interrupt flag status in QEI
|
||||
* peripheral is set or not
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulIntType Interrupt Flag Status type, should be:
|
||||
- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
|
||||
- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
|
||||
- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
|
||||
- QEI_INTFLAG_DIR_Int: Change of direction interrupt
|
||||
- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
|
||||
- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
|
||||
- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
|
||||
index count interrupt
|
||||
- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
|
||||
* @return New State of specified interrupt flag status (SET or RESET)
|
||||
**********************************************************************/
|
||||
FlagStatus QEI_GetIntStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
|
||||
|
||||
return((QEIx->QEIINTSTAT & ulIntType) ? SET : RESET);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable specified interrupt in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulIntType Interrupt Flag Status type, should be:
|
||||
* - QEI_INTFLAG_INX_Int: index pulse was detected interrupt
|
||||
* - QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
|
||||
* - QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
|
||||
* - QEI_INTFLAG_DIR_Int: Change of direction interrupt
|
||||
* - QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
|
||||
* - QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
|
||||
* - QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
|
||||
* current position interrupt
|
||||
* - QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
|
||||
* current position interrupt
|
||||
* - QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
|
||||
* current position interrupt
|
||||
* - QEI_INTFLAG_REV_Int: Index compare value is equal to the current
|
||||
* index count interrupt
|
||||
* - QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
|
||||
* - QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
|
||||
* - QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
|
||||
* @param[in] NewState New function state, should be:
|
||||
* - DISABLE
|
||||
* - ENABLE
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_IntCmd(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE) {
|
||||
QEIx->QEIIES = ulIntType;
|
||||
} else {
|
||||
QEIx->QEIIEC = ulIntType;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Sets (forces) specified interrupt in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulIntType Interrupt Flag Status type, should be:
|
||||
- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
|
||||
- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
|
||||
- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
|
||||
- QEI_INTFLAG_DIR_Int: Change of direction interrupt
|
||||
- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
|
||||
- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
|
||||
- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
|
||||
index count interrupt
|
||||
- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_IntSet(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
|
||||
|
||||
QEIx->QEISET = ulIntType;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear (force) specified interrupt (pending) in QEI peripheral
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulIntType Interrupt Flag Status type, should be:
|
||||
- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
|
||||
- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
|
||||
- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
|
||||
- QEI_INTFLAG_DIR_Int: Change of direction interrupt
|
||||
- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
|
||||
- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
|
||||
- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
|
||||
current position interrupt
|
||||
- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
|
||||
index count interrupt
|
||||
- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
|
||||
- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void QEI_IntClear(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_QEIx(QEIx));
|
||||
CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
|
||||
|
||||
QEIx->QEICLR = ulIntType;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Calculates the actual velocity in RPM passed via velocity
|
||||
* capture value and Pulse Per Round (of the encoder) value
|
||||
* parameter input.
|
||||
* @param[in] QEIx QEI peripheral, should be LPC_QEI
|
||||
* @param[in] ulVelCapValue Velocity capture input value that can
|
||||
* be got from QEI_GetVelocityCap() function
|
||||
* @param[in] ulPPR Pulse per round of encoder
|
||||
* @return The actual value of velocity in RPM (Round per minute)
|
||||
**********************************************************************/
|
||||
uint32_t QEI_CalculateRPM(LPC_QEI_TypeDef *QEIx, uint32_t ulVelCapValue, uint32_t ulPPR)
|
||||
{
|
||||
uint64_t rpm, clock, Load, edges;
|
||||
|
||||
// Get current Clock rate for timer input
|
||||
clock = (uint64_t)CLKPWR_GetPCLK(CLKPWR_PCLKSEL_QEI);
|
||||
// Get Timer load value (velocity capture period)
|
||||
Load = (uint64_t)(QEIx->QEILOAD + 1);
|
||||
// Get Edge
|
||||
edges = (uint64_t)((QEIx->QEICONF & QEI_CONF_CAPMODE) ? 4 : 2);
|
||||
// Calculate RPM
|
||||
rpm = ((clock * ulVelCapValue * 60) / (Load * ulPPR * edges));
|
||||
|
||||
return (uint32_t)(rpm);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _QEI */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,199 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_rit.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_rit.c
|
||||
* @brief Contains all functions support for RIT firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup RIT
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_rit.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
#ifdef _RIT
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup RIT_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/******************************************************************************//*
|
||||
* @brief Initial for RIT
|
||||
* - Turn on power and clock
|
||||
* - Setup default register values
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void RIT_Init(LPC_RIT_TypeDef *RITx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRIT, ENABLE);
|
||||
//Set up default register values
|
||||
RITx->RICOMPVAL = 0xFFFFFFFF;
|
||||
RITx->RIMASK = 0x00000000;
|
||||
RITx->RICTRL = 0x0C;
|
||||
RITx->RICOUNTER = 0x00000000;
|
||||
// Turn on power and clock
|
||||
|
||||
}
|
||||
/******************************************************************************//*
|
||||
* @brief DeInitial for RIT
|
||||
* - Turn off power and clock
|
||||
* - ReSetup default register values
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void RIT_DeInit(LPC_RIT_TypeDef *RITx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
|
||||
// Turn off power and clock
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRIT, DISABLE);
|
||||
//ReSetup default register values
|
||||
RITx->RICOMPVAL = 0xFFFFFFFF;
|
||||
RITx->RIMASK = 0x00000000;
|
||||
RITx->RICTRL = 0x0C;
|
||||
RITx->RICOUNTER = 0x00000000;
|
||||
}
|
||||
|
||||
/******************************************************************************//*
|
||||
* @brief Set compare value, mask value and time counter value
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @param[in] time_interval: timer interval value (ms)
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void RIT_TimerConfig(LPC_RIT_TypeDef *RITx, uint32_t time_interval)
|
||||
{
|
||||
uint32_t clock_rate, cmp_value;
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
|
||||
// Get PCLK value of RIT
|
||||
clock_rate = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_RIT);
|
||||
|
||||
/* calculate compare value for RIT to generate interrupt at
|
||||
* specified time interval
|
||||
* COMPVAL = (RIT_PCLK * time_interval)/1000
|
||||
* (with time_interval unit is millisecond)
|
||||
*/
|
||||
cmp_value = (clock_rate /1000) * time_interval;
|
||||
RITx->RICOMPVAL = cmp_value;
|
||||
|
||||
/* Set timer enable clear bit to clear timer to 0 whenever
|
||||
* counter value equals the contents of RICOMPVAL
|
||||
*/
|
||||
RITx->RICTRL |= (1<<1);
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************//*
|
||||
* @brief Enable/Disable Timer
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @param[in] NewState New State of this function
|
||||
* -ENABLE: Enable Timer
|
||||
* -DISABLE: Disable Timer
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void RIT_Cmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
//Enable or Disable Timer
|
||||
if(NewState==ENABLE)
|
||||
{
|
||||
RITx->RICTRL |= RIT_CTRL_TEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
RITx->RICTRL &= ~RIT_CTRL_TEN;
|
||||
}
|
||||
}
|
||||
|
||||
/******************************************************************************//*
|
||||
* @brief Timer Enable/Disable on debug
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @param[in] NewState New State of this function
|
||||
* -ENABLE: The timer is halted whenever a hardware break condition occurs
|
||||
* -DISABLE: Hardware break has no effect on the timer operation
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void RIT_TimerDebugCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
//Timer Enable/Disable on break
|
||||
if(NewState==ENABLE)
|
||||
{
|
||||
RITx->RICTRL |= RIT_CTRL_ENBR;
|
||||
}
|
||||
else
|
||||
{
|
||||
RITx->RICTRL &= ~RIT_CTRL_ENBR;
|
||||
}
|
||||
}
|
||||
/******************************************************************************//*
|
||||
* @brief Check whether interrupt flag is set or not
|
||||
* @param[in] RITx is RIT peripheral selected, should be: LPC_RIT
|
||||
* @return Current interrupt status, could be: SET/RESET
|
||||
*******************************************************************************/
|
||||
IntStatus RIT_GetIntStatus(LPC_RIT_TypeDef *RITx)
|
||||
{
|
||||
IntStatus result;
|
||||
CHECK_PARAM(PARAM_RITx(RITx));
|
||||
if((RITx->RICTRL&RIT_CTRL_INTEN)==1) result= SET;
|
||||
else return RESET;
|
||||
//clear interrupt flag
|
||||
RITx->RICTRL |= RIT_CTRL_INTEN;
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _RIT */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,783 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_rtc.c 2011-06-06
|
||||
*//**
|
||||
* @file lpc17xx_rtc.c
|
||||
* @brief Contains all functions support for RTC firmware library on LPC17xx
|
||||
* @version 3.1
|
||||
* @date 6. June. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup RTC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_rtc.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _RTC
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup RTC_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Initializes the RTC peripheral.
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void RTC_Init (LPC_RTC_TypeDef *RTCx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
/* Set up clock and power for RTC module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRTC, ENABLE);
|
||||
|
||||
// Clear all register to be default
|
||||
RTCx->ILR = 0x00;
|
||||
RTCx->CCR = 0x00;
|
||||
RTCx->CIIR = 0x00;
|
||||
RTCx->AMR = 0xFF;
|
||||
RTCx->CALIBRATION = 0x00;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the RTC peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_DeInit(LPC_RTC_TypeDef *RTCx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
RTCx->CCR = 0x00;
|
||||
// Disable power and clock for RTC module
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRTC, DISABLE);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Reset clock tick counter in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_ResetClockTickCounter(LPC_RTC_TypeDef *RTCx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
RTCx->CCR |= RTC_CCR_CTCRST;
|
||||
RTCx->CCR &= (~RTC_CCR_CTCRST) & RTC_CCR_BITMASK;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Start/Stop RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: The time counters are enabled
|
||||
* - DISABLE: The time counters are disabled
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_Cmd (LPC_RTC_TypeDef *RTCx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
RTCx->CCR |= RTC_CCR_CLKEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
RTCx->CCR &= (~RTC_CCR_CLKEN) & RTC_CCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable Counter increment interrupt for each time type
|
||||
* in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] CntIncrIntType: Counter Increment Interrupt type,
|
||||
* an increment of this type value below will generates
|
||||
* an interrupt, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: Counter Increment interrupt for this
|
||||
* time type are enabled
|
||||
* - DISABLE: Counter Increment interrupt for this
|
||||
* time type are disabled
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_CntIncrIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t CntIncrIntType, \
|
||||
FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
CHECK_PARAM(PARAM_RTC_TIMETYPE(CntIncrIntType));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
switch (CntIncrIntType)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
RTCx->CIIR |= RTC_CIIR_IMSEC;
|
||||
break;
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
RTCx->CIIR |= RTC_CIIR_IMMIN;
|
||||
break;
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
RTCx->CIIR |= RTC_CIIR_IMHOUR;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
RTCx->CIIR |= RTC_CIIR_IMDOW;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
RTCx->CIIR |= RTC_CIIR_IMDOM;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
RTCx->CIIR |= RTC_CIIR_IMDOY;
|
||||
break;
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
RTCx->CIIR |= RTC_CIIR_IMMON;
|
||||
break;
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
RTCx->CIIR |= RTC_CIIR_IMYEAR;
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
switch (CntIncrIntType)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMSEC) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMMIN) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMHOUR) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMDOW) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMDOM) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMDOY) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMMON) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
RTCx->CIIR &= (~RTC_CIIR_IMYEAR) & RTC_CIIR_BITMASK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable Alarm interrupt for each time type
|
||||
* in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] AlarmTimeType: Alarm Time Interrupt type,
|
||||
* an matching of this type value below with current time
|
||||
* in RTC will generates an interrupt, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: Alarm interrupt for this
|
||||
* time type are enabled
|
||||
* - DISABLE: Alarm interrupt for this
|
||||
* time type are disabled
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_AlarmIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t AlarmTimeType, \
|
||||
FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
CHECK_PARAM(PARAM_RTC_TIMETYPE(AlarmTimeType));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
switch (AlarmTimeType)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRSEC) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRMIN) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRHOUR) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRDOW) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRDOM) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRDOY) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRMON) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
RTCx->AMR &= (~RTC_AMR_AMRYEAR) & RTC_AMR_BITMASK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
switch (AlarmTimeType)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
RTCx->AMR |= (RTC_AMR_AMRSEC);
|
||||
break;
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
RTCx->AMR |= (RTC_AMR_AMRMIN);
|
||||
break;
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
RTCx->AMR |= (RTC_AMR_AMRHOUR);
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
RTCx->AMR |= (RTC_AMR_AMRDOW);
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
RTCx->AMR |= (RTC_AMR_AMRDOM);
|
||||
break;
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
RTCx->AMR |= (RTC_AMR_AMRDOY);
|
||||
break;
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
RTCx->AMR |= (RTC_AMR_AMRMON);
|
||||
break;
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
RTCx->AMR |= (RTC_AMR_AMRYEAR);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set current time value for each time type in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Timetype: Time Type, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @param[in] TimeValue Time value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_SetTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t TimeValue)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_TIMETYPE(Timetype));
|
||||
|
||||
switch ( Timetype)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
CHECK_PARAM(TimeValue <= RTC_SECOND_MAX);
|
||||
|
||||
RTCx->SEC = TimeValue & RTC_SEC_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
CHECK_PARAM(TimeValue <= RTC_MINUTE_MAX);
|
||||
|
||||
RTCx->MIN = TimeValue & RTC_MIN_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
CHECK_PARAM(TimeValue <= RTC_HOUR_MAX);
|
||||
|
||||
RTCx->HOUR = TimeValue & RTC_HOUR_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
CHECK_PARAM(TimeValue <= RTC_DAYOFWEEK_MAX);
|
||||
|
||||
RTCx->DOW = TimeValue & RTC_DOW_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
CHECK_PARAM((TimeValue <= RTC_DAYOFMONTH_MAX) \
|
||||
&& (TimeValue >= RTC_DAYOFMONTH_MIN));
|
||||
|
||||
RTCx->DOM = TimeValue & RTC_DOM_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
CHECK_PARAM((TimeValue >= RTC_DAYOFYEAR_MIN) \
|
||||
&& (TimeValue <= RTC_DAYOFYEAR_MAX));
|
||||
|
||||
RTCx->DOY = TimeValue & RTC_DOY_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
CHECK_PARAM((TimeValue >= RTC_MONTH_MIN) \
|
||||
&& (TimeValue <= RTC_MONTH_MAX));
|
||||
|
||||
RTCx->MONTH = TimeValue & RTC_MONTH_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
CHECK_PARAM(TimeValue <= RTC_YEAR_MAX);
|
||||
|
||||
RTCx->YEAR = TimeValue & RTC_YEAR_MASK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current time value for each type time type
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Timetype: Time Type, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @return Value of time according to specified time type
|
||||
**********************************************************************/
|
||||
uint32_t RTC_GetTime(LPC_RTC_TypeDef *RTCx, uint32_t Timetype)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_TIMETYPE(Timetype));
|
||||
|
||||
switch (Timetype)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
return (RTCx->SEC & RTC_SEC_MASK);
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
return (RTCx->MIN & RTC_MIN_MASK);
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
return (RTCx->HOUR & RTC_HOUR_MASK);
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
return (RTCx->DOW & RTC_DOW_MASK);
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
return (RTCx->DOM & RTC_DOM_MASK);
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
return (RTCx->DOY & RTC_DOY_MASK);
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
return (RTCx->MONTH & RTC_MONTH_MASK);
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
return (RTCx->YEAR & RTC_YEAR_MASK);
|
||||
default:
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set full of time in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] pFullTime Pointer to a RTC_TIME_Type structure that
|
||||
* contains time value in full.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_SetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
RTCx->DOM = pFullTime->DOM & RTC_DOM_MASK;
|
||||
RTCx->DOW = pFullTime->DOW & RTC_DOW_MASK;
|
||||
RTCx->DOY = pFullTime->DOY & RTC_DOY_MASK;
|
||||
RTCx->HOUR = pFullTime->HOUR & RTC_HOUR_MASK;
|
||||
RTCx->MIN = pFullTime->MIN & RTC_MIN_MASK;
|
||||
RTCx->SEC = pFullTime->SEC & RTC_SEC_MASK;
|
||||
RTCx->MONTH = pFullTime->MONTH & RTC_MONTH_MASK;
|
||||
RTCx->YEAR = pFullTime->YEAR & RTC_YEAR_MASK;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get full of time in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] pFullTime Pointer to a RTC_TIME_Type structure that
|
||||
* will be stored time in full.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_GetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
pFullTime->DOM = RTCx->DOM & RTC_DOM_MASK;
|
||||
pFullTime->DOW = RTCx->DOW & RTC_DOW_MASK;
|
||||
pFullTime->DOY = RTCx->DOY & RTC_DOY_MASK;
|
||||
pFullTime->HOUR = RTCx->HOUR & RTC_HOUR_MASK;
|
||||
pFullTime->MIN = RTCx->MIN & RTC_MIN_MASK;
|
||||
pFullTime->SEC = RTCx->SEC & RTC_SEC_MASK;
|
||||
pFullTime->MONTH = RTCx->MONTH & RTC_MONTH_MASK;
|
||||
pFullTime->YEAR = RTCx->YEAR & RTC_YEAR_MASK;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set alarm time value for each time type
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Timetype: Time Type, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @param[in] ALValue Alarm time value to set
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_SetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t ALValue)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
switch (Timetype)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
CHECK_PARAM(ALValue <= RTC_SECOND_MAX);
|
||||
|
||||
RTCx->ALSEC = ALValue & RTC_SEC_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
CHECK_PARAM(ALValue <= RTC_MINUTE_MAX);
|
||||
|
||||
RTCx->ALMIN = ALValue & RTC_MIN_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
CHECK_PARAM(ALValue <= RTC_HOUR_MAX);
|
||||
|
||||
RTCx->ALHOUR = ALValue & RTC_HOUR_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
CHECK_PARAM(ALValue <= RTC_DAYOFWEEK_MAX);
|
||||
|
||||
RTCx->ALDOW = ALValue & RTC_DOW_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
CHECK_PARAM((ALValue <= RTC_DAYOFMONTH_MAX) \
|
||||
&& (ALValue >= RTC_DAYOFMONTH_MIN));
|
||||
|
||||
RTCx->ALDOM = ALValue & RTC_DOM_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
CHECK_PARAM((ALValue >= RTC_DAYOFYEAR_MIN) \
|
||||
&& (ALValue <= RTC_DAYOFYEAR_MAX));
|
||||
|
||||
RTCx->ALDOY = ALValue & RTC_DOY_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
CHECK_PARAM((ALValue >= RTC_MONTH_MIN) \
|
||||
&& (ALValue <= RTC_MONTH_MAX));
|
||||
|
||||
RTCx->ALMON = ALValue & RTC_MONTH_MASK;
|
||||
break;
|
||||
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
CHECK_PARAM(ALValue <= RTC_YEAR_MAX);
|
||||
|
||||
RTCx->ALYEAR = ALValue & RTC_YEAR_MASK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get alarm time value for each time type
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Timetype: Time Type, should be:
|
||||
* - RTC_TIMETYPE_SECOND
|
||||
* - RTC_TIMETYPE_MINUTE
|
||||
* - RTC_TIMETYPE_HOUR
|
||||
* - RTC_TIMETYPE_DAYOFWEEK
|
||||
* - RTC_TIMETYPE_DAYOFMONTH
|
||||
* - RTC_TIMETYPE_DAYOFYEAR
|
||||
* - RTC_TIMETYPE_MONTH
|
||||
* - RTC_TIMETYPE_YEAR
|
||||
* @return Value of Alarm time according to specified time type
|
||||
**********************************************************************/
|
||||
uint32_t RTC_GetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype)
|
||||
{
|
||||
switch (Timetype)
|
||||
{
|
||||
case RTC_TIMETYPE_SECOND:
|
||||
return (RTCx->ALSEC & RTC_SEC_MASK);
|
||||
case RTC_TIMETYPE_MINUTE:
|
||||
return (RTCx->ALMIN & RTC_MIN_MASK);
|
||||
case RTC_TIMETYPE_HOUR:
|
||||
return (RTCx->ALHOUR & RTC_HOUR_MASK);
|
||||
case RTC_TIMETYPE_DAYOFWEEK:
|
||||
return (RTCx->ALDOW & RTC_DOW_MASK);
|
||||
case RTC_TIMETYPE_DAYOFMONTH:
|
||||
return (RTCx->ALDOM & RTC_DOM_MASK);
|
||||
case RTC_TIMETYPE_DAYOFYEAR:
|
||||
return (RTCx->ALDOY & RTC_DOY_MASK);
|
||||
case RTC_TIMETYPE_MONTH:
|
||||
return (RTCx->ALMON & RTC_MONTH_MASK);
|
||||
case RTC_TIMETYPE_YEAR:
|
||||
return (RTCx->ALYEAR & RTC_YEAR_MASK);
|
||||
default:
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Set full of alarm time in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] pFullTime Pointer to a RTC_TIME_Type structure that
|
||||
* contains alarm time value in full.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_SetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
RTCx->ALDOM = pFullTime->DOM & RTC_DOM_MASK;
|
||||
RTCx->ALDOW = pFullTime->DOW & RTC_DOW_MASK;
|
||||
RTCx->ALDOY = pFullTime->DOY & RTC_DOY_MASK;
|
||||
RTCx->ALHOUR = pFullTime->HOUR & RTC_HOUR_MASK;
|
||||
RTCx->ALMIN = pFullTime->MIN & RTC_MIN_MASK;
|
||||
RTCx->ALSEC = pFullTime->SEC & RTC_SEC_MASK;
|
||||
RTCx->ALMON = pFullTime->MONTH & RTC_MONTH_MASK;
|
||||
RTCx->ALYEAR = pFullTime->YEAR & RTC_YEAR_MASK;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get full of alarm time in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] pFullTime Pointer to a RTC_TIME_Type structure that
|
||||
* will be stored alarm time in full.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_GetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
|
||||
pFullTime->DOM = RTCx->ALDOM & RTC_DOM_MASK;
|
||||
pFullTime->DOW = RTCx->ALDOW & RTC_DOW_MASK;
|
||||
pFullTime->DOY = RTCx->ALDOY & RTC_DOY_MASK;
|
||||
pFullTime->HOUR = RTCx->ALHOUR & RTC_HOUR_MASK;
|
||||
pFullTime->MIN = RTCx->ALMIN & RTC_MIN_MASK;
|
||||
pFullTime->SEC = RTCx->ALSEC & RTC_SEC_MASK;
|
||||
pFullTime->MONTH = RTCx->ALMON & RTC_MONTH_MASK;
|
||||
pFullTime->YEAR = RTCx->ALYEAR & RTC_YEAR_MASK;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether if specified Location interrupt in
|
||||
* RTC peripheral is set or not
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] IntType Interrupt location type, should be:
|
||||
* - RTC_INT_COUNTER_INCREASE: Counter Increment Interrupt
|
||||
* block generated an interrupt.
|
||||
* - RTC_INT_ALARM: Alarm generated an
|
||||
* interrupt.
|
||||
* @return New state of specified Location interrupt in RTC peripheral
|
||||
* (SET or RESET)
|
||||
**********************************************************************/
|
||||
IntStatus RTC_GetIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_INT(IntType));
|
||||
|
||||
return ((RTCx->ILR & IntType) ? SET : RESET);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear specified Location interrupt pending in
|
||||
* RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] IntType Interrupt location type, should be:
|
||||
* - RTC_INT_COUNTER_INCREASE: Clear Counter Increment
|
||||
* Interrupt pending.
|
||||
* - RTC_INT_ALARM: Clear alarm interrupt pending
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_ClearIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_INT(IntType));
|
||||
|
||||
RTCx->ILR |= IntType;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable calibration counter in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] NewState New State of this function, should be:
|
||||
* - ENABLE: The calibration counter is enabled and counting
|
||||
* - DISABLE: The calibration counter is disabled and reset to zero
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_CalibCounterCmd(LPC_RTC_TypeDef *RTCx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
RTCx->CCR &= (~RTC_CCR_CCALEN) & RTC_CCR_BITMASK;
|
||||
}
|
||||
else
|
||||
{
|
||||
RTCx->CCR |= RTC_CCR_CCALEN;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configures Calibration in RTC peripheral
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] CalibValue Calibration value, should be in range from
|
||||
* 0 to 131,072
|
||||
* @param[in] CalibDir Calibration Direction, should be:
|
||||
* - RTC_CALIB_DIR_FORWARD: Forward calibration
|
||||
* - RTC_CALIB_DIR_BACKWARD: Backward calibration
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void RTC_CalibConfig(LPC_RTC_TypeDef *RTCx, uint32_t CalibValue, uint8_t CalibDir)
|
||||
{
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_CALIB_DIR(CalibDir));
|
||||
CHECK_PARAM(CalibValue < RTC_CALIBRATION_MAX);
|
||||
|
||||
RTCx->CALIBRATION = ((CalibValue) & RTC_CALIBRATION_CALVAL_MASK) \
|
||||
| ((CalibDir == RTC_CALIB_DIR_BACKWARD) ? RTC_CALIBRATION_LIBDIR : 0);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Write value to General purpose registers
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Channel General purpose registers Channel number,
|
||||
* should be in range from 0 to 4.
|
||||
* @param[in] Value Value to write
|
||||
* @return None
|
||||
* Note: These General purpose registers can be used to store important
|
||||
* information when the main power supply is off. The value in these
|
||||
* registers is not affected by chip reset.
|
||||
**********************************************************************/
|
||||
void RTC_WriteGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel, uint32_t Value)
|
||||
{
|
||||
uint32_t *preg;
|
||||
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_GPREG_CH(Channel));
|
||||
|
||||
preg = (uint32_t *)&RTCx->GPREG0;
|
||||
preg += Channel;
|
||||
*preg = Value;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read value from General purpose registers
|
||||
* @param[in] RTCx RTC peripheral selected, should be LPC_RTC
|
||||
* @param[in] Channel General purpose registers Channel number,
|
||||
* should be in range from 0 to 4.
|
||||
* @return Read Value
|
||||
* Note: These General purpose registers can be used to store important
|
||||
* information when the main power supply is off. The value in these
|
||||
* registers is not affected by chip reset.
|
||||
**********************************************************************/
|
||||
uint32_t RTC_ReadGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel)
|
||||
{
|
||||
uint32_t *preg;
|
||||
uint32_t value;
|
||||
|
||||
CHECK_PARAM(PARAM_RTCx(RTCx));
|
||||
CHECK_PARAM(PARAM_RTC_GPREG_CH(Channel));
|
||||
|
||||
preg = (uint32_t *)&RTCx->GPREG0;
|
||||
preg += Channel;
|
||||
value = *preg;
|
||||
return (value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _RTC */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,443 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_spi.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_spi.c
|
||||
* @brief Contains all functions support for SPI firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup SPI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_spi.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
#ifdef _SPI
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup SPI_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup clock rate for SPI device
|
||||
* @param[in] SPIx SPI peripheral definition, should be LPC_SPI
|
||||
* @param[in] target_clock : clock of SPI (Hz)
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
void SPI_SetClock (LPC_SPI_TypeDef *SPIx, uint32_t target_clock)
|
||||
{
|
||||
uint32_t spi_pclk;
|
||||
uint32_t prescale, temp;
|
||||
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
if (SPIx == LPC_SPI){
|
||||
spi_pclk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SPI);
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
prescale = 8;
|
||||
// Find closest clock to target clock
|
||||
while (1){
|
||||
temp = target_clock * prescale;
|
||||
if (temp >= spi_pclk){
|
||||
break;
|
||||
}
|
||||
prescale += 2;
|
||||
if(prescale >= 254){
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Write to register
|
||||
SPIx->SPCCR = SPI_SPCCR_COUNTER(prescale);
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the SPIx peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SPI_DeInit(LPC_SPI_TypeDef *SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
if (SPIx == LPC_SPI){
|
||||
/* Set up clock and power for SPI module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSPI, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get data bit size per transfer
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return number of bit per transfer, could be 8-16
|
||||
**********************************************************************/
|
||||
uint8_t SPI_GetDataSize (LPC_SPI_TypeDef *SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
return ((SPIx->SPCR)>>8 & 0xF);
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Initializes the SPIx peripheral according to the specified
|
||||
* parameters in the UART_ConfigStruct.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @param[in] SPI_ConfigStruct Pointer to a SPI_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified SPI peripheral.
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void SPI_Init(LPC_SPI_TypeDef *SPIx, SPI_CFG_Type *SPI_ConfigStruct)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
if(SPIx == LPC_SPI){
|
||||
/* Set up clock and power for UART module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSPI, ENABLE);
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
// Configure SPI, interrupt is disable as default
|
||||
tmp = ((SPI_ConfigStruct->CPHA) | (SPI_ConfigStruct->CPOL) \
|
||||
| (SPI_ConfigStruct->DataOrder) | (SPI_ConfigStruct->Databit) \
|
||||
| (SPI_ConfigStruct->Mode) | SPI_SPCR_BIT_EN) & SPI_SPCR_BITMASK;
|
||||
// write back to SPI control register
|
||||
SPIx->SPCR = tmp;
|
||||
|
||||
// Set clock rate for SPI peripheral
|
||||
SPI_SetClock(SPIx, SPI_ConfigStruct->ClockRate);
|
||||
|
||||
// If interrupt flag is set, Write '1' to Clear interrupt flag
|
||||
if (SPIx->SPINT & SPI_SPINT_INTFLAG){
|
||||
SPIx->SPINT = SPI_SPINT_INTFLAG;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Fills each SPI_InitStruct member with its default value:
|
||||
* - CPHA = SPI_CPHA_FIRST
|
||||
* - CPOL = SPI_CPOL_HI
|
||||
* - ClockRate = 1000000
|
||||
* - DataOrder = SPI_DATA_MSB_FIRST
|
||||
* - Databit = SPI_DATABIT_8
|
||||
* - Mode = SPI_MASTER_MODE
|
||||
* @param[in] SPI_InitStruct Pointer to a SPI_CFG_Type structure
|
||||
* which will be initialized.
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void SPI_ConfigStructInit(SPI_CFG_Type *SPI_InitStruct)
|
||||
{
|
||||
SPI_InitStruct->CPHA = SPI_CPHA_FIRST;
|
||||
SPI_InitStruct->CPOL = SPI_CPOL_HI;
|
||||
SPI_InitStruct->ClockRate = 1000000;
|
||||
SPI_InitStruct->DataOrder = SPI_DATA_MSB_FIRST;
|
||||
SPI_InitStruct->Databit = SPI_DATABIT_8;
|
||||
SPI_InitStruct->Mode = SPI_MASTER_MODE;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Transmit a single data through SPIx peripheral
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @param[in] Data Data to transmit (must be 16 or 8-bit long,
|
||||
* this depend on SPI data bit number configured)
|
||||
* @return none
|
||||
**********************************************************************/
|
||||
void SPI_SendData(LPC_SPI_TypeDef* SPIx, uint16_t Data)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
SPIx->SPDR = Data & SPI_SPDR_BITMASK;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Receive a single data from SPIx peripheral
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return Data received (16-bit long)
|
||||
**********************************************************************/
|
||||
uint16_t SPI_ReceiveData(LPC_SPI_TypeDef* SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
return ((uint16_t) (SPIx->SPDR & SPI_SPDR_BITMASK));
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief SPI Read write data function
|
||||
* @param[in] SPIx Pointer to SPI peripheral, should be LPC_SPI
|
||||
* @param[in] dataCfg Pointer to a SPI_DATA_SETUP_Type structure that
|
||||
* contains specified information about transmit
|
||||
* data configuration.
|
||||
* @param[in] xfType Transfer type, should be:
|
||||
* - SPI_TRANSFER_POLLING: Polling mode
|
||||
* - SPI_TRANSFER_INTERRUPT: Interrupt mode
|
||||
* @return Actual Data length has been transferred in polling mode.
|
||||
* In interrupt mode, always return (0)
|
||||
* Return (-1) if error.
|
||||
* Note: This function can be used in both master and slave mode.
|
||||
***********************************************************************/
|
||||
int32_t SPI_ReadWrite (LPC_SPI_TypeDef *SPIx, SPI_DATA_SETUP_Type *dataCfg, \
|
||||
SPI_TRANSFER_Type xfType)
|
||||
{
|
||||
uint8_t *rdata8;
|
||||
uint8_t *wdata8;
|
||||
uint16_t *rdata16;
|
||||
uint16_t *wdata16;
|
||||
uint32_t stat;
|
||||
uint32_t temp;
|
||||
uint8_t dataword;
|
||||
|
||||
//read for empty buffer
|
||||
temp = SPIx->SPDR;
|
||||
//dummy to clear status
|
||||
temp = SPIx->SPSR;
|
||||
dataCfg->counter = 0;
|
||||
dataCfg->status = 0;
|
||||
|
||||
if(SPI_GetDataSize (SPIx) == 8)
|
||||
dataword = 0;
|
||||
else dataword = 1;
|
||||
if (xfType == SPI_TRANSFER_POLLING){
|
||||
|
||||
if (dataword == 0){
|
||||
rdata8 = (uint8_t *)dataCfg->rx_data;
|
||||
wdata8 = (uint8_t *)dataCfg->tx_data;
|
||||
} else {
|
||||
rdata16 = (uint16_t *)dataCfg->rx_data;
|
||||
wdata16 = (uint16_t *)dataCfg->tx_data;
|
||||
}
|
||||
|
||||
while(dataCfg->counter < dataCfg->length)
|
||||
{
|
||||
// Write data to buffer
|
||||
if(dataCfg->tx_data == NULL){
|
||||
if (dataword == 0){
|
||||
SPI_SendData(SPIx, 0xFF);
|
||||
} else {
|
||||
SPI_SendData(SPIx, 0xFFFF);
|
||||
}
|
||||
} else {
|
||||
if (dataword == 0){
|
||||
SPI_SendData(SPIx, *wdata8);
|
||||
wdata8++;
|
||||
} else {
|
||||
SPI_SendData(SPIx, *wdata16);
|
||||
wdata16++;
|
||||
}
|
||||
}
|
||||
// Wait for transfer complete
|
||||
while (!((stat = SPIx->SPSR) & SPI_SPSR_SPIF));
|
||||
// Check for error
|
||||
if (stat & (SPI_SPSR_ABRT | SPI_SPSR_MODF | SPI_SPSR_ROVR | SPI_SPSR_WCOL)){
|
||||
// save status
|
||||
dataCfg->status = stat | SPI_STAT_ERROR;
|
||||
return (dataCfg->counter);
|
||||
}
|
||||
// Read data from SPI dat
|
||||
temp = (uint32_t) SPI_ReceiveData(SPIx);
|
||||
|
||||
// Store data to destination
|
||||
if (dataCfg->rx_data != NULL)
|
||||
{
|
||||
if (dataword == 0){
|
||||
*(rdata8) = (uint8_t) temp;
|
||||
rdata8++;
|
||||
} else {
|
||||
*(rdata16) = (uint16_t) temp;
|
||||
rdata16++;
|
||||
}
|
||||
}
|
||||
// Increase counter
|
||||
if (dataword == 0){
|
||||
dataCfg->counter++;
|
||||
} else {
|
||||
dataCfg->counter += 2;
|
||||
}
|
||||
}
|
||||
|
||||
// Return length of actual data transferred
|
||||
// save status
|
||||
dataCfg->status = stat | SPI_STAT_DONE;
|
||||
return (dataCfg->counter);
|
||||
}
|
||||
// Interrupt mode
|
||||
else {
|
||||
|
||||
// Check if interrupt flag is already set
|
||||
if(SPIx->SPINT & SPI_SPINT_INTFLAG){
|
||||
SPIx->SPINT = SPI_SPINT_INTFLAG;
|
||||
}
|
||||
if (dataCfg->counter < dataCfg->length){
|
||||
// Write data to buffer
|
||||
if(dataCfg->tx_data == NULL){
|
||||
if (dataword == 0){
|
||||
SPI_SendData(SPIx, 0xFF);
|
||||
} else {
|
||||
SPI_SendData(SPIx, 0xFFFF);
|
||||
}
|
||||
} else {
|
||||
if (dataword == 0){
|
||||
SPI_SendData(SPIx, (*(uint8_t *)dataCfg->tx_data));
|
||||
} else {
|
||||
SPI_SendData(SPIx, (*(uint16_t *)dataCfg->tx_data));
|
||||
}
|
||||
}
|
||||
SPI_IntCmd(SPIx, ENABLE);
|
||||
} else {
|
||||
// Save status
|
||||
dataCfg->status = SPI_STAT_DONE;
|
||||
}
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Enable or disable SPIx interrupt.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @param[in] NewState New state of specified UART interrupt type,
|
||||
* should be:
|
||||
* - ENALBE: Enable this SPI interrupt.
|
||||
* - DISALBE: Disable this SPI interrupt.
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void SPI_IntCmd(LPC_SPI_TypeDef *SPIx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SPIx->SPCR |= SPI_SPCR_SPIE;
|
||||
}
|
||||
else
|
||||
{
|
||||
SPIx->SPCR &= (~SPI_SPCR_SPIE) & SPI_SPCR_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Checks whether the SPI interrupt flag is set or not.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return The new state of SPI Interrupt Flag (SET or RESET)
|
||||
*********************************************************************/
|
||||
IntStatus SPI_GetIntStatus (LPC_SPI_TypeDef *SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
return ((SPIx->SPINT & SPI_SPINT_INTFLAG) ? SET : RESET);
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Clear SPI interrupt flag.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void SPI_ClearIntPending(LPC_SPI_TypeDef *SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
SPIx->SPINT = SPI_SPINT_INTFLAG;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get current value of SPI Status register in SPIx peripheral.
|
||||
* @param[in] SPIx SPI peripheral selected, should be LPC_SPI
|
||||
* @return Current value of SPI Status register in SPI peripheral.
|
||||
* Note: The return value of this function must be used with
|
||||
* SPI_CheckStatus() to determine current flag status
|
||||
* corresponding to each SPI status type. Because some flags in
|
||||
* SPI Status register will be cleared after reading, the next reading
|
||||
* SPI Status register could not be correct. So this function used to
|
||||
* read SPI status register in one time only, then the return value
|
||||
* used to check all flags.
|
||||
*********************************************************************/
|
||||
uint32_t SPI_GetStatus(LPC_SPI_TypeDef* SPIx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPIx(SPIx));
|
||||
|
||||
return (SPIx->SPSR & SPI_SPSR_BITMASK);
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Checks whether the specified SPI Status flag is set or not
|
||||
* via inputSPIStatus parameter.
|
||||
* @param[in] inputSPIStatus Value to check status of each flag type.
|
||||
* This value is the return value from SPI_GetStatus().
|
||||
* @param[in] SPIStatus Specifies the SPI status flag to check,
|
||||
* should be one of the following:
|
||||
- SPI_STAT_ABRT: Slave abort.
|
||||
- SPI_STAT_MODF: Mode fault.
|
||||
- SPI_STAT_ROVR: Read overrun.
|
||||
- SPI_STAT_WCOL: Write collision.
|
||||
- SPI_STAT_SPIF: SPI transfer complete.
|
||||
* @return The new state of SPIStatus (SET or RESET)
|
||||
*********************************************************************/
|
||||
FlagStatus SPI_CheckStatus (uint32_t inputSPIStatus, uint8_t SPIStatus)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SPI_STAT(SPIStatus));
|
||||
|
||||
return ((inputSPIStatus & SPIStatus) ? SET : RESET);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _SPI */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,694 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_ssp.c 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_ssp.c
|
||||
* @brief Contains all functions support for SSP firmware library on LPC17xx
|
||||
* @version 3.0
|
||||
* @date 18. June. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup SSP
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_ssp.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _SSP
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup SSP_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
static void setSSPclock (LPC_SSP_TypeDef *SSPx, uint32_t target_clock);
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Setup clock rate for SSP device
|
||||
* @param[in] SSPx SSP peripheral definition, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] target_clock : clock of SSP (Hz)
|
||||
* @return None
|
||||
***********************************************************************/
|
||||
static void setSSPclock (LPC_SSP_TypeDef *SSPx, uint32_t target_clock)
|
||||
{
|
||||
uint32_t prescale, cr0_div, cmp_clk, ssp_clk;
|
||||
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
/* The SSP clock is derived from the (main system oscillator / 2),
|
||||
so compute the best divider from that clock */
|
||||
if (SSPx == LPC_SSP0){
|
||||
ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP0);
|
||||
} else if (SSPx == LPC_SSP1) {
|
||||
ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP1);
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Find closest divider to get at or under the target frequency.
|
||||
Use smallest prescale possible and rely on the divider to get
|
||||
the closest target frequency */
|
||||
cr0_div = 0;
|
||||
cmp_clk = 0xFFFFFFFF;
|
||||
prescale = 2;
|
||||
while (cmp_clk > target_clock)
|
||||
{
|
||||
cmp_clk = ssp_clk / ((cr0_div + 1) * prescale);
|
||||
if (cmp_clk > target_clock)
|
||||
{
|
||||
cr0_div++;
|
||||
if (cr0_div > 0xFF)
|
||||
{
|
||||
cr0_div = 0;
|
||||
prescale += 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Write computed prescaler and divider back to register */
|
||||
SSPx->CR0 &= (~SSP_CR0_SCR(0xFF)) & SSP_CR0_BITMASK;
|
||||
SSPx->CR0 |= (SSP_CR0_SCR(cr0_div)) & SSP_CR0_BITMASK;
|
||||
SSPx->CPSR = prescale & SSP_CPSR_BITMASK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup SSP_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Initializes the SSPx peripheral according to the specified
|
||||
* parameters in the SSP_ConfigStruct.
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] SSP_ConfigStruct Pointer to a SSP_CFG_Type structure
|
||||
* that contains the configuration information for the
|
||||
* specified SSP peripheral.
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void SSP_Init(LPC_SSP_TypeDef *SSPx, SSP_CFG_Type *SSP_ConfigStruct)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
if(SSPx == LPC_SSP0) {
|
||||
/* Set up clock and power for SSP0 module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP0, ENABLE);
|
||||
} else if(SSPx == LPC_SSP1) {
|
||||
/* Set up clock and power for SSP1 module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP1, ENABLE);
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Configure SSP, interrupt is disable, LoopBack mode is disable,
|
||||
* SSP is disable, Slave output is disable as default
|
||||
*/
|
||||
tmp = ((SSP_ConfigStruct->CPHA) | (SSP_ConfigStruct->CPOL) \
|
||||
| (SSP_ConfigStruct->FrameFormat) | (SSP_ConfigStruct->Databit))
|
||||
& SSP_CR0_BITMASK;
|
||||
// write back to SSP control register
|
||||
SSPx->CR0 = tmp;
|
||||
|
||||
tmp = SSP_ConfigStruct->Mode & SSP_CR1_BITMASK;
|
||||
// Write back to CR1
|
||||
SSPx->CR1 = tmp;
|
||||
|
||||
// Set clock rate for SSP peripheral
|
||||
setSSPclock(SSPx, SSP_ConfigStruct->ClockRate);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief De-initializes the SSPx peripheral registers to their
|
||||
* default reset values.
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SSP_DeInit(LPC_SSP_TypeDef* SSPx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
if (SSPx == LPC_SSP0){
|
||||
/* Set up clock and power for SSP0 module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP0, DISABLE);
|
||||
} else if (SSPx == LPC_SSP1) {
|
||||
/* Set up clock and power for SSP1 module */
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP1, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Get data size bit selected
|
||||
* @param[in] SSPx pointer to LPC_SSP_TypeDef structure, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @return Data size, could be:
|
||||
* - SSP_DATABIT_4: 4 bit transfer
|
||||
* - SSP_DATABIT_5: 5 bit transfer
|
||||
* ...
|
||||
* - SSP_DATABIT_16: 16 bit transfer
|
||||
*******************************************************************************/
|
||||
uint8_t SSP_GetDataSize(LPC_SSP_TypeDef* SSPx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
return (SSPx->CR0 & (0xF));
|
||||
}
|
||||
|
||||
/*****************************************************************************//**
|
||||
* @brief Fills each SSP_InitStruct member with its default value:
|
||||
* - CPHA = SSP_CPHA_FIRST
|
||||
* - CPOL = SSP_CPOL_HI
|
||||
* - ClockRate = 1000000
|
||||
* - Databit = SSP_DATABIT_8
|
||||
* - Mode = SSP_MASTER_MODE
|
||||
* - FrameFormat = SSP_FRAME_SSP
|
||||
* @param[in] SSP_InitStruct Pointer to a SSP_CFG_Type structure
|
||||
* which will be initialized.
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
void SSP_ConfigStructInit(SSP_CFG_Type *SSP_InitStruct)
|
||||
{
|
||||
SSP_InitStruct->CPHA = SSP_CPHA_FIRST;
|
||||
SSP_InitStruct->CPOL = SSP_CPOL_HI;
|
||||
SSP_InitStruct->ClockRate = 1000000;
|
||||
SSP_InitStruct->Databit = SSP_DATABIT_8;
|
||||
SSP_InitStruct->Mode = SSP_MASTER_MODE;
|
||||
SSP_InitStruct->FrameFormat = SSP_FRAME_SPI;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable or disable SSP peripheral's operation
|
||||
* @param[in] SSPx SSP peripheral, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] NewState New State of SSPx peripheral's operation
|
||||
* @return none
|
||||
**********************************************************************/
|
||||
void SSP_Cmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SSPx->CR1 |= SSP_CR1_SSP_EN;
|
||||
}
|
||||
else
|
||||
{
|
||||
SSPx->CR1 &= (~SSP_CR1_SSP_EN) & SSP_CR1_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable or disable Loop Back mode function in SSP peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] NewState New State of Loop Back mode, should be:
|
||||
* - ENABLE: Enable this function
|
||||
* - DISABLE: Disable this function
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SSP_LoopBackCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SSPx->CR1 |= SSP_CR1_LBM_EN;
|
||||
}
|
||||
else
|
||||
{
|
||||
SSPx->CR1 &= (~SSP_CR1_LBM_EN) & SSP_CR1_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable or disable Slave Output function in SSP peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] NewState New State of Slave Output function, should be:
|
||||
* - ENABLE: Slave Output in normal operation
|
||||
* - DISABLE: Slave Output is disabled. This blocks
|
||||
* SSP controller from driving the transmit data
|
||||
* line (MISO)
|
||||
* Note: This function is available when SSP peripheral in Slave mode
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SSP_SlaveOutputCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SSPx->CR1 &= (~SSP_CR1_SO_DISABLE) & SSP_CR1_BITMASK;
|
||||
}
|
||||
else
|
||||
{
|
||||
SSPx->CR1 |= SSP_CR1_SO_DISABLE;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Transmit a single data through SSPx peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] Data Data to transmit (must be 16 or 8-bit long,
|
||||
* this depend on SSP data bit number configured)
|
||||
* @return none
|
||||
**********************************************************************/
|
||||
void SSP_SendData(LPC_SSP_TypeDef* SSPx, uint16_t Data)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
SSPx->DR = SSP_DR_BITMASK(Data);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Receive a single data from SSPx peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @return Data received (16-bit long)
|
||||
**********************************************************************/
|
||||
uint16_t SSP_ReceiveData(LPC_SSP_TypeDef* SSPx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
return ((uint16_t) (SSP_DR_BITMASK(SSPx->DR)));
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief SSP Read write data function
|
||||
* @param[in] SSPx Pointer to SSP peripheral, should be
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] dataCfg Pointer to a SSP_DATA_SETUP_Type structure that
|
||||
* contains specified information about transmit
|
||||
* data configuration.
|
||||
* @param[in] xfType Transfer type, should be:
|
||||
* - SSP_TRANSFER_POLLING: Polling mode
|
||||
* - SSP_TRANSFER_INTERRUPT: Interrupt mode
|
||||
* @return Actual Data length has been transferred in polling mode.
|
||||
* In interrupt mode, always return (0)
|
||||
* Return (-1) if error.
|
||||
* Note: This function can be used in both master and slave mode.
|
||||
***********************************************************************/
|
||||
int32_t SSP_ReadWrite (LPC_SSP_TypeDef *SSPx, SSP_DATA_SETUP_Type *dataCfg, \
|
||||
SSP_TRANSFER_Type xfType)
|
||||
{
|
||||
uint8_t *rdata8;
|
||||
uint8_t *wdata8;
|
||||
uint16_t *rdata16;
|
||||
uint16_t *wdata16;
|
||||
uint32_t stat;
|
||||
uint32_t tmp;
|
||||
int32_t dataword;
|
||||
|
||||
dataCfg->rx_cnt = 0;
|
||||
dataCfg->tx_cnt = 0;
|
||||
dataCfg->status = 0;
|
||||
|
||||
|
||||
/* Clear all remaining data in RX FIFO */
|
||||
while (SSPx->SR & SSP_SR_RNE){
|
||||
tmp = (uint32_t) SSP_ReceiveData(SSPx);
|
||||
}
|
||||
|
||||
// Clear status
|
||||
SSPx->ICR = SSP_ICR_BITMASK;
|
||||
if(SSP_GetDataSize(SSPx)>SSP_DATABIT_8)
|
||||
dataword = 1;
|
||||
else dataword = 0;
|
||||
|
||||
// Polling mode ----------------------------------------------------------------------
|
||||
if (xfType == SSP_TRANSFER_POLLING){
|
||||
if (dataword == 0){
|
||||
rdata8 = (uint8_t *)dataCfg->rx_data;
|
||||
wdata8 = (uint8_t *)dataCfg->tx_data;
|
||||
} else {
|
||||
rdata16 = (uint16_t *)dataCfg->rx_data;
|
||||
wdata16 = (uint16_t *)dataCfg->tx_data;
|
||||
}
|
||||
while ((dataCfg->tx_cnt < dataCfg->length) || (dataCfg->rx_cnt < dataCfg->length)){
|
||||
if ((SSPx->SR & SSP_SR_TNF) && (dataCfg->tx_cnt < dataCfg->length)){
|
||||
// Write data to buffer
|
||||
if(dataCfg->tx_data == NULL){
|
||||
if (dataword == 0){
|
||||
SSP_SendData(SSPx, 0xFF);
|
||||
dataCfg->tx_cnt++;
|
||||
} else {
|
||||
SSP_SendData(SSPx, 0xFFFF);
|
||||
dataCfg->tx_cnt += 2;
|
||||
}
|
||||
} else {
|
||||
if (dataword == 0){
|
||||
SSP_SendData(SSPx, *wdata8);
|
||||
wdata8++;
|
||||
dataCfg->tx_cnt++;
|
||||
} else {
|
||||
SSP_SendData(SSPx, *wdata16);
|
||||
wdata16++;
|
||||
dataCfg->tx_cnt += 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Check overrun error
|
||||
if ((stat = SSPx->RIS) & SSP_RIS_ROR){
|
||||
// save status and return
|
||||
dataCfg->status = stat | SSP_STAT_ERROR;
|
||||
return (-1);
|
||||
}
|
||||
|
||||
// Check for any data available in RX FIFO
|
||||
while ((SSPx->SR & SSP_SR_RNE) && (dataCfg->rx_cnt < dataCfg->length)){
|
||||
// Read data from SSP data
|
||||
tmp = SSP_ReceiveData(SSPx);
|
||||
|
||||
// Store data to destination
|
||||
if (dataCfg->rx_data != NULL)
|
||||
{
|
||||
if (dataword == 0){
|
||||
*(rdata8) = (uint8_t) tmp;
|
||||
rdata8++;
|
||||
} else {
|
||||
*(rdata16) = (uint16_t) tmp;
|
||||
rdata16++;
|
||||
}
|
||||
}
|
||||
// Increase counter
|
||||
if (dataword == 0){
|
||||
dataCfg->rx_cnt++;
|
||||
} else {
|
||||
dataCfg->rx_cnt += 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// save status
|
||||
dataCfg->status = SSP_STAT_DONE;
|
||||
|
||||
if (dataCfg->tx_data != NULL){
|
||||
return dataCfg->tx_cnt;
|
||||
} else if (dataCfg->rx_data != NULL){
|
||||
return dataCfg->rx_cnt;
|
||||
} else {
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
// Interrupt mode ----------------------------------------------------------------------
|
||||
else if (xfType == SSP_TRANSFER_INTERRUPT){
|
||||
|
||||
while ((SSPx->SR & SSP_SR_TNF) && (dataCfg->tx_cnt < dataCfg->length)){
|
||||
// Write data to buffer
|
||||
if(dataCfg->tx_data == NULL){
|
||||
if (dataword == 0){
|
||||
SSP_SendData(SSPx, 0xFF);
|
||||
dataCfg->tx_cnt++;
|
||||
} else {
|
||||
SSP_SendData(SSPx, 0xFFFF);
|
||||
dataCfg->tx_cnt += 2;
|
||||
}
|
||||
} else {
|
||||
if (dataword == 0){
|
||||
SSP_SendData(SSPx, (*(uint8_t *)((uint32_t)dataCfg->tx_data + dataCfg->tx_cnt)));
|
||||
dataCfg->tx_cnt++;
|
||||
} else {
|
||||
SSP_SendData(SSPx, (*(uint16_t *)((uint32_t)dataCfg->tx_data + dataCfg->tx_cnt)));
|
||||
dataCfg->tx_cnt += 2;
|
||||
}
|
||||
}
|
||||
|
||||
// Check error
|
||||
if ((stat = SSPx->RIS) & SSP_RIS_ROR){
|
||||
// save status and return
|
||||
dataCfg->status = stat | SSP_STAT_ERROR;
|
||||
return (-1);
|
||||
}
|
||||
|
||||
// Check for any data available in RX FIFO
|
||||
while ((SSPx->SR & SSP_SR_RNE) && (dataCfg->rx_cnt < dataCfg->length)){
|
||||
// Read data from SSP data
|
||||
tmp = SSP_ReceiveData(SSPx);
|
||||
|
||||
// Store data to destination
|
||||
if (dataCfg->rx_data != NULL)
|
||||
{
|
||||
if (dataword == 0){
|
||||
*(uint8_t *)((uint32_t)dataCfg->rx_data + dataCfg->rx_cnt) = (uint8_t) tmp;
|
||||
} else {
|
||||
*(uint16_t *)((uint32_t)dataCfg->rx_data + dataCfg->rx_cnt) = (uint16_t) tmp;
|
||||
}
|
||||
}
|
||||
// Increase counter
|
||||
if (dataword == 0){
|
||||
dataCfg->rx_cnt++;
|
||||
} else {
|
||||
dataCfg->rx_cnt += 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// If there more data to sent or receive
|
||||
if ((dataCfg->rx_cnt < dataCfg->length) || (dataCfg->tx_cnt < dataCfg->length)){
|
||||
// Enable all interrupt
|
||||
SSPx->IMSC = SSP_IMSC_BITMASK;
|
||||
} else {
|
||||
// Save status
|
||||
dataCfg->status = SSP_STAT_DONE;
|
||||
}
|
||||
return (0);
|
||||
}
|
||||
|
||||
return (-1);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Checks whether the specified SSP status flag is set or not
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] FlagType Type of flag to check status, should be one
|
||||
* of following:
|
||||
* - SSP_STAT_TXFIFO_EMPTY: TX FIFO is empty
|
||||
* - SSP_STAT_TXFIFO_NOTFULL: TX FIFO is not full
|
||||
* - SSP_STAT_RXFIFO_NOTEMPTY: RX FIFO is not empty
|
||||
* - SSP_STAT_RXFIFO_FULL: RX FIFO is full
|
||||
* - SSP_STAT_BUSY: SSP peripheral is busy
|
||||
* @return New State of specified SSP status flag
|
||||
**********************************************************************/
|
||||
FlagStatus SSP_GetStatus(LPC_SSP_TypeDef* SSPx, uint32_t FlagType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_SSP_STAT(FlagType));
|
||||
|
||||
return ((SSPx->SR & FlagType) ? SET : RESET);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable or disable specified interrupt type in SSP peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] IntType Interrupt type in SSP peripheral, should be:
|
||||
* - SSP_INTCFG_ROR: Receive Overrun interrupt
|
||||
* - SSP_INTCFG_RT: Receive Time out interrupt
|
||||
* - SSP_INTCFG_RX: RX FIFO is at least half full interrupt
|
||||
* - SSP_INTCFG_TX: TX FIFO is at least half empty interrupt
|
||||
* @param[in] NewState New State of specified interrupt type, should be:
|
||||
* - ENABLE: Enable this interrupt type
|
||||
* - DISABLE: Disable this interrupt type
|
||||
* @return None
|
||||
* Note: We can enable/disable multi-interrupt type by OR multi value
|
||||
**********************************************************************/
|
||||
void SSP_IntConfig(LPC_SSP_TypeDef *SSPx, uint32_t IntType, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SSPx->IMSC |= IntType;
|
||||
}
|
||||
else
|
||||
{
|
||||
SSPx->IMSC &= (~IntType) & SSP_IMSC_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether the specified Raw interrupt status flag is
|
||||
* set or not
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] RawIntType Raw Interrupt Type, should be:
|
||||
* - SSP_INTSTAT_RAW_ROR: Receive Overrun interrupt
|
||||
* - SSP_INTSTAT_RAW_RT: Receive Time out interrupt
|
||||
* - SSP_INTSTAT_RAW_RX: RX FIFO is at least half full interrupt
|
||||
* - SSP_INTSTAT_RAW_TX: TX FIFO is at least half empty interrupt
|
||||
* @return New State of specified Raw interrupt status flag in SSP peripheral
|
||||
* Note: Enabling/Disabling specified interrupt in SSP peripheral does not
|
||||
* effect to Raw Interrupt Status flag.
|
||||
**********************************************************************/
|
||||
IntStatus SSP_GetRawIntStatus(LPC_SSP_TypeDef *SSPx, uint32_t RawIntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_SSP_INTSTAT_RAW(RawIntType));
|
||||
|
||||
return ((SSPx->RIS & RawIntType) ? SET : RESET);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get Raw Interrupt Status register
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @return Raw Interrupt Status (RIS) register value
|
||||
**********************************************************************/
|
||||
uint32_t SSP_GetRawIntStatusReg(LPC_SSP_TypeDef *SSPx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
return (SSPx->RIS);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Check whether the specified interrupt status flag is
|
||||
* set or not
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] IntType Raw Interrupt Type, should be:
|
||||
* - SSP_INTSTAT_ROR: Receive Overrun interrupt
|
||||
* - SSP_INTSTAT_RT: Receive Time out interrupt
|
||||
* - SSP_INTSTAT_RX: RX FIFO is at least half full interrupt
|
||||
* - SSP_INTSTAT_TX: TX FIFO is at least half empty interrupt
|
||||
* @return New State of specified interrupt status flag in SSP peripheral
|
||||
* Note: Enabling/Disabling specified interrupt in SSP peripheral effects
|
||||
* to Interrupt Status flag.
|
||||
**********************************************************************/
|
||||
IntStatus SSP_GetIntStatus (LPC_SSP_TypeDef *SSPx, uint32_t IntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_SSP_INTSTAT(IntType));
|
||||
|
||||
return ((SSPx->MIS & IntType) ? SET :RESET);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear specified interrupt pending in SSP peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] IntType Interrupt pending to clear, should be:
|
||||
* - SSP_INTCLR_ROR: clears the "frame was received when
|
||||
* RxFIFO was full" interrupt.
|
||||
* - SSP_INTCLR_RT: clears the "Rx FIFO was not empty and
|
||||
* has not been read for a timeout period" interrupt.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SSP_ClearIntPending(LPC_SSP_TypeDef *SSPx, uint32_t IntType)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_SSP_INTCLR(IntType));
|
||||
|
||||
SSPx->ICR = IntType;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/Disable DMA function for SSP peripheral
|
||||
* @param[in] SSPx SSP peripheral selected, should be:
|
||||
* - LPC_SSP0: SSP0 peripheral
|
||||
* - LPC_SSP1: SSP1 peripheral
|
||||
* @param[in] DMAMode Type of DMA, should be:
|
||||
* - SSP_DMA_TX: DMA for the transmit FIFO
|
||||
* - SSP_DMA_RX: DMA for the Receive FIFO
|
||||
* @param[in] NewState New State of DMA function on SSP peripheral,
|
||||
* should be:
|
||||
* - ENALBE: Enable this function
|
||||
* - DISABLE: Disable this function
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SSP_DMACmd(LPC_SSP_TypeDef *SSPx, uint32_t DMAMode, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_SSPx(SSPx));
|
||||
CHECK_PARAM(PARAM_SSP_DMA(DMAMode));
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
SSPx->DMACR |= DMAMode;
|
||||
}
|
||||
else
|
||||
{
|
||||
SSPx->DMACR &= (~DMAMode) & SSP_DMA_BITMASK;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _SSP */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,193 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_systick.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_systick.c
|
||||
* @brief Contains all functions support for SYSTICK firmware library
|
||||
* on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup SYSTICK
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_systick.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _SYSTICK
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup SYSTICK_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
/*********************************************************************//**
|
||||
* @brief Initial System Tick with using internal CPU clock source
|
||||
* @param[in] time time interval(ms)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SYSTICK_InternalInit(uint32_t time)
|
||||
{
|
||||
uint32_t cclk;
|
||||
float maxtime;
|
||||
|
||||
cclk = SystemCoreClock;
|
||||
/* With internal CPU clock frequency for LPC17xx is 'SystemCoreClock'
|
||||
* And limit 24 bit for RELOAD value
|
||||
* So the maximum time can be set:
|
||||
* 1/SystemCoreClock * (2^24) * 1000 (ms)
|
||||
*/
|
||||
//check time value is available or not
|
||||
maxtime = (1<<24)/(SystemCoreClock / 1000);
|
||||
if(time > maxtime)
|
||||
//Error loop
|
||||
while(1);
|
||||
else
|
||||
{
|
||||
//Select CPU clock is System Tick clock source
|
||||
SysTick->CTRL |= ST_CTRL_CLKSOURCE;
|
||||
/* Set RELOAD value
|
||||
* RELOAD = (SystemCoreClock/1000) * time - 1
|
||||
* with time base is millisecond
|
||||
*/
|
||||
SysTick->LOAD = (cclk/1000)*time - 1;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial System Tick with using external clock source
|
||||
* @param[in] freq external clock frequency(Hz)
|
||||
* @param[in] time time interval(ms)
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SYSTICK_ExternalInit(uint32_t freq, uint32_t time)
|
||||
{
|
||||
float maxtime;
|
||||
|
||||
/* With external clock frequency for LPC17xx is 'freq'
|
||||
* And limit 24 bit for RELOAD value
|
||||
* So the maximum time can be set:
|
||||
* 1/freq * (2^24) * 1000 (ms)
|
||||
*/
|
||||
//check time value is available or not
|
||||
maxtime = (1<<24)/(freq / 1000);
|
||||
if (time>maxtime)
|
||||
//Error Loop
|
||||
while(1);
|
||||
else
|
||||
{
|
||||
//Select external clock is System Tick clock source
|
||||
SysTick->CTRL &= ~ ST_CTRL_CLKSOURCE;
|
||||
/* Set RELOAD value
|
||||
* RELOAD = (freq/1000) * time - 1
|
||||
* with time base is millisecond
|
||||
*/
|
||||
maxtime = (freq/1000)*time - 1;
|
||||
SysTick->LOAD = (freq/1000)*time - 1;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/disable System Tick counter
|
||||
* @param[in] NewState System Tick counter status, should be:
|
||||
* - ENABLE
|
||||
* - DISABLE
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SYSTICK_Cmd(FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if(NewState == ENABLE)
|
||||
//Enable System Tick counter
|
||||
SysTick->CTRL |= ST_CTRL_ENABLE;
|
||||
else
|
||||
//Disable System Tick counter
|
||||
SysTick->CTRL &= ~ST_CTRL_ENABLE;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Enable/disable System Tick interrupt
|
||||
* @param[in] NewState System Tick interrupt status, should be:
|
||||
* - ENABLE
|
||||
* - DISABLE
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SYSTICK_IntCmd(FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
|
||||
|
||||
if(NewState == ENABLE)
|
||||
//Enable System Tick counter
|
||||
SysTick->CTRL |= ST_CTRL_TICKINT;
|
||||
else
|
||||
//Disable System Tick counter
|
||||
SysTick->CTRL &= ~ST_CTRL_TICKINT;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get current value of System Tick counter
|
||||
* @param[in] None
|
||||
* @return current value of System Tick counter
|
||||
**********************************************************************/
|
||||
uint32_t SYSTICK_GetCurrentValue(void)
|
||||
{
|
||||
return (SysTick->VAL);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear Counter flag
|
||||
* @param[in] None
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void SYSTICK_ClearCounterFlag(void)
|
||||
{
|
||||
SysTick->CTRL &= ~ST_CTRL_COUNTFLAG;
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _SYSTICK */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,609 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_timer.c 2011-03-10
|
||||
*//**
|
||||
* @file lpc17xx_timer.c
|
||||
* @brief Contains all functions support for Timer firmware library
|
||||
* on LPC17xx
|
||||
* @version 3.1
|
||||
* @date 10. March. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup TIM
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_timer.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
#include "lpc17xx_pinsel.h"
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
#ifdef _TIM
|
||||
|
||||
/* Private Functions ---------------------------------------------------------- */
|
||||
|
||||
static uint32_t getPClock (uint32_t timernum);
|
||||
static uint32_t converUSecToVal (uint32_t timernum, uint32_t usec);
|
||||
static uint32_t converPtrToTimeNum (LPC_TIM_TypeDef *TIMx);
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get peripheral clock of each timer controller
|
||||
* @param[in] timernum Timer number
|
||||
* @return Peripheral clock of timer
|
||||
**********************************************************************/
|
||||
static uint32_t getPClock (uint32_t timernum)
|
||||
{
|
||||
uint32_t clkdlycnt;
|
||||
switch (timernum)
|
||||
{
|
||||
case 0:
|
||||
clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER0);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER1);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER2);
|
||||
break;
|
||||
|
||||
case 3:
|
||||
clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER3);
|
||||
break;
|
||||
}
|
||||
return clkdlycnt;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Convert a time to a timer count value
|
||||
* @param[in] timernum Timer number
|
||||
* @param[in] usec Time in microseconds
|
||||
* @return The number of required clock ticks to give the time delay
|
||||
**********************************************************************/
|
||||
uint32_t converUSecToVal (uint32_t timernum, uint32_t usec)
|
||||
{
|
||||
uint64_t clkdlycnt;
|
||||
|
||||
// Get Pclock of timer
|
||||
clkdlycnt = (uint64_t) getPClock(timernum);
|
||||
|
||||
clkdlycnt = (clkdlycnt * usec) / 1000000;
|
||||
return (uint32_t) clkdlycnt;
|
||||
}
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Convert a timer register pointer to a timer number
|
||||
* @param[in] TIMx Pointer to LPC_TIM_TypeDef, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @return The timer number (0 to 3) or 0xFFFF FFFF if register pointer is bad
|
||||
**********************************************************************/
|
||||
uint32_t converPtrToTimeNum (LPC_TIM_TypeDef *TIMx)
|
||||
{
|
||||
uint32_t tnum = 0xFFFFFFFF;
|
||||
|
||||
if (TIMx == LPC_TIM0)
|
||||
{
|
||||
tnum = 0;
|
||||
}
|
||||
else if (TIMx == LPC_TIM1)
|
||||
{
|
||||
tnum = 1;
|
||||
}
|
||||
else if (TIMx == LPC_TIM2)
|
||||
{
|
||||
tnum = 2;
|
||||
}
|
||||
else if (TIMx == LPC_TIM3)
|
||||
{
|
||||
tnum = 3;
|
||||
}
|
||||
|
||||
return tnum;
|
||||
}
|
||||
|
||||
/* End of Private Functions ---------------------------------------------------- */
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup TIM_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Get Interrupt Status
|
||||
* @param[in] TIMx Timer selection, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] IntFlag: interrupt type, should be:
|
||||
* - TIM_MR0_INT: Interrupt for Match channel 0
|
||||
* - TIM_MR1_INT: Interrupt for Match channel 1
|
||||
* - TIM_MR2_INT: Interrupt for Match channel 2
|
||||
* - TIM_MR3_INT: Interrupt for Match channel 3
|
||||
* - TIM_CR0_INT: Interrupt for Capture channel 0
|
||||
* - TIM_CR1_INT: Interrupt for Capture channel 1
|
||||
* @return FlagStatus
|
||||
* - SET : interrupt
|
||||
* - RESET : no interrupt
|
||||
**********************************************************************/
|
||||
FlagStatus TIM_GetIntStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
|
||||
{
|
||||
uint8_t temp;
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
|
||||
temp = (TIMx->IR)& TIM_IR_CLR(IntFlag);
|
||||
if (temp)
|
||||
return SET;
|
||||
|
||||
return RESET;
|
||||
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Get Capture Interrupt Status
|
||||
* @param[in] TIMx Timer selection, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] IntFlag: interrupt type, should be:
|
||||
* - TIM_MR0_INT: Interrupt for Match channel 0
|
||||
* - TIM_MR1_INT: Interrupt for Match channel 1
|
||||
* - TIM_MR2_INT: Interrupt for Match channel 2
|
||||
* - TIM_MR3_INT: Interrupt for Match channel 3
|
||||
* - TIM_CR0_INT: Interrupt for Capture channel 0
|
||||
* - TIM_CR1_INT: Interrupt for Capture channel 1
|
||||
* @return FlagStatus
|
||||
* - SET : interrupt
|
||||
* - RESET : no interrupt
|
||||
**********************************************************************/
|
||||
FlagStatus TIM_GetIntCaptureStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
|
||||
{
|
||||
uint8_t temp;
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
|
||||
temp = (TIMx->IR) & (1<<(4+IntFlag));
|
||||
if(temp)
|
||||
return SET;
|
||||
return RESET;
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Clear Interrupt pending
|
||||
* @param[in] TIMx Timer selection, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] IntFlag: interrupt type, should be:
|
||||
* - TIM_MR0_INT: Interrupt for Match channel 0
|
||||
* - TIM_MR1_INT: Interrupt for Match channel 1
|
||||
* - TIM_MR2_INT: Interrupt for Match channel 2
|
||||
* - TIM_MR3_INT: Interrupt for Match channel 3
|
||||
* - TIM_CR0_INT: Interrupt for Capture channel 0
|
||||
* - TIM_CR1_INT: Interrupt for Capture channel 1
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ClearIntPending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
|
||||
TIMx->IR = TIM_IR_CLR(IntFlag);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Clear Capture Interrupt pending
|
||||
* @param[in] TIMx Timer selection, should be
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] IntFlag interrupt type, should be:
|
||||
* - TIM_MR0_INT: Interrupt for Match channel 0
|
||||
* - TIM_MR1_INT: Interrupt for Match channel 1
|
||||
* - TIM_MR2_INT: Interrupt for Match channel 2
|
||||
* - TIM_MR3_INT: Interrupt for Match channel 3
|
||||
* - TIM_CR0_INT: Interrupt for Capture channel 0
|
||||
* - TIM_CR1_INT: Interrupt for Capture channel 1
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ClearIntCapturePending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
|
||||
TIMx->IR = (1<<(4+IntFlag));
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configuration for Timer at initial time
|
||||
* @param[in] TimerCounterMode timer counter mode, should be:
|
||||
* - TIM_TIMER_MODE: Timer mode
|
||||
* - TIM_COUNTER_RISING_MODE: Counter rising mode
|
||||
* - TIM_COUNTER_FALLING_MODE: Counter falling mode
|
||||
* - TIM_COUNTER_ANY_MODE:Counter on both edges
|
||||
* @param[in] TIM_ConfigStruct pointer to TIM_TIMERCFG_Type or
|
||||
* TIM_COUNTERCFG_Type
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ConfigStructInit(TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct)
|
||||
{
|
||||
if (TimerCounterMode == TIM_TIMER_MODE )
|
||||
{
|
||||
TIM_TIMERCFG_Type * pTimeCfg = (TIM_TIMERCFG_Type *)TIM_ConfigStruct;
|
||||
pTimeCfg->PrescaleOption = TIM_PRESCALE_USVAL;
|
||||
pTimeCfg->PrescaleValue = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
TIM_COUNTERCFG_Type * pCounterCfg = (TIM_COUNTERCFG_Type *)TIM_ConfigStruct;
|
||||
pCounterCfg->CountInputSelect = TIM_COUNTER_INCAP0;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial Timer/Counter device
|
||||
* Set Clock frequency for Timer
|
||||
* Set initial configuration for Timer
|
||||
* @param[in] TIMx Timer selection, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] TimerCounterMode Timer counter mode, should be:
|
||||
* - TIM_TIMER_MODE: Timer mode
|
||||
* - TIM_COUNTER_RISING_MODE: Counter rising mode
|
||||
* - TIM_COUNTER_FALLING_MODE: Counter falling mode
|
||||
* - TIM_COUNTER_ANY_MODE:Counter on both edges
|
||||
* @param[in] TIM_ConfigStruct pointer to TIM_TIMERCFG_Type
|
||||
* that contains the configuration information for the
|
||||
* specified Timer peripheral.
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_Init(LPC_TIM_TypeDef *TIMx, TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct)
|
||||
{
|
||||
TIM_TIMERCFG_Type *pTimeCfg;
|
||||
TIM_COUNTERCFG_Type *pCounterCfg;
|
||||
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_MODE_OPT(TimerCounterMode));
|
||||
|
||||
//set power
|
||||
|
||||
if (TIMx== LPC_TIM0)
|
||||
{
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM0, ENABLE);
|
||||
//PCLK_Timer0 = CCLK/4
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER0, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
}
|
||||
else if (TIMx== LPC_TIM1)
|
||||
{
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM1, ENABLE);
|
||||
//PCLK_Timer1 = CCLK/4
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER1, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
|
||||
}
|
||||
|
||||
else if (TIMx== LPC_TIM2)
|
||||
{
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, ENABLE);
|
||||
//PCLK_Timer2= CCLK/4
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER2, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
}
|
||||
else if (TIMx== LPC_TIM3)
|
||||
{
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM3, ENABLE);
|
||||
//PCLK_Timer3= CCLK/4
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER3, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
|
||||
}
|
||||
|
||||
TIMx->CCR &= ~TIM_CTCR_MODE_MASK;
|
||||
TIMx->CCR |= TIM_TIMER_MODE;
|
||||
|
||||
TIMx->TC =0;
|
||||
TIMx->PC =0;
|
||||
TIMx->PR =0;
|
||||
TIMx->TCR |= (1<<1); //Reset Counter
|
||||
TIMx->TCR &= ~(1<<1); //release reset
|
||||
if (TimerCounterMode == TIM_TIMER_MODE )
|
||||
{
|
||||
pTimeCfg = (TIM_TIMERCFG_Type *)TIM_ConfigStruct;
|
||||
if (pTimeCfg->PrescaleOption == TIM_PRESCALE_TICKVAL)
|
||||
{
|
||||
TIMx->PR = pTimeCfg->PrescaleValue -1 ;
|
||||
}
|
||||
else
|
||||
{
|
||||
TIMx->PR = converUSecToVal (converPtrToTimeNum(TIMx),pTimeCfg->PrescaleValue)-1;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
pCounterCfg = (TIM_COUNTERCFG_Type *)TIM_ConfigStruct;
|
||||
TIMx->CCR &= ~TIM_CTCR_INPUT_MASK;
|
||||
if (pCounterCfg->CountInputSelect == TIM_COUNTER_INCAP1)
|
||||
TIMx->CCR |= _BIT(2);
|
||||
}
|
||||
|
||||
// Clear interrupt pending
|
||||
TIMx->IR = 0xFFFFFFFF;
|
||||
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Close Timer/Counter device
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_DeInit (LPC_TIM_TypeDef *TIMx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
// Disable timer/counter
|
||||
TIMx->TCR = 0x00;
|
||||
|
||||
// Disable power
|
||||
if (TIMx== LPC_TIM0)
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM0, DISABLE);
|
||||
|
||||
else if (TIMx== LPC_TIM1)
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM1, DISABLE);
|
||||
|
||||
else if (TIMx== LPC_TIM2)
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, DISABLE);
|
||||
|
||||
else if (TIMx== LPC_TIM3)
|
||||
CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, DISABLE);
|
||||
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Start/Stop Timer/Counter device
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] NewState
|
||||
* - ENABLE : set timer enable
|
||||
* - DISABLE : disable timer
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_Cmd(LPC_TIM_TypeDef *TIMx, FunctionalState NewState)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
if (NewState == ENABLE)
|
||||
{
|
||||
TIMx->TCR |= TIM_ENABLE;
|
||||
}
|
||||
else
|
||||
{
|
||||
TIMx->TCR &= ~TIM_ENABLE;
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Reset Timer/Counter device,
|
||||
* Make TC and PC are synchronously reset on the next
|
||||
* positive edge of PCLK
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ResetCounter(LPC_TIM_TypeDef *TIMx)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
TIMx->TCR |= TIM_RESET;
|
||||
TIMx->TCR &= ~TIM_RESET;
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Configuration for Match register
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] TIM_MatchConfigStruct Pointer to TIM_MATCHCFG_Type
|
||||
* - MatchChannel : choose channel 0 or 1
|
||||
* - IntOnMatch : if SET, interrupt will be generated when MRxx match
|
||||
* the value in TC
|
||||
* - StopOnMatch : if SET, TC and PC will be stopped whenM Rxx match
|
||||
* the value in TC
|
||||
* - ResetOnMatch : if SET, Reset on MR0 when MRxx match
|
||||
* the value in TC
|
||||
* -ExtMatchOutputType: Select output for external match
|
||||
* + 0: Do nothing for external output pin if match
|
||||
* + 1: Force external output pin to low if match
|
||||
* + 2: Force external output pin to high if match
|
||||
* + 3: Toggle external output pin if match
|
||||
* MatchValue: Set the value to be compared with TC value
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ConfigMatch(LPC_TIM_TypeDef *TIMx, TIM_MATCHCFG_Type *TIM_MatchConfigStruct)
|
||||
{
|
||||
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_EXTMATCH_OPT(TIM_MatchConfigStruct->ExtMatchOutputType));
|
||||
|
||||
switch(TIM_MatchConfigStruct->MatchChannel)
|
||||
{
|
||||
case 0:
|
||||
TIMx->MR0 = TIM_MatchConfigStruct->MatchValue;
|
||||
break;
|
||||
case 1:
|
||||
TIMx->MR1 = TIM_MatchConfigStruct->MatchValue;
|
||||
break;
|
||||
case 2:
|
||||
TIMx->MR2 = TIM_MatchConfigStruct->MatchValue;
|
||||
break;
|
||||
case 3:
|
||||
TIMx->MR3 = TIM_MatchConfigStruct->MatchValue;
|
||||
break;
|
||||
default:
|
||||
//Error match value
|
||||
//Error loop
|
||||
while(1);
|
||||
}
|
||||
//interrupt on MRn
|
||||
TIMx->MCR &=~TIM_MCR_CHANNEL_MASKBIT(TIM_MatchConfigStruct->MatchChannel);
|
||||
|
||||
if (TIM_MatchConfigStruct->IntOnMatch)
|
||||
TIMx->MCR |= TIM_INT_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
|
||||
|
||||
//reset on MRn
|
||||
if (TIM_MatchConfigStruct->ResetOnMatch)
|
||||
TIMx->MCR |= TIM_RESET_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
|
||||
|
||||
//stop on MRn
|
||||
if (TIM_MatchConfigStruct->StopOnMatch)
|
||||
TIMx->MCR |= TIM_STOP_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
|
||||
|
||||
// match output type
|
||||
|
||||
TIMx->EMR &= ~TIM_EM_MASK(TIM_MatchConfigStruct->MatchChannel);
|
||||
TIMx->EMR |= TIM_EM_SET(TIM_MatchConfigStruct->MatchChannel,TIM_MatchConfigStruct->ExtMatchOutputType);
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Update Match value
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] MatchChannel Match channel, should be: 0..3
|
||||
* @param[in] MatchValue updated match value
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_UpdateMatchValue(LPC_TIM_TypeDef *TIMx,uint8_t MatchChannel, uint32_t MatchValue)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
switch(MatchChannel)
|
||||
{
|
||||
case 0:
|
||||
TIMx->MR0 = MatchValue;
|
||||
break;
|
||||
case 1:
|
||||
TIMx->MR1 = MatchValue;
|
||||
break;
|
||||
case 2:
|
||||
TIMx->MR2 = MatchValue;
|
||||
break;
|
||||
case 3:
|
||||
TIMx->MR3 = MatchValue;
|
||||
break;
|
||||
default:
|
||||
//Error Loop
|
||||
while(1);
|
||||
}
|
||||
|
||||
}
|
||||
/*********************************************************************//**
|
||||
* @brief Configuration for Capture register
|
||||
* @param[in] TIMx Pointer to timer device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* - CaptureChannel: set the channel to capture data
|
||||
* - RisingEdge : if SET, Capture at rising edge
|
||||
* - FallingEdge : if SET, Capture at falling edge
|
||||
* - IntOnCaption : if SET, Capture generate interrupt
|
||||
* @param[in] TIM_CaptureConfigStruct Pointer to TIM_CAPTURECFG_Type
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void TIM_ConfigCapture(LPC_TIM_TypeDef *TIMx, TIM_CAPTURECFG_Type *TIM_CaptureConfigStruct)
|
||||
{
|
||||
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
TIMx->CCR &= ~TIM_CCR_CHANNEL_MASKBIT(TIM_CaptureConfigStruct->CaptureChannel);
|
||||
|
||||
if (TIM_CaptureConfigStruct->RisingEdge)
|
||||
TIMx->CCR |= TIM_CAP_RISING(TIM_CaptureConfigStruct->CaptureChannel);
|
||||
|
||||
if (TIM_CaptureConfigStruct->FallingEdge)
|
||||
TIMx->CCR |= TIM_CAP_FALLING(TIM_CaptureConfigStruct->CaptureChannel);
|
||||
|
||||
if (TIM_CaptureConfigStruct->IntOnCaption)
|
||||
TIMx->CCR |= TIM_INT_ON_CAP(TIM_CaptureConfigStruct->CaptureChannel);
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Read value of capture register in timer/counter device
|
||||
* @param[in] TIMx Pointer to timer/counter device, should be:
|
||||
* - LPC_TIM0: TIMER0 peripheral
|
||||
* - LPC_TIM1: TIMER1 peripheral
|
||||
* - LPC_TIM2: TIMER2 peripheral
|
||||
* - LPC_TIM3: TIMER3 peripheral
|
||||
* @param[in] CaptureChannel: capture channel number, should be:
|
||||
* - TIM_COUNTER_INCAP0: CAPn.0 input pin for TIMERn
|
||||
* - TIM_COUNTER_INCAP1: CAPn.1 input pin for TIMERn
|
||||
* @return Value of capture register
|
||||
**********************************************************************/
|
||||
uint32_t TIM_GetCaptureValue(LPC_TIM_TypeDef *TIMx, TIM_COUNTER_INPUT_OPT CaptureChannel)
|
||||
{
|
||||
CHECK_PARAM(PARAM_TIMx(TIMx));
|
||||
CHECK_PARAM(PARAM_TIM_COUNTER_INPUT_OPT(CaptureChannel));
|
||||
|
||||
if(CaptureChannel==0)
|
||||
return TIMx->CR0;
|
||||
else
|
||||
return TIMx->CR1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _TIMER */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
File diff suppressed because it is too large
Load diff
|
@ -1,274 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_wdt.c 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_wdt.c
|
||||
* @brief Contains all functions support for WDT firmware library
|
||||
* on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @addtogroup WDT
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc17xx_wdt.h"
|
||||
#include "lpc17xx_clkpwr.h"
|
||||
#include "lpc17xx_pinsel.h"
|
||||
|
||||
|
||||
/* If this source file built with example, the LPC17xx FW library configuration
|
||||
* file in each example directory ("lpc17xx_libcfg.h") must be included,
|
||||
* otherwise the default FW library configuration file must be included instead
|
||||
*/
|
||||
#ifdef __BUILD_WITH_EXAMPLE__
|
||||
#include "lpc17xx_libcfg.h"
|
||||
#else
|
||||
#include "lpc17xx_libcfg_default.h"
|
||||
#endif /* __BUILD_WITH_EXAMPLE__ */
|
||||
|
||||
|
||||
#ifdef _WDT
|
||||
|
||||
/* Private Functions ---------------------------------------------------------- */
|
||||
|
||||
static uint8_t WDT_SetTimeOut (uint8_t clk_source, uint32_t timeout);
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Set WDT time out value and WDT mode
|
||||
* @param[in] clk_source select Clock source for WDT device
|
||||
* @param[in] timeout value of time-out for WDT (us)
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
static uint8_t WDT_SetTimeOut (uint8_t clk_source, uint32_t timeout)
|
||||
{
|
||||
|
||||
uint32_t pclk_wdt = 0;
|
||||
uint32_t tempval = 0;
|
||||
|
||||
switch ((WDT_CLK_OPT) clk_source)
|
||||
{
|
||||
case WDT_CLKSRC_IRC:
|
||||
pclk_wdt = 4000000;
|
||||
// Calculate TC in WDT
|
||||
tempval = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
|
||||
// Check if it valid
|
||||
if (tempval >= WDT_TIMEOUT_MIN)
|
||||
{
|
||||
LPC_WDT->WDTC = tempval;
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case WDT_CLKSRC_PCLK:
|
||||
|
||||
// Get WDT clock with CCLK divider = 4
|
||||
pclk_wdt = SystemCoreClock / 4;
|
||||
// Calculate TC in WDT
|
||||
tempval = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
|
||||
|
||||
if (tempval >= WDT_TIMEOUT_MIN)
|
||||
{
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
LPC_WDT->WDTC = (uint32_t) tempval;
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
// Get WDT clock with CCLK divider = 2
|
||||
pclk_wdt = SystemCoreClock / 2;
|
||||
// Calculate TC in WDT
|
||||
tempval = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
|
||||
|
||||
if (tempval >= WDT_TIMEOUT_MIN)
|
||||
{
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_2);
|
||||
LPC_WDT->WDTC = (uint32_t) tempval;
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
// Get WDT clock with CCLK divider = 1
|
||||
pclk_wdt = SystemCoreClock;
|
||||
// Calculate TC in WDT
|
||||
tempval = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
|
||||
|
||||
if (tempval >= WDT_TIMEOUT_MIN)
|
||||
{
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_1);
|
||||
LPC_WDT->WDTC = (uint32_t) tempval;
|
||||
return SUCCESS;
|
||||
}
|
||||
break ;
|
||||
|
||||
|
||||
case WDT_CLKSRC_RTC:
|
||||
pclk_wdt = 32768;
|
||||
// Calculate TC in WDT
|
||||
tempval = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
|
||||
// Check if it valid
|
||||
if (tempval >= WDT_TIMEOUT_MIN)
|
||||
{
|
||||
LPC_WDT->WDTC = (uint32_t) tempval;
|
||||
return SUCCESS;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
// Error parameter
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* End of Private Functions --------------------------------------------------- */
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @addtogroup WDT_Public_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Initial for Watchdog function
|
||||
* Clock source = RTC ,
|
||||
* @param[in] ClkSrc Select clock source, should be:
|
||||
* - WDT_CLKSRC_IRC: Clock source from Internal RC oscillator
|
||||
* - WDT_CLKSRC_PCLK: Selects the APB peripheral clock (PCLK)
|
||||
* - WDT_CLKSRC_RTC: Selects the RTC oscillator
|
||||
* @param[in] WDTMode WDT mode, should be:
|
||||
* - WDT_MODE_INT_ONLY: Use WDT to generate interrupt only
|
||||
* - WDT_MODE_RESET: Use WDT to generate interrupt and reset MCU
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void WDT_Init (WDT_CLK_OPT ClkSrc, WDT_MODE_OPT WDTMode)
|
||||
{
|
||||
CHECK_PARAM(PARAM_WDT_CLK_OPT(ClkSrc));
|
||||
CHECK_PARAM(PARAM_WDT_MODE_OPT(WDTMode));
|
||||
CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_4);
|
||||
|
||||
//Set clock source
|
||||
LPC_WDT->WDCLKSEL &= ~WDT_WDCLKSEL_MASK;
|
||||
LPC_WDT->WDCLKSEL |= ClkSrc;
|
||||
//Set WDT mode
|
||||
if (WDTMode == WDT_MODE_RESET){
|
||||
LPC_WDT->WDMOD |= WDT_WDMOD(WDTMode);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief Start WDT activity with given timeout value
|
||||
* @param[in] TimeOut WDT reset after timeout if it is not feed
|
||||
* @return None
|
||||
**********************************************************************/
|
||||
void WDT_Start(uint32_t TimeOut)
|
||||
{
|
||||
uint32_t ClkSrc;
|
||||
|
||||
ClkSrc = LPC_WDT->WDCLKSEL;
|
||||
ClkSrc &=WDT_WDCLKSEL_MASK;
|
||||
WDT_SetTimeOut(ClkSrc,TimeOut);
|
||||
//enable watchdog
|
||||
LPC_WDT->WDMOD |= WDT_WDMOD_WDEN;
|
||||
WDT_Feed();
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Read WDT Time out flag
|
||||
* @param[in] None
|
||||
* @return Time out flag status of WDT
|
||||
*********************************************************************/
|
||||
FlagStatus WDT_ReadTimeOutFlag (void)
|
||||
{
|
||||
return ((FlagStatus)((LPC_WDT->WDMOD & WDT_WDMOD_WDTOF) >>2));
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Clear WDT Time out flag
|
||||
* @param[in] None
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void WDT_ClrTimeOutFlag (void)
|
||||
{
|
||||
LPC_WDT->WDMOD &=~WDT_WDMOD_WDTOF;
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Update WDT timeout value and feed
|
||||
* @param[in] TimeOut TimeOut value to be updated
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void WDT_UpdateTimeOut ( uint32_t TimeOut)
|
||||
{
|
||||
uint32_t ClkSrc;
|
||||
ClkSrc = LPC_WDT->WDCLKSEL;
|
||||
ClkSrc &=WDT_WDCLKSEL_MASK;
|
||||
WDT_SetTimeOut(ClkSrc,TimeOut);
|
||||
WDT_Feed();
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief After set WDTEN, call this function to start Watchdog
|
||||
* or reload the Watchdog timer
|
||||
* @param[in] None
|
||||
*
|
||||
* @return None
|
||||
*********************************************************************/
|
||||
void WDT_Feed (void)
|
||||
{
|
||||
// Disable irq interrupt
|
||||
__disable_irq();
|
||||
LPC_WDT->WDFEED = 0xAA;
|
||||
LPC_WDT->WDFEED = 0x55;
|
||||
// Then enable irq interrupt
|
||||
__enable_irq();
|
||||
}
|
||||
|
||||
/********************************************************************//**
|
||||
* @brief Get the current value of WDT
|
||||
* @param[in] None
|
||||
* @return current value of WDT
|
||||
*********************************************************************/
|
||||
uint32_t WDT_GetCurrentCount(void)
|
||||
{
|
||||
return LPC_WDT->WDTV;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* _WDT */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
File diff suppressed because it is too large
Load diff
|
@ -1,35 +0,0 @@
|
|||
/* ----------------------------------------------------------------------
|
||||
* Copyright (C) 2010 ARM Limited. All rights reserved.
|
||||
*
|
||||
* $Date: 11. November 2010
|
||||
* $Revision: V1.0.2
|
||||
*
|
||||
* Project: CMSIS DSP Library
|
||||
* Title: arm_common_tables.h
|
||||
*
|
||||
* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions
|
||||
*
|
||||
* Target Processor: Cortex-M4/Cortex-M3
|
||||
*
|
||||
* Version 1.0.2 2010/11/11
|
||||
* Documentation updated.
|
||||
*
|
||||
* Version 1.0.1 2010/10/05
|
||||
* Production release and review comments incorporated.
|
||||
*
|
||||
* Version 1.0.0 2010/09/20
|
||||
* Production release and review comments incorporated.
|
||||
* -------------------------------------------------------------------- */
|
||||
|
||||
#ifndef _ARM_COMMON_TABLES_H
|
||||
#define _ARM_COMMON_TABLES_H
|
||||
|
||||
#include "arm_math.h"
|
||||
|
||||
extern uint16_t armBitRevTable[256];
|
||||
extern q15_t armRecipTableQ15[64];
|
||||
extern q31_t armRecipTableQ31[64];
|
||||
extern const q31_t realCoefAQ31[1024];
|
||||
extern const q31_t realCoefBQ31[1024];
|
||||
|
||||
#endif /* ARM_COMMON_TABLES_H */
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -1,609 +0,0 @@
|
|||
/**************************************************************************//**
|
||||
* @file core_cmFunc.h
|
||||
* @brief CMSIS Cortex-M Core Function Access Header File
|
||||
* @version V2.10
|
||||
* @date 26. July 2011
|
||||
*
|
||||
* @note
|
||||
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
|
||||
*
|
||||
* @par
|
||||
* ARM Limited (ARM) is supplying this software for use with Cortex-M
|
||||
* processor based microcontrollers. This file can be freely distributed
|
||||
* within development tools that are supporting such ARM based processors.
|
||||
*
|
||||
* @par
|
||||
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
|
||||
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
|
||||
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
|
||||
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
|
||||
*
|
||||
******************************************************************************/
|
||||
|
||||
#ifndef __CORE_CMFUNC_H
|
||||
#define __CORE_CMFUNC_H
|
||||
|
||||
|
||||
/* ########################### Core Function Access ########################### */
|
||||
/** \ingroup CMSIS_Core_FunctionInterface
|
||||
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
|
||||
@{
|
||||
*/
|
||||
|
||||
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
|
||||
/* ARM armcc specific functions */
|
||||
|
||||
#if (__ARMCC_VERSION < 400677)
|
||||
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
|
||||
#endif
|
||||
|
||||
/* intrinsic void __enable_irq(); */
|
||||
/* intrinsic void __disable_irq(); */
|
||||
|
||||
/** \brief Get Control Register
|
||||
|
||||
This function returns the content of the Control Register.
|
||||
|
||||
\return Control Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_CONTROL(void)
|
||||
{
|
||||
register uint32_t __regControl __ASM("control");
|
||||
return(__regControl);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Control Register
|
||||
|
||||
This function writes the given value to the Control Register.
|
||||
|
||||
\param [in] control Control Register value to set
|
||||
*/
|
||||
static __INLINE void __set_CONTROL(uint32_t control)
|
||||
{
|
||||
register uint32_t __regControl __ASM("control");
|
||||
__regControl = control;
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get ISPR Register
|
||||
|
||||
This function returns the content of the ISPR Register.
|
||||
|
||||
\return ISPR Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_IPSR(void)
|
||||
{
|
||||
register uint32_t __regIPSR __ASM("ipsr");
|
||||
return(__regIPSR);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get APSR Register
|
||||
|
||||
This function returns the content of the APSR Register.
|
||||
|
||||
\return APSR Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_APSR(void)
|
||||
{
|
||||
register uint32_t __regAPSR __ASM("apsr");
|
||||
return(__regAPSR);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get xPSR Register
|
||||
|
||||
This function returns the content of the xPSR Register.
|
||||
|
||||
\return xPSR Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_xPSR(void)
|
||||
{
|
||||
register uint32_t __regXPSR __ASM("xpsr");
|
||||
return(__regXPSR);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Process Stack Pointer
|
||||
|
||||
This function returns the current value of the Process Stack Pointer (PSP).
|
||||
|
||||
\return PSP Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_PSP(void)
|
||||
{
|
||||
register uint32_t __regProcessStackPointer __ASM("psp");
|
||||
return(__regProcessStackPointer);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Process Stack Pointer
|
||||
|
||||
This function assigns the given value to the Process Stack Pointer (PSP).
|
||||
|
||||
\param [in] topOfProcStack Process Stack Pointer value to set
|
||||
*/
|
||||
static __INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||
{
|
||||
register uint32_t __regProcessStackPointer __ASM("psp");
|
||||
__regProcessStackPointer = topOfProcStack;
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Main Stack Pointer
|
||||
|
||||
This function returns the current value of the Main Stack Pointer (MSP).
|
||||
|
||||
\return MSP Register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_MSP(void)
|
||||
{
|
||||
register uint32_t __regMainStackPointer __ASM("msp");
|
||||
return(__regMainStackPointer);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Main Stack Pointer
|
||||
|
||||
This function assigns the given value to the Main Stack Pointer (MSP).
|
||||
|
||||
\param [in] topOfMainStack Main Stack Pointer value to set
|
||||
*/
|
||||
static __INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||
{
|
||||
register uint32_t __regMainStackPointer __ASM("msp");
|
||||
__regMainStackPointer = topOfMainStack;
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Priority Mask
|
||||
|
||||
This function returns the current state of the priority mask bit from the Priority Mask Register.
|
||||
|
||||
\return Priority Mask value
|
||||
*/
|
||||
static __INLINE uint32_t __get_PRIMASK(void)
|
||||
{
|
||||
register uint32_t __regPriMask __ASM("primask");
|
||||
return(__regPriMask);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Priority Mask
|
||||
|
||||
This function assigns the given value to the Priority Mask Register.
|
||||
|
||||
\param [in] priMask Priority Mask
|
||||
*/
|
||||
static __INLINE void __set_PRIMASK(uint32_t priMask)
|
||||
{
|
||||
register uint32_t __regPriMask __ASM("primask");
|
||||
__regPriMask = (priMask);
|
||||
}
|
||||
|
||||
|
||||
#if (__CORTEX_M >= 0x03)
|
||||
|
||||
/** \brief Enable FIQ
|
||||
|
||||
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
#define __enable_fault_irq __enable_fiq
|
||||
|
||||
|
||||
/** \brief Disable FIQ
|
||||
|
||||
This function disables FIQ interrupts by setting the F-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
#define __disable_fault_irq __disable_fiq
|
||||
|
||||
|
||||
/** \brief Get Base Priority
|
||||
|
||||
This function returns the current value of the Base Priority register.
|
||||
|
||||
\return Base Priority register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_BASEPRI(void)
|
||||
{
|
||||
register uint32_t __regBasePri __ASM("basepri");
|
||||
return(__regBasePri);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Base Priority
|
||||
|
||||
This function assigns the given value to the Base Priority register.
|
||||
|
||||
\param [in] basePri Base Priority value to set
|
||||
*/
|
||||
static __INLINE void __set_BASEPRI(uint32_t basePri)
|
||||
{
|
||||
register uint32_t __regBasePri __ASM("basepri");
|
||||
__regBasePri = (basePri & 0xff);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Fault Mask
|
||||
|
||||
This function returns the current value of the Fault Mask register.
|
||||
|
||||
\return Fault Mask register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_FAULTMASK(void)
|
||||
{
|
||||
register uint32_t __regFaultMask __ASM("faultmask");
|
||||
return(__regFaultMask);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Fault Mask
|
||||
|
||||
This function assigns the given value to the Fault Mask register.
|
||||
|
||||
\param [in] faultMask Fault Mask value to set
|
||||
*/
|
||||
static __INLINE void __set_FAULTMASK(uint32_t faultMask)
|
||||
{
|
||||
register uint32_t __regFaultMask __ASM("faultmask");
|
||||
__regFaultMask = (faultMask & (uint32_t)1);
|
||||
}
|
||||
|
||||
#endif /* (__CORTEX_M >= 0x03) */
|
||||
|
||||
|
||||
#if (__CORTEX_M == 0x04)
|
||||
|
||||
/** \brief Get FPSCR
|
||||
|
||||
This function returns the current value of the Floating Point Status/Control register.
|
||||
|
||||
\return Floating Point Status/Control register value
|
||||
*/
|
||||
static __INLINE uint32_t __get_FPSCR(void)
|
||||
{
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
register uint32_t __regfpscr __ASM("fpscr");
|
||||
return(__regfpscr);
|
||||
#else
|
||||
return(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set FPSCR
|
||||
|
||||
This function assigns the given value to the Floating Point Status/Control register.
|
||||
|
||||
\param [in] fpscr Floating Point Status/Control value to set
|
||||
*/
|
||||
static __INLINE void __set_FPSCR(uint32_t fpscr)
|
||||
{
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
register uint32_t __regfpscr __ASM("fpscr");
|
||||
__regfpscr = (fpscr);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* (__CORTEX_M == 0x04) */
|
||||
|
||||
|
||||
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
|
||||
/* IAR iccarm specific functions */
|
||||
|
||||
#include <cmsis_iar.h>
|
||||
|
||||
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
|
||||
/* GNU gcc specific functions */
|
||||
|
||||
/** \brief Enable IRQ Interrupts
|
||||
|
||||
This function enables IRQ interrupts by clearing the I-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void)
|
||||
{
|
||||
__ASM volatile ("cpsie i");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Disable IRQ Interrupts
|
||||
|
||||
This function disables IRQ interrupts by setting the I-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void)
|
||||
{
|
||||
__ASM volatile ("cpsid i");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Control Register
|
||||
|
||||
This function returns the content of the Control Register.
|
||||
|
||||
\return Control Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, control" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Control Register
|
||||
|
||||
This function writes the given value to the Control Register.
|
||||
|
||||
\param [in] control Control Register value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control)
|
||||
{
|
||||
__ASM volatile ("MSR control, %0" : : "r" (control) );
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get ISPR Register
|
||||
|
||||
This function returns the content of the ISPR Register.
|
||||
|
||||
\return ISPR Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, ipsr" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get APSR Register
|
||||
|
||||
This function returns the content of the APSR Register.
|
||||
|
||||
\return APSR Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, apsr" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get xPSR Register
|
||||
|
||||
This function returns the content of the xPSR Register.
|
||||
|
||||
\return xPSR Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, xpsr" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Process Stack Pointer
|
||||
|
||||
This function returns the current value of the Process Stack Pointer (PSP).
|
||||
|
||||
\return PSP Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void)
|
||||
{
|
||||
register uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, psp\n" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Process Stack Pointer
|
||||
|
||||
This function assigns the given value to the Process Stack Pointer (PSP).
|
||||
|
||||
\param [in] topOfProcStack Process Stack Pointer value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||
{
|
||||
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) );
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Main Stack Pointer
|
||||
|
||||
This function returns the current value of the Main Stack Pointer (MSP).
|
||||
|
||||
\return MSP Register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void)
|
||||
{
|
||||
register uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, msp\n" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Main Stack Pointer
|
||||
|
||||
This function assigns the given value to the Main Stack Pointer (MSP).
|
||||
|
||||
\param [in] topOfMainStack Main Stack Pointer value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||
{
|
||||
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) );
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Priority Mask
|
||||
|
||||
This function returns the current state of the priority mask bit from the Priority Mask Register.
|
||||
|
||||
\return Priority Mask value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, primask" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Priority Mask
|
||||
|
||||
This function assigns the given value to the Priority Mask Register.
|
||||
|
||||
\param [in] priMask Priority Mask
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask)
|
||||
{
|
||||
__ASM volatile ("MSR primask, %0" : : "r" (priMask) );
|
||||
}
|
||||
|
||||
|
||||
#if (__CORTEX_M >= 0x03)
|
||||
|
||||
/** \brief Enable FIQ
|
||||
|
||||
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void)
|
||||
{
|
||||
__ASM volatile ("cpsie f");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Disable FIQ
|
||||
|
||||
This function disables FIQ interrupts by setting the F-bit in the CPSR.
|
||||
Can only be executed in Privileged modes.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void)
|
||||
{
|
||||
__ASM volatile ("cpsid f");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Base Priority
|
||||
|
||||
This function returns the current value of the Base Priority register.
|
||||
|
||||
\return Base Priority register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Base Priority
|
||||
|
||||
This function assigns the given value to the Base Priority register.
|
||||
|
||||
\param [in] basePri Base Priority value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value)
|
||||
{
|
||||
__ASM volatile ("MSR basepri, %0" : : "r" (value) );
|
||||
}
|
||||
|
||||
|
||||
/** \brief Get Fault Mask
|
||||
|
||||
This function returns the current value of the Fault Mask register.
|
||||
|
||||
\return Fault Mask register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("MRS %0, faultmask" : "=r" (result) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set Fault Mask
|
||||
|
||||
This function assigns the given value to the Fault Mask register.
|
||||
|
||||
\param [in] faultMask Fault Mask value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask)
|
||||
{
|
||||
__ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
|
||||
}
|
||||
|
||||
#endif /* (__CORTEX_M >= 0x03) */
|
||||
|
||||
|
||||
#if (__CORTEX_M == 0x04)
|
||||
|
||||
/** \brief Get FPSCR
|
||||
|
||||
This function returns the current value of the Floating Point Status/Control register.
|
||||
|
||||
\return Floating Point Status/Control register value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void)
|
||||
{
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
|
||||
return(result);
|
||||
#else
|
||||
return(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/** \brief Set FPSCR
|
||||
|
||||
This function assigns the given value to the Floating Point Status/Control register.
|
||||
|
||||
\param [in] fpscr Floating Point Status/Control value to set
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr)
|
||||
{
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
__ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) );
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* (__CORTEX_M == 0x04) */
|
||||
|
||||
|
||||
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
|
||||
/* TASKING carm specific functions */
|
||||
|
||||
/*
|
||||
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||
* Please use "carm -?i" to get an up to date list of all instrinsics,
|
||||
* Including the CMSIS ones.
|
||||
*/
|
||||
|
||||
#endif
|
||||
|
||||
/*@} end of CMSIS_Core_RegAccFunctions */
|
||||
|
||||
|
||||
#endif /* __CORE_CMFUNC_H */
|
|
@ -1,586 +0,0 @@
|
|||
/**************************************************************************//**
|
||||
* @file core_cmInstr.h
|
||||
* @brief CMSIS Cortex-M Core Instruction Access Header File
|
||||
* @version V2.10
|
||||
* @date 19. July 2011
|
||||
*
|
||||
* @note
|
||||
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
|
||||
*
|
||||
* @par
|
||||
* ARM Limited (ARM) is supplying this software for use with Cortex-M
|
||||
* processor based microcontrollers. This file can be freely distributed
|
||||
* within development tools that are supporting such ARM based processors.
|
||||
*
|
||||
* @par
|
||||
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
|
||||
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
|
||||
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
|
||||
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
|
||||
*
|
||||
******************************************************************************/
|
||||
|
||||
#ifndef __CORE_CMINSTR_H
|
||||
#define __CORE_CMINSTR_H
|
||||
|
||||
|
||||
/* ########################## Core Instruction Access ######################### */
|
||||
/** \ingroup CMSIS_Core
|
||||
\defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
|
||||
Access to dedicated instructions
|
||||
@{
|
||||
*/
|
||||
|
||||
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
|
||||
/* ARM armcc specific functions */
|
||||
|
||||
#if (__ARMCC_VERSION < 400677)
|
||||
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
|
||||
#endif
|
||||
|
||||
|
||||
/** \brief No Operation
|
||||
|
||||
No Operation does nothing. This instruction can be used for code alignment purposes.
|
||||
*/
|
||||
#define __NOP __nop
|
||||
|
||||
|
||||
/** \brief Wait For Interrupt
|
||||
|
||||
Wait For Interrupt is a hint instruction that suspends execution
|
||||
until one of a number of events occurs.
|
||||
*/
|
||||
#define __WFI __wfi
|
||||
|
||||
|
||||
/** \brief Wait For Event
|
||||
|
||||
Wait For Event is a hint instruction that permits the processor to enter
|
||||
a low-power state until one of a number of events occurs.
|
||||
*/
|
||||
#define __WFE __wfe
|
||||
|
||||
|
||||
/** \brief Send Event
|
||||
|
||||
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
|
||||
*/
|
||||
#define __SEV __sev
|
||||
|
||||
|
||||
/** \brief Instruction Synchronization Barrier
|
||||
|
||||
Instruction Synchronization Barrier flushes the pipeline in the processor,
|
||||
so that all instructions following the ISB are fetched from cache or
|
||||
memory, after the instruction has been completed.
|
||||
*/
|
||||
#define __ISB() __isb(0xF)
|
||||
|
||||
|
||||
/** \brief Data Synchronization Barrier
|
||||
|
||||
This function acts as a special kind of Data Memory Barrier.
|
||||
It completes when all explicit memory accesses before this instruction complete.
|
||||
*/
|
||||
#define __DSB() __dsb(0xF)
|
||||
|
||||
|
||||
/** \brief Data Memory Barrier
|
||||
|
||||
This function ensures the apparent order of the explicit memory operations before
|
||||
and after the instruction, without ensuring their completion.
|
||||
*/
|
||||
#define __DMB() __dmb(0xF)
|
||||
|
||||
|
||||
/** \brief Reverse byte order (32 bit)
|
||||
|
||||
This function reverses the byte order in integer value.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
#define __REV __rev
|
||||
|
||||
|
||||
/** \brief Reverse byte order (16 bit)
|
||||
|
||||
This function reverses the byte order in two unsigned short values.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
static __INLINE __ASM uint32_t __REV16(uint32_t value)
|
||||
{
|
||||
rev16 r0, r0
|
||||
bx lr
|
||||
}
|
||||
|
||||
|
||||
/** \brief Reverse byte order in signed short value
|
||||
|
||||
This function reverses the byte order in a signed short value with sign extension to integer.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
static __INLINE __ASM int32_t __REVSH(int32_t value)
|
||||
{
|
||||
revsh r0, r0
|
||||
bx lr
|
||||
}
|
||||
|
||||
|
||||
#if (__CORTEX_M >= 0x03)
|
||||
|
||||
/** \brief Reverse bit order of value
|
||||
|
||||
This function reverses the bit order of the given value.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
#define __RBIT __rbit
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (8 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 8 bit value.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint8_t at (*ptr)
|
||||
*/
|
||||
#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (16 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 16 bit values.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint16_t at (*ptr)
|
||||
*/
|
||||
#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (32 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 32 bit values.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint32_t at (*ptr)
|
||||
*/
|
||||
#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
|
||||
|
||||
|
||||
/** \brief STR Exclusive (8 bit)
|
||||
|
||||
This function performs a exclusive STR command for 8 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
#define __STREXB(value, ptr) __strex(value, ptr)
|
||||
|
||||
|
||||
/** \brief STR Exclusive (16 bit)
|
||||
|
||||
This function performs a exclusive STR command for 16 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
#define __STREXH(value, ptr) __strex(value, ptr)
|
||||
|
||||
|
||||
/** \brief STR Exclusive (32 bit)
|
||||
|
||||
This function performs a exclusive STR command for 32 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
#define __STREXW(value, ptr) __strex(value, ptr)
|
||||
|
||||
|
||||
/** \brief Remove the exclusive lock
|
||||
|
||||
This function removes the exclusive lock which is created by LDREX.
|
||||
|
||||
*/
|
||||
#define __CLREX __clrex
|
||||
|
||||
|
||||
/** \brief Signed Saturate
|
||||
|
||||
This function saturates a signed value.
|
||||
|
||||
\param [in] value Value to be saturated
|
||||
\param [in] sat Bit position to saturate to (1..32)
|
||||
\return Saturated value
|
||||
*/
|
||||
#define __SSAT __ssat
|
||||
|
||||
|
||||
/** \brief Unsigned Saturate
|
||||
|
||||
This function saturates an unsigned value.
|
||||
|
||||
\param [in] value Value to be saturated
|
||||
\param [in] sat Bit position to saturate to (0..31)
|
||||
\return Saturated value
|
||||
*/
|
||||
#define __USAT __usat
|
||||
|
||||
|
||||
/** \brief Count leading zeros
|
||||
|
||||
This function counts the number of leading zeros of a data value.
|
||||
|
||||
\param [in] value Value to count the leading zeros
|
||||
\return number of leading zeros in value
|
||||
*/
|
||||
#define __CLZ __clz
|
||||
|
||||
#endif /* (__CORTEX_M >= 0x03) */
|
||||
|
||||
|
||||
|
||||
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
|
||||
/* IAR iccarm specific functions */
|
||||
|
||||
#include <cmsis_iar.h>
|
||||
|
||||
|
||||
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
|
||||
/* GNU gcc specific functions */
|
||||
|
||||
/** \brief No Operation
|
||||
|
||||
No Operation does nothing. This instruction can be used for code alignment purposes.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __NOP(void)
|
||||
{
|
||||
__ASM volatile ("nop");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Wait For Interrupt
|
||||
|
||||
Wait For Interrupt is a hint instruction that suspends execution
|
||||
until one of a number of events occurs.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __WFI(void)
|
||||
{
|
||||
__ASM volatile ("wfi");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Wait For Event
|
||||
|
||||
Wait For Event is a hint instruction that permits the processor to enter
|
||||
a low-power state until one of a number of events occurs.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __WFE(void)
|
||||
{
|
||||
__ASM volatile ("wfe");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Send Event
|
||||
|
||||
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __SEV(void)
|
||||
{
|
||||
__ASM volatile ("sev");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Instruction Synchronization Barrier
|
||||
|
||||
Instruction Synchronization Barrier flushes the pipeline in the processor,
|
||||
so that all instructions following the ISB are fetched from cache or
|
||||
memory, after the instruction has been completed.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __ISB(void)
|
||||
{
|
||||
__ASM volatile ("isb");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Data Synchronization Barrier
|
||||
|
||||
This function acts as a special kind of Data Memory Barrier.
|
||||
It completes when all explicit memory accesses before this instruction complete.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __DSB(void)
|
||||
{
|
||||
__ASM volatile ("dsb");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Data Memory Barrier
|
||||
|
||||
This function ensures the apparent order of the explicit memory operations before
|
||||
and after the instruction, without ensuring their completion.
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __DMB(void)
|
||||
{
|
||||
__ASM volatile ("dmb");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Reverse byte order (32 bit)
|
||||
|
||||
This function reverses the byte order in integer value.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Reverse byte order (16 bit)
|
||||
|
||||
This function reverses the byte order in two unsigned short values.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Reverse byte order in signed short value
|
||||
|
||||
This function reverses the byte order in a signed short value with sign extension to integer.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
#if (__CORTEX_M >= 0x03)
|
||||
|
||||
/** \brief Reverse bit order of value
|
||||
|
||||
This function reverses the bit order of the given value.
|
||||
|
||||
\param [in] value Value to reverse
|
||||
\return Reversed value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (8 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 8 bit value.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint8_t at (*ptr)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr)
|
||||
{
|
||||
uint8_t result;
|
||||
|
||||
__ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (16 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 16 bit values.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint16_t at (*ptr)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr)
|
||||
{
|
||||
uint16_t result;
|
||||
|
||||
__ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief LDR Exclusive (32 bit)
|
||||
|
||||
This function performs a exclusive LDR command for 32 bit values.
|
||||
|
||||
\param [in] ptr Pointer to data
|
||||
\return value of type uint32_t at (*ptr)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief STR Exclusive (8 bit)
|
||||
|
||||
This function performs a exclusive STR command for 8 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief STR Exclusive (16 bit)
|
||||
|
||||
This function performs a exclusive STR command for 16 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief STR Exclusive (32 bit)
|
||||
|
||||
This function performs a exclusive STR command for 32 bit values.
|
||||
|
||||
\param [in] value Value to store
|
||||
\param [in] ptr Pointer to location
|
||||
\return 0 Function succeeded
|
||||
\return 1 Function failed
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
|
||||
/** \brief Remove the exclusive lock
|
||||
|
||||
This function removes the exclusive lock which is created by LDREX.
|
||||
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE void __CLREX(void)
|
||||
{
|
||||
__ASM volatile ("clrex");
|
||||
}
|
||||
|
||||
|
||||
/** \brief Signed Saturate
|
||||
|
||||
This function saturates a signed value.
|
||||
|
||||
\param [in] value Value to be saturated
|
||||
\param [in] sat Bit position to saturate to (1..32)
|
||||
\return Saturated value
|
||||
*/
|
||||
#define __SSAT(ARG1,ARG2) \
|
||||
({ \
|
||||
uint32_t __RES, __ARG1 = (ARG1); \
|
||||
__ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||
__RES; \
|
||||
})
|
||||
|
||||
|
||||
/** \brief Unsigned Saturate
|
||||
|
||||
This function saturates an unsigned value.
|
||||
|
||||
\param [in] value Value to be saturated
|
||||
\param [in] sat Bit position to saturate to (0..31)
|
||||
\return Saturated value
|
||||
*/
|
||||
#define __USAT(ARG1,ARG2) \
|
||||
({ \
|
||||
uint32_t __RES, __ARG1 = (ARG1); \
|
||||
__ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||
__RES; \
|
||||
})
|
||||
|
||||
|
||||
/** \brief Count leading zeros
|
||||
|
||||
This function counts the number of leading zeros of a data value.
|
||||
|
||||
\param [in] value Value to count the leading zeros
|
||||
\return number of leading zeros in value
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value)
|
||||
{
|
||||
uint8_t result;
|
||||
|
||||
__ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
|
||||
return(result);
|
||||
}
|
||||
|
||||
#endif /* (__CORTEX_M >= 0x03) */
|
||||
|
||||
|
||||
|
||||
|
||||
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
|
||||
/* TASKING carm specific functions */
|
||||
|
||||
/*
|
||||
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||
* Please use "carm -?i" to get an up to date list of all intrinsics,
|
||||
* Including the CMSIS ones.
|
||||
*/
|
||||
|
||||
#endif
|
||||
|
||||
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
|
||||
|
||||
#endif /* __CORE_CMINSTR_H */
|
|
@ -1,80 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ debug_frmwrk.h 2010-05-21
|
||||
*//**
|
||||
* @file debug_frmwrk.h
|
||||
* @brief Contains some utilities that used for debugging through UART
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
#ifndef DEBUG_FRMWRK_H_
|
||||
#define DEBUG_FRMWRK_H_
|
||||
|
||||
//#include <stdarg.h>
|
||||
#include "lpc17xx_uart.h"
|
||||
|
||||
#define USED_UART_DEBUG_PORT 0
|
||||
|
||||
#if (USED_UART_DEBUG_PORT==0)
|
||||
#define DEBUG_UART_PORT LPC_UART0
|
||||
#elif (USED_UART_DEBUG_PORT==1)
|
||||
#define DEBUG_UART_PORT LPC_UART1
|
||||
#endif
|
||||
|
||||
#define _DBG(x) _db_msg(DEBUG_UART_PORT, x)
|
||||
#define _DBG_(x) _db_msg_(DEBUG_UART_PORT, x)
|
||||
#define _DBC(x) _db_char(DEBUG_UART_PORT, x)
|
||||
#define _DBD(x) _db_dec(DEBUG_UART_PORT, x)
|
||||
#define _DBD16(x) _db_dec_16(DEBUG_UART_PORT, x)
|
||||
#define _DBD32(x) _db_dec_32(DEBUG_UART_PORT, x)
|
||||
#define _DBH(x) _db_hex(DEBUG_UART_PORT, x)
|
||||
#define _DBH16(x) _db_hex_16(DEBUG_UART_PORT, x)
|
||||
#define _DBH32(x) _db_hex_32(DEBUG_UART_PORT, x)
|
||||
#define _DG _db_get_char(DEBUG_UART_PORT)
|
||||
//void _printf (const char *format, ...);
|
||||
|
||||
extern void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s);
|
||||
extern void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s);
|
||||
extern void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch);
|
||||
extern void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn);
|
||||
extern void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn);
|
||||
extern void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn);
|
||||
extern void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn);
|
||||
extern void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn);
|
||||
extern void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn);
|
||||
extern uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx);
|
||||
|
||||
void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch);
|
||||
void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str);
|
||||
void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str);
|
||||
void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum);
|
||||
void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum);
|
||||
void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum);
|
||||
void UARTPutHex (LPC_UART_TypeDef *UARTx, uint8_t hexnum);
|
||||
void UARTPutHex16 (LPC_UART_TypeDef *UARTx, uint16_t hexnum);
|
||||
void UARTPutHex32 (LPC_UART_TypeDef *UARTx, uint32_t hexnum);
|
||||
uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx);
|
||||
void debug_frmwrk_init(void);
|
||||
|
||||
#endif /* DEBUG_FRMWRK_H_ */
|
|
@ -1,302 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_adc.h 2008-07-27
|
||||
*//**
|
||||
* @file lpc17xx_adc.h
|
||||
* @brief Contains the NXP ABL typedefs for C standard types.
|
||||
* It is intended to be used in ISO C conforming development
|
||||
* environments and checks for this insofar as it is possible
|
||||
* to do so.
|
||||
* @version 2.0
|
||||
* @date 27 Jul. 2008
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2008, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup ADC ADC (Analog-to-Digital Converter)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_ADC_H_
|
||||
#define LPC17XX_ADC_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Private macros ------------------------------------------------------------- */
|
||||
/** @defgroup ADC_Private_Macros ADC Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* -------------------------- BIT DEFINITIONS ----------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC control register
|
||||
**********************************************************************/
|
||||
/** Selects which of the AD0.0:7 pins is (are) to be sampled and converted */
|
||||
#define ADC_CR_CH_SEL(n) ((1UL << n))
|
||||
/** The APB clock (PCLK) is divided by (this value plus one)
|
||||
* to produce the clock for the A/D */
|
||||
#define ADC_CR_CLKDIV(n) ((n<<8))
|
||||
/** Repeated conversions A/D enable bit */
|
||||
#define ADC_CR_BURST ((1UL<<16))
|
||||
/** ADC convert in power down mode */
|
||||
#define ADC_CR_PDN ((1UL<<21))
|
||||
/** Start mask bits */
|
||||
#define ADC_CR_START_MASK ((7UL<<24))
|
||||
/** Select Start Mode */
|
||||
#define ADC_CR_START_MODE_SEL(SEL) ((SEL<<24))
|
||||
/** Start conversion now */
|
||||
#define ADC_CR_START_NOW ((1UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on P2.10/EINT0 */
|
||||
#define ADC_CR_START_EINT0 ((2UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on P1.27/CAP0.1 */
|
||||
#define ADC_CR_START_CAP01 ((3UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on MAT0.1 */
|
||||
#define ADC_CR_START_MAT01 ((4UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on MAT0.3 */
|
||||
#define ADC_CR_START_MAT03 ((5UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on MAT1.0 */
|
||||
#define ADC_CR_START_MAT10 ((6UL<<24))
|
||||
/** Start conversion when the edge selected by bit 27 occurs on MAT1.1 */
|
||||
#define ADC_CR_START_MAT11 ((7UL<<24))
|
||||
/** Start conversion on a falling edge on the selected CAP/MAT signal */
|
||||
#define ADC_CR_EDGE ((1UL<<27))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC Global Data register
|
||||
**********************************************************************/
|
||||
/** When DONE is 1, this field contains result value of ADC conversion */
|
||||
#define ADC_GDR_RESULT(n) (((n>>4)&0xFFF))
|
||||
/** These bits contain the channel from which the LS bits were converted */
|
||||
#define ADC_GDR_CH(n) (((n>>24)&0x7))
|
||||
/** This bit is 1 in burst mode if the results of one or
|
||||
* more conversions was (were) lost */
|
||||
#define ADC_GDR_OVERRUN_FLAG ((1UL<<30))
|
||||
/** This bit is set to 1 when an A/D conversion completes */
|
||||
#define ADC_GDR_DONE_FLAG ((1UL<<31))
|
||||
|
||||
/** This bits is used to mask for Channel */
|
||||
#define ADC_GDR_CH_MASK ((7UL<<24))
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC Interrupt register
|
||||
**********************************************************************/
|
||||
/** These bits allow control over which A/D channels generate
|
||||
* interrupts for conversion completion */
|
||||
#define ADC_INTEN_CH(n) ((1UL<<n))
|
||||
/** When 1, enables the global DONE flag in ADDR to generate an interrupt */
|
||||
#define ADC_INTEN_GLOBAL ((1UL<<8))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC Data register
|
||||
**********************************************************************/
|
||||
/** When DONE is 1, this field contains result value of ADC conversion */
|
||||
#define ADC_DR_RESULT(n) (((n>>4)&0xFFF))
|
||||
/** These bits mirror the OVERRRUN status flags that appear in the
|
||||
* result register for each A/D channel */
|
||||
#define ADC_DR_OVERRUN_FLAG ((1UL<<30))
|
||||
/** This bit is set to 1 when an A/D conversion completes. It is cleared
|
||||
* when this register is read */
|
||||
#define ADC_DR_DONE_FLAG ((1UL<<31))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC Status register
|
||||
**********************************************************************/
|
||||
/** These bits mirror the DONE status flags that appear in the result
|
||||
* register for each A/D channel */
|
||||
#define ADC_STAT_CH_DONE_FLAG(n) ((n&0xFF))
|
||||
/** These bits mirror the OVERRRUN status flags that appear in the
|
||||
* result register for each A/D channel */
|
||||
#define ADC_STAT_CH_OVERRUN_FLAG(n) (((n>>8)&0xFF))
|
||||
/** This bit is the A/D interrupt flag */
|
||||
#define ADC_STAT_INT_FLAG ((1UL<<16))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for ADC Trim register
|
||||
**********************************************************************/
|
||||
/** Offset trim bits for ADC operation */
|
||||
#define ADC_ADCOFFS(n) (((n&0xF)<<4))
|
||||
/** Written to boot code*/
|
||||
#define ADC_TRIM(n) (((n&0xF)<<8))
|
||||
|
||||
/* ------------------- CHECK PARAM DEFINITIONS ------------------------- */
|
||||
/** Check ADC parameter */
|
||||
#define PARAM_ADCx(n) (((uint32_t *)n)==((uint32_t *)LPC_ADC))
|
||||
|
||||
/** Check ADC state parameter */
|
||||
#define PARAM_ADC_START_ON_EDGE_OPT(OPT) ((OPT == ADC_START_ON_RISING)||(OPT == ADC_START_ON_FALLING))
|
||||
|
||||
/** Check ADC state parameter */
|
||||
#define PARAM_ADC_DATA_STATUS(OPT) ((OPT== ADC_DATA_BURST)||(OPT== ADC_DATA_DONE))
|
||||
|
||||
/** Check ADC rate parameter */
|
||||
#define PARAM_ADC_RATE(rate) ((rate>0)&&(rate<=200000))
|
||||
|
||||
/** Check ADC channel selection parameter */
|
||||
#define PARAM_ADC_CHANNEL_SELECTION(SEL) ((SEL == ADC_CHANNEL_0)||(ADC_CHANNEL_1)\
|
||||
||(SEL == ADC_CHANNEL_2)|(ADC_CHANNEL_3)\
|
||||
||(SEL == ADC_CHANNEL_4)||(ADC_CHANNEL_5)\
|
||||
||(SEL == ADC_CHANNEL_6)||(ADC_CHANNEL_7))
|
||||
|
||||
/** Check ADC start option parameter */
|
||||
#define PARAM_ADC_START_OPT(OPT) ((OPT == ADC_START_CONTINUOUS)||(OPT == ADC_START_NOW)\
|
||||
||(OPT == ADC_START_ON_EINT0)||(OPT == ADC_START_ON_CAP01)\
|
||||
||(OPT == ADC_START_ON_MAT01)||(OPT == ADC_START_ON_MAT03)\
|
||||
||(OPT == ADC_START_ON_MAT10)||(OPT == ADC_START_ON_MAT11))
|
||||
|
||||
/** Check ADC interrupt type parameter */
|
||||
#define PARAM_ADC_TYPE_INT_OPT(OPT) ((OPT == ADC_ADINTEN0)||(OPT == ADC_ADINTEN1)\
|
||||
||(OPT == ADC_ADINTEN2)||(OPT == ADC_ADINTEN3)\
|
||||
||(OPT == ADC_ADINTEN4)||(OPT == ADC_ADINTEN5)\
|
||||
||(OPT == ADC_ADINTEN6)||(OPT == ADC_ADINTEN7)\
|
||||
||(OPT == ADC_ADGINTEN))
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup ADC_Public_Types ADC Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* @brief ADC enumeration
|
||||
**********************************************************************/
|
||||
/** @brief Channel Selection */
|
||||
typedef enum
|
||||
{
|
||||
ADC_CHANNEL_0 = 0, /*!< Channel 0 */
|
||||
ADC_CHANNEL_1, /*!< Channel 1 */
|
||||
ADC_CHANNEL_2, /*!< Channel 2 */
|
||||
ADC_CHANNEL_3, /*!< Channel 3 */
|
||||
ADC_CHANNEL_4, /*!< Channel 4 */
|
||||
ADC_CHANNEL_5, /*!< Channel 5 */
|
||||
ADC_CHANNEL_6, /*!< Channel 6 */
|
||||
ADC_CHANNEL_7 /*!< Channel 7 */
|
||||
}ADC_CHANNEL_SELECTION;
|
||||
|
||||
/** @brief Type of start option */
|
||||
typedef enum
|
||||
{
|
||||
ADC_START_CONTINUOUS =0, /*!< Continuous mode */
|
||||
ADC_START_NOW, /*!< Start conversion now */
|
||||
ADC_START_ON_EINT0, /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on P2.10/EINT0 */
|
||||
ADC_START_ON_CAP01, /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on P1.27/CAP0.1 */
|
||||
ADC_START_ON_MAT01, /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on MAT0.1 */
|
||||
ADC_START_ON_MAT03, /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on MAT0.3 */
|
||||
ADC_START_ON_MAT10, /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on MAT1.0 */
|
||||
ADC_START_ON_MAT11 /*!< Start conversion when the edge selected
|
||||
* by bit 27 occurs on MAT1.1 */
|
||||
} ADC_START_OPT;
|
||||
|
||||
|
||||
/** @brief Type of edge when start conversion on the selected CAP/MAT signal */
|
||||
typedef enum
|
||||
{
|
||||
ADC_START_ON_RISING = 0, /*!< Start conversion on a rising edge
|
||||
*on the selected CAP/MAT signal */
|
||||
ADC_START_ON_FALLING /*!< Start conversion on a falling edge
|
||||
*on the selected CAP/MAT signal */
|
||||
} ADC_START_ON_EDGE_OPT;
|
||||
|
||||
/** @brief* ADC type interrupt enum */
|
||||
typedef enum
|
||||
{
|
||||
ADC_ADINTEN0 = 0, /*!< Interrupt channel 0 */
|
||||
ADC_ADINTEN1, /*!< Interrupt channel 1 */
|
||||
ADC_ADINTEN2, /*!< Interrupt channel 2 */
|
||||
ADC_ADINTEN3, /*!< Interrupt channel 3 */
|
||||
ADC_ADINTEN4, /*!< Interrupt channel 4 */
|
||||
ADC_ADINTEN5, /*!< Interrupt channel 5 */
|
||||
ADC_ADINTEN6, /*!< Interrupt channel 6 */
|
||||
ADC_ADINTEN7, /*!< Interrupt channel 7 */
|
||||
ADC_ADGINTEN /*!< Individual channel/global flag done generate an interrupt */
|
||||
}ADC_TYPE_INT_OPT;
|
||||
|
||||
/** @brief ADC Data status */
|
||||
typedef enum
|
||||
{
|
||||
ADC_DATA_BURST = 0, /*Burst bit*/
|
||||
ADC_DATA_DONE /*Done bit*/
|
||||
}ADC_DATA_STATUS;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup ADC_Public_Functions ADC Public Functions
|
||||
* @{
|
||||
*/
|
||||
/* Init/DeInit ADC peripheral ----------------*/
|
||||
void ADC_Init(LPC_ADC_TypeDef *ADCx, uint32_t rate);
|
||||
void ADC_DeInit(LPC_ADC_TypeDef *ADCx);
|
||||
|
||||
/* Enable/Disable ADC functions --------------*/
|
||||
void ADC_BurstCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState);
|
||||
void ADC_PowerdownCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState);
|
||||
void ADC_StartCmd(LPC_ADC_TypeDef *ADCx, uint8_t start_mode);
|
||||
void ADC_ChannelCmd (LPC_ADC_TypeDef *ADCx, uint8_t Channel, FunctionalState NewState);
|
||||
|
||||
/* Configure ADC functions -------------------*/
|
||||
void ADC_EdgeStartConfig(LPC_ADC_TypeDef *ADCx, uint8_t EdgeOption);
|
||||
void ADC_IntConfig (LPC_ADC_TypeDef *ADCx, ADC_TYPE_INT_OPT IntType, FunctionalState NewState);
|
||||
|
||||
/* Get ADC information functions -------------------*/
|
||||
uint16_t ADC_ChannelGetData(LPC_ADC_TypeDef *ADCx, uint8_t channel);
|
||||
FlagStatus ADC_ChannelGetStatus(LPC_ADC_TypeDef *ADCx, uint8_t channel, uint32_t StatusType);
|
||||
uint32_t ADC_GlobalGetData(LPC_ADC_TypeDef *ADCx);
|
||||
FlagStatus ADC_GlobalGetStatus(LPC_ADC_TypeDef *ADCx, uint32_t StatusType);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* LPC17XX_ADC_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,872 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_can.h 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_can.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for CAN firmware library on LPC17xx
|
||||
* @version 3.0
|
||||
* @date 18. June. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup CAN CAN (Control Area Network)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_CAN_H_
|
||||
#define LPC17XX_CAN_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup CAN_Public_Macros CAN Public Macros
|
||||
* @{
|
||||
*/
|
||||
#define MSG_ENABLE ((uint8_t)(0))
|
||||
#define MSG_DISABLE ((uint8_t)(1))
|
||||
#define CAN1_CTRL ((uint8_t)(0))
|
||||
#define CAN2_CTRL ((uint8_t)(1))
|
||||
#define PARAM_FULLCAN_IC(n) ((n==FULLCAN_IC0)||(n==FULLCAN_IC1))
|
||||
#define ID_11 1
|
||||
#define MAX_HW_FULLCAN_OBJ 64
|
||||
#define MAX_SW_FULLCAN_OBJ 32
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup CAN_Private_Macros CAN Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Mode Register
|
||||
**********************************************************************/
|
||||
/** CAN Reset mode */
|
||||
#define CAN_MOD_RM ((uint32_t)(1))
|
||||
/** CAN Listen Only Mode */
|
||||
#define CAN_MOD_LOM ((uint32_t)(1<<1))
|
||||
/** CAN Self Test mode */
|
||||
#define CAN_MOD_STM ((uint32_t)(1<<2))
|
||||
/** CAN Transmit Priority mode */
|
||||
#define CAN_MOD_TPM ((uint32_t)(1<<3))
|
||||
/** CAN Sleep mode */
|
||||
#define CAN_MOD_SM ((uint32_t)(1<<4))
|
||||
/** CAN Receive Polarity mode */
|
||||
#define CAN_MOD_RPM ((uint32_t)(1<<5))
|
||||
/** CAN Test mode */
|
||||
#define CAN_MOD_TM ((uint32_t)(1<<7))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Command Register
|
||||
**********************************************************************/
|
||||
/** CAN Transmission Request */
|
||||
#define CAN_CMR_TR ((uint32_t)(1))
|
||||
/** CAN Abort Transmission */
|
||||
#define CAN_CMR_AT ((uint32_t)(1<<1))
|
||||
/** CAN Release Receive Buffer */
|
||||
#define CAN_CMR_RRB ((uint32_t)(1<<2))
|
||||
/** CAN Clear Data Overrun */
|
||||
#define CAN_CMR_CDO ((uint32_t)(1<<3))
|
||||
/** CAN Self Reception Request */
|
||||
#define CAN_CMR_SRR ((uint32_t)(1<<4))
|
||||
/** CAN Select Tx Buffer 1 */
|
||||
#define CAN_CMR_STB1 ((uint32_t)(1<<5))
|
||||
/** CAN Select Tx Buffer 2 */
|
||||
#define CAN_CMR_STB2 ((uint32_t)(1<<6))
|
||||
/** CAN Select Tx Buffer 3 */
|
||||
#define CAN_CMR_STB3 ((uint32_t)(1<<7))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Global Status Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Buffer Status */
|
||||
#define CAN_GSR_RBS ((uint32_t)(1))
|
||||
/** CAN Data Overrun Status */
|
||||
#define CAN_GSR_DOS ((uint32_t)(1<<1))
|
||||
/** CAN Transmit Buffer Status */
|
||||
#define CAN_GSR_TBS ((uint32_t)(1<<2))
|
||||
/** CAN Transmit Complete Status */
|
||||
#define CAN_GSR_TCS ((uint32_t)(1<<3))
|
||||
/** CAN Receive Status */
|
||||
#define CAN_GSR_RS ((uint32_t)(1<<4))
|
||||
/** CAN Transmit Status */
|
||||
#define CAN_GSR_TS ((uint32_t)(1<<5))
|
||||
/** CAN Error Status */
|
||||
#define CAN_GSR_ES ((uint32_t)(1<<6))
|
||||
/** CAN Bus Status */
|
||||
#define CAN_GSR_BS ((uint32_t)(1<<7))
|
||||
/** CAN Current value of the Rx Error Counter */
|
||||
#define CAN_GSR_RXERR(n) ((uint32_t)((n&0xFF)<<16))
|
||||
/** CAN Current value of the Tx Error Counter */
|
||||
#define CAN_GSR_TXERR(n) ((uint32_t)(n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Interrupt and Capture Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Interrupt */
|
||||
#define CAN_ICR_RI ((uint32_t)(1))
|
||||
/** CAN Transmit Interrupt 1 */
|
||||
#define CAN_ICR_TI1 ((uint32_t)(1<<1))
|
||||
/** CAN Error Warning Interrupt */
|
||||
#define CAN_ICR_EI ((uint32_t)(1<<2))
|
||||
/** CAN Data Overrun Interrupt */
|
||||
#define CAN_ICR_DOI ((uint32_t)(1<<3))
|
||||
/** CAN Wake-Up Interrupt */
|
||||
#define CAN_ICR_WUI ((uint32_t)(1<<4))
|
||||
/** CAN Error Passive Interrupt */
|
||||
#define CAN_ICR_EPI ((uint32_t)(1<<5))
|
||||
/** CAN Arbitration Lost Interrupt */
|
||||
#define CAN_ICR_ALI ((uint32_t)(1<<6))
|
||||
/** CAN Bus Error Interrupt */
|
||||
#define CAN_ICR_BEI ((uint32_t)(1<<7))
|
||||
/** CAN ID Ready Interrupt */
|
||||
#define CAN_ICR_IDI ((uint32_t)(1<<8))
|
||||
/** CAN Transmit Interrupt 2 */
|
||||
#define CAN_ICR_TI2 ((uint32_t)(1<<9))
|
||||
/** CAN Transmit Interrupt 3 */
|
||||
#define CAN_ICR_TI3 ((uint32_t)(1<<10))
|
||||
/** CAN Error Code Capture */
|
||||
#define CAN_ICR_ERRBIT(n) ((uint32_t)((n&0x1F)<<16))
|
||||
/** CAN Error Direction */
|
||||
#define CAN_ICR_ERRDIR ((uint32_t)(1<<21))
|
||||
/** CAN Error Capture */
|
||||
#define CAN_ICR_ERRC(n) ((uint32_t)((n&0x3)<<22))
|
||||
/** CAN Arbitration Lost Capture */
|
||||
#define CAN_ICR_ALCBIT(n) ((uint32_t)((n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Interrupt Enable Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Interrupt Enable */
|
||||
#define CAN_IER_RIE ((uint32_t)(1))
|
||||
/** CAN Transmit Interrupt Enable for buffer 1 */
|
||||
#define CAN_IER_TIE1 ((uint32_t)(1<<1))
|
||||
/** CAN Error Warning Interrupt Enable */
|
||||
#define CAN_IER_EIE ((uint32_t)(1<<2))
|
||||
/** CAN Data Overrun Interrupt Enable */
|
||||
#define CAN_IER_DOIE ((uint32_t)(1<<3))
|
||||
/** CAN Wake-Up Interrupt Enable */
|
||||
#define CAN_IER_WUIE ((uint32_t)(1<<4))
|
||||
/** CAN Error Passive Interrupt Enable */
|
||||
#define CAN_IER_EPIE ((uint32_t)(1<<5))
|
||||
/** CAN Arbitration Lost Interrupt Enable */
|
||||
#define CAN_IER_ALIE ((uint32_t)(1<<6))
|
||||
/** CAN Bus Error Interrupt Enable */
|
||||
#define CAN_IER_BEIE ((uint32_t)(1<<7))
|
||||
/** CAN ID Ready Interrupt Enable */
|
||||
#define CAN_IER_IDIE ((uint32_t)(1<<8))
|
||||
/** CAN Transmit Enable Interrupt for Buffer 2 */
|
||||
#define CAN_IER_TIE2 ((uint32_t)(1<<9))
|
||||
/** CAN Transmit Enable Interrupt for Buffer 3 */
|
||||
#define CAN_IER_TIE3 ((uint32_t)(1<<10))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Bus Timing Register
|
||||
**********************************************************************/
|
||||
/** CAN Baudrate Prescaler */
|
||||
#define CAN_BTR_BRP(n) ((uint32_t)(n&0x3FF))
|
||||
/** CAN Synchronization Jump Width */
|
||||
#define CAN_BTR_SJM(n) ((uint32_t)((n&0x3)<<14))
|
||||
/** CAN Time Segment 1 */
|
||||
#define CAN_BTR_TESG1(n) ((uint32_t)(n&0xF)<<16))
|
||||
/** CAN Time Segment 2 */
|
||||
#define CAN_BTR_TESG2(n) ((uint32_t)(n&0xF)<<20))
|
||||
/** CAN Sampling */
|
||||
#define CAN_BTR_SAM(n) ((uint32_t)(1<<23))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Error Warning Limit Register
|
||||
**********************************************************************/
|
||||
/** CAN Error Warning Limit */
|
||||
#define CAN_EWL_EWL(n) ((uint32_t)(n&0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Status Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Buffer Status */
|
||||
#define CAN_SR_RBS ((uint32_t)(1))
|
||||
/** CAN Data Overrun Status */
|
||||
#define CAN_SR_DOS ((uint32_t)(1<<1))
|
||||
/** CAN Transmit Buffer Status 1 */
|
||||
#define CAN_SR_TBS1 ((uint32_t)(1<<2))
|
||||
/** CAN Transmission Complete Status of Buffer 1 */
|
||||
#define CAN_SR_TCS1 ((uint32_t)(1<<3))
|
||||
/** CAN Receive Status */
|
||||
#define CAN_SR_RS ((uint32_t)(1<<4))
|
||||
/** CAN Transmit Status 1 */
|
||||
#define CAN_SR_TS1 ((uint32_t)(1<<5))
|
||||
/** CAN Error Status */
|
||||
#define CAN_SR_ES ((uint32_t)(1<<6))
|
||||
/** CAN Bus Status */
|
||||
#define CAN_SR_BS ((uint32_t)(1<<7))
|
||||
/** CAN Transmit Buffer Status 2 */
|
||||
#define CAN_SR_TBS2 ((uint32_t)(1<<10))
|
||||
/** CAN Transmission Complete Status of Buffer 2 */
|
||||
#define CAN_SR_TCS2 ((uint32_t)(1<<11))
|
||||
/** CAN Transmit Status 2 */
|
||||
#define CAN_SR_TS2 ((uint32_t)(1<<13))
|
||||
/** CAN Transmit Buffer Status 2 */
|
||||
#define CAN_SR_TBS3 ((uint32_t)(1<<18))
|
||||
/** CAN Transmission Complete Status of Buffer 2 */
|
||||
#define CAN_SR_TCS3 ((uint32_t)(1<<19))
|
||||
/** CAN Transmit Status 2 */
|
||||
#define CAN_SR_TS3 ((uint32_t)(1<<21))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Receive Frame Status Register
|
||||
**********************************************************************/
|
||||
/** CAN ID Index */
|
||||
#define CAN_RFS_ID_INDEX(n) ((uint32_t)(n&0x3FF))
|
||||
/** CAN Bypass */
|
||||
#define CAN_RFS_BP ((uint32_t)(1<<10))
|
||||
/** CAN Data Length Code */
|
||||
#define CAN_RFS_DLC(n) ((uint32_t)((n&0xF)<<16)
|
||||
/** CAN Remote Transmission Request */
|
||||
#define CAN_RFS_RTR ((uint32_t)(1<<30))
|
||||
/** CAN control 11 bit or 29 bit Identifier */
|
||||
#define CAN_RFS_FF ((uint32_t)(1<<31))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Receive Identifier Register
|
||||
**********************************************************************/
|
||||
/** CAN 11 bit Identifier */
|
||||
#define CAN_RID_ID_11(n) ((uint32_t)(n&0x7FF))
|
||||
/** CAN 29 bit Identifier */
|
||||
#define CAN_RID_ID_29(n) ((uint32_t)(n&0x1FFFFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Receive Data A Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Data 1 */
|
||||
#define CAN_RDA_DATA1(n) ((uint32_t)(n&0xFF))
|
||||
/** CAN Receive Data 2 */
|
||||
#define CAN_RDA_DATA2(n) ((uint32_t)((n&0xFF)<<8))
|
||||
/** CAN Receive Data 3 */
|
||||
#define CAN_RDA_DATA3(n) ((uint32_t)((n&0xFF)<<16))
|
||||
/** CAN Receive Data 4 */
|
||||
#define CAN_RDA_DATA4(n) ((uint32_t)((n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Receive Data B Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Data 5 */
|
||||
#define CAN_RDB_DATA5(n) ((uint32_t)(n&0xFF))
|
||||
/** CAN Receive Data 6 */
|
||||
#define CAN_RDB_DATA6(n) ((uint32_t)((n&0xFF)<<8))
|
||||
/** CAN Receive Data 7 */
|
||||
#define CAN_RDB_DATA7(n) ((uint32_t)((n&0xFF)<<16))
|
||||
/** CAN Receive Data 8 */
|
||||
#define CAN_RDB_DATA8(n) ((uint32_t)((n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Transmit Frame Information Register
|
||||
**********************************************************************/
|
||||
/** CAN Priority */
|
||||
#define CAN_TFI_PRIO(n) ((uint32_t)(n&0xFF))
|
||||
/** CAN Data Length Code */
|
||||
#define CAN_TFI_DLC(n) ((uint32_t)((n&0xF)<<16))
|
||||
/** CAN Remote Frame Transmission */
|
||||
#define CAN_TFI_RTR ((uint32_t)(1<<30))
|
||||
/** CAN control 11-bit or 29-bit Identifier */
|
||||
#define CAN_TFI_FF ((uint32_t)(1<<31))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Transmit Identifier Register
|
||||
**********************************************************************/
|
||||
/** CAN 11-bit Identifier */
|
||||
#define CAN_TID_ID11(n) ((uint32_t)(n&0x7FF))
|
||||
/** CAN 11-bit Identifier */
|
||||
#define CAN_TID_ID29(n) ((uint32_t)(n&0x1FFFFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Transmit Data A Register
|
||||
**********************************************************************/
|
||||
/** CAN Transmit Data 1 */
|
||||
#define CAN_TDA_DATA1(n) ((uint32_t)(n&0xFF))
|
||||
/** CAN Transmit Data 2 */
|
||||
#define CAN_TDA_DATA2(n) ((uint32_t)((n&0xFF)<<8))
|
||||
/** CAN Transmit Data 3 */
|
||||
#define CAN_TDA_DATA3(n) ((uint32_t)((n&0xFF)<<16))
|
||||
/** CAN Transmit Data 4 */
|
||||
#define CAN_TDA_DATA4(n) ((uint32_t)((n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Transmit Data B Register
|
||||
**********************************************************************/
|
||||
/** CAN Transmit Data 5 */
|
||||
#define CAN_TDA_DATA5(n) ((uint32_t)(n&0xFF))
|
||||
/** CAN Transmit Data 6 */
|
||||
#define CAN_TDA_DATA6(n) ((uint32_t)((n&0xFF)<<8))
|
||||
/** CAN Transmit Data 7 */
|
||||
#define CAN_TDA_DATA7(n) ((uint32_t)((n&0xFF)<<16))
|
||||
/** CAN Transmit Data 8 */
|
||||
#define CAN_TDA_DATA8(n) ((uint32_t)((n&0xFF)<<24))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Sleep Clear Register
|
||||
**********************************************************************/
|
||||
/** CAN1 Sleep mode */
|
||||
#define CAN1SLEEPCLR ((uint32_t)(1<<1))
|
||||
/** CAN2 Sleep Mode */
|
||||
#define CAN2SLEEPCLR ((uint32_t)(1<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CAN Wake up Flags Register
|
||||
**********************************************************************/
|
||||
/** CAN1 Sleep mode */
|
||||
#define CAN_WAKEFLAGES_CAN1WAKE ((uint32_t)(1<<1))
|
||||
/** CAN2 Sleep Mode */
|
||||
#define CAN_WAKEFLAGES_CAN2WAKE ((uint32_t)(1<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Central transmit Status Register
|
||||
**********************************************************************/
|
||||
/** CAN Transmit 1 */
|
||||
#define CAN_TSR_TS1 ((uint32_t)(1))
|
||||
/** CAN Transmit 2 */
|
||||
#define CAN_TSR_TS2 ((uint32_t)(1<<1))
|
||||
/** CAN Transmit Buffer Status 1 */
|
||||
#define CAN_TSR_TBS1 ((uint32_t)(1<<8))
|
||||
/** CAN Transmit Buffer Status 2 */
|
||||
#define CAN_TSR_TBS2 ((uint32_t)(1<<9))
|
||||
/** CAN Transmission Complete Status 1 */
|
||||
#define CAN_TSR_TCS1 ((uint32_t)(1<<16))
|
||||
/** CAN Transmission Complete Status 2 */
|
||||
#define CAN_TSR_TCS2 ((uint32_t)(1<<17))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Central Receive Status Register
|
||||
**********************************************************************/
|
||||
/** CAN Receive Status 1 */
|
||||
#define CAN_RSR_RS1 ((uint32_t)(1))
|
||||
/** CAN Receive Status 1 */
|
||||
#define CAN_RSR_RS2 ((uint32_t)(1<<1))
|
||||
/** CAN Receive Buffer Status 1*/
|
||||
#define CAN_RSR_RB1 ((uint32_t)(1<<8))
|
||||
/** CAN Receive Buffer Status 2*/
|
||||
#define CAN_RSR_RB2 ((uint32_t)(1<<9))
|
||||
/** CAN Data Overrun Status 1 */
|
||||
#define CAN_RSR_DOS1 ((uint32_t)(1<<16))
|
||||
/** CAN Data Overrun Status 1 */
|
||||
#define CAN_RSR_DOS2 ((uint32_t)(1<<17))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Central Miscellaneous Status Register
|
||||
**********************************************************************/
|
||||
/** Same CAN Error Status in CAN1GSR */
|
||||
#define CAN_MSR_E1 ((uint32_t)(1))
|
||||
/** Same CAN Error Status in CAN2GSR */
|
||||
#define CAN_MSR_E2 ((uint32_t)(1<<1))
|
||||
/** Same CAN Bus Status in CAN1GSR */
|
||||
#define CAN_MSR_BS1 ((uint32_t)(1<<8))
|
||||
/** Same CAN Bus Status in CAN2GSR */
|
||||
#define CAN_MSR_BS2 ((uint32_t)(1<<9))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Acceptance Filter Mode Register
|
||||
**********************************************************************/
|
||||
/** CAN Acceptance Filter Off mode */
|
||||
#define CAN_AFMR_AccOff ((uint32_t)(1))
|
||||
/** CAN Acceptance File Bypass mode */
|
||||
#define CAN_AFMR_AccBP ((uint32_t)(1<<1))
|
||||
/** FullCAN Mode Enhancements */
|
||||
#define CAN_AFMR_eFCAN ((uint32_t)(1<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Standard Frame Individual Start Address Register
|
||||
**********************************************************************/
|
||||
/** The start address of the table of individual Standard Identifier */
|
||||
#define CAN_STT_sa(n) ((uint32_t)((n&1FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Standard Frame Group Start Address Register
|
||||
**********************************************************************/
|
||||
/** The start address of the table of grouped Standard Identifier */
|
||||
#define CAN_SFF_GRP_sa(n) ((uint32_t)((n&3FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Extended Frame Start Address Register
|
||||
**********************************************************************/
|
||||
/** The start address of the table of individual Extended Identifier */
|
||||
#define CAN_EFF_sa(n) ((uint32_t)((n&1FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Extended Frame Group Start Address Register
|
||||
**********************************************************************/
|
||||
/** The start address of the table of grouped Extended Identifier */
|
||||
#define CAN_Eff_GRP_sa(n) ((uint32_t)((n&3FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for End Of AF Table Register
|
||||
**********************************************************************/
|
||||
/** The End of Table of AF LookUp Table */
|
||||
#define CAN_EndofTable(n) ((uint32_t)((n&3FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for LUT Error Address Register
|
||||
**********************************************************************/
|
||||
/** CAN Look-Up Table Error Address */
|
||||
#define CAN_LUTerrAd(n) ((uint32_t)((n&1FF)<<2))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for LUT Error Register
|
||||
**********************************************************************/
|
||||
/** CAN Look-Up Table Error */
|
||||
#define CAN_LUTerr ((uint32_t)(1))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Global FullCANInterrupt Enable Register
|
||||
**********************************************************************/
|
||||
/** Global FullCANInterrupt Enable */
|
||||
#define CAN_FCANIE ((uint32_t)(1))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for FullCAN Interrupt and Capture Register 0
|
||||
**********************************************************************/
|
||||
/** FullCAN Interrupt and Capture (0-31)*/
|
||||
#define CAN_FCANIC0_IntPnd(n) ((uint32_t)(1<<n))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for FullCAN Interrupt and Capture Register 1
|
||||
**********************************************************************/
|
||||
/** FullCAN Interrupt and Capture (0-31)*/
|
||||
#define CAN_FCANIC1_IntPnd(n) ((uint32_t)(1<<(n-32)))
|
||||
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/** Macro to determine if it is valid CAN peripheral or not */
|
||||
#define PARAM_CANx(x) ((((uint32_t*)x)==((uint32_t *)LPC_CAN1)) \
|
||||
||(((uint32_t*)x)==((uint32_t *)LPC_CAN2)))
|
||||
|
||||
/* Macro to determine if it is valid CANAF or not*/
|
||||
#define PARAM_CANAFx(x) (((uint32_t*)x)== ((uint32_t*)LPC_CANAF))
|
||||
|
||||
/* Macro to determine if it is valid CANAF RAM or not*/
|
||||
#define PARAM_CANAFRAMx(x) (((uint32_t*)x)== (uint32_t*)LPC_CANAF_RAM)
|
||||
|
||||
/* Macro to determine if it is valid CANCR or not*/
|
||||
#define PARAM_CANCRx(x) (((uint32_t*)x)==((uint32_t*)LPC_CANCR))
|
||||
|
||||
/** Macro to check Data to send valid */
|
||||
#define PARAM_I2S_DATA(data) ((data>=0)&&(data <= 0xFFFFFFFF))
|
||||
|
||||
/** Macro to check frequency value */
|
||||
#define PRAM_I2S_FREQ(freq) ((freq>=16000)&&(freq <= 96000))
|
||||
|
||||
/** Macro to check Frame Identifier */
|
||||
#define PARAM_ID_11(n) ((n>>11)==0) /*-- 11 bit --*/
|
||||
#define PARAM_ID_29(n) ((n>>29)==0) /*-- 29 bit --*/
|
||||
|
||||
/** Macro to check DLC value */
|
||||
#define PARAM_DLC(n) ((n>>4)==0) /*-- 4 bit --*/
|
||||
/** Macro to check ID format type */
|
||||
#define PARAM_ID_FORMAT(n) ((n==STD_ID_FORMAT)||(n==EXT_ID_FORMAT))
|
||||
|
||||
/** Macro to check Group identifier */
|
||||
#define PARAM_GRP_ID(x, y) ((x<=y))
|
||||
|
||||
/** Macro to check Frame type */
|
||||
#define PARAM_FRAME_TYPE(n) ((n==DATA_FRAME)||(n==REMOTE_FRAME))
|
||||
|
||||
/** Macro to check Control/Central Status type parameter */
|
||||
#define PARAM_CTRL_STS_TYPE(n) ((n==CANCTRL_GLOBAL_STS)||(n==CANCTRL_INT_CAP) \
|
||||
||(n==CANCTRL_ERR_WRN)||(n==CANCTRL_STS))
|
||||
|
||||
/** Macro to check CR status type */
|
||||
#define PARAM_CR_STS_TYPE(n) ((n==CANCR_TX_STS)||(n==CANCR_RX_STS) \
|
||||
||(n==CANCR_MS))
|
||||
/** Macro to check AF Mode type parameter */
|
||||
#define PARAM_AFMODE_TYPE(n) ((n==CAN_Normal)||(n==CAN_AccOff) \
|
||||
||(n==CAN_AccBP)||(n==CAN_eFCAN))
|
||||
|
||||
/** Macro to check Operation Mode */
|
||||
#define PARAM_MODE_TYPE(n) ((n==CAN_OPERATING_MODE)||(n==CAN_RESET_MODE) \
|
||||
||(n==CAN_LISTENONLY_MODE)||(n==CAN_SELFTEST_MODE) \
|
||||
||(n==CAN_TXPRIORITY_MODE)||(n==CAN_SLEEP_MODE) \
|
||||
||(n==CAN_RXPOLARITY_MODE)||(n==CAN_TEST_MODE))
|
||||
|
||||
/** Macro define for struct AF_Section parameter */
|
||||
#define PARAM_CTRL(n) ((n==CAN1_CTRL)|(n==CAN2_CTRL))
|
||||
|
||||
/** Macro define for struct AF_Section parameter */
|
||||
#define PARAM_MSG_DISABLE(n) ((n==MSG_ENABLE)|(n==MSG_DISABLE))
|
||||
|
||||
/**Macro to check Interrupt Type parameter */
|
||||
#define PARAM_INT_EN_TYPE(n) ((n==CANINT_RIE)||(n==CANINT_TIE1) \
|
||||
||(n==CANINT_EIE)||(n==CANINT_DOIE) \
|
||||
||(n==CANINT_WUIE)||(n==CANINT_EPIE) \
|
||||
||(n==CANINT_ALIE)||(n==CANINT_BEIE) \
|
||||
||(n==CANINT_IDIE)||(n==CANINT_TIE2) \
|
||||
||(n==CANINT_TIE3)||(n==CANINT_FCE))
|
||||
|
||||
/** Macro to check AFLUT Entry type */
|
||||
#define PARAM_AFLUT_ENTRY_TYPE(n) ((n==FULLCAN_ENTRY)||(n==EXPLICIT_STANDARD_ENTRY)\
|
||||
||(n==GROUP_STANDARD_ENTRY)||(n==EXPLICIT_EXTEND_ENTRY) \
|
||||
||(n==GROUP_EXTEND_ENTRY))
|
||||
|
||||
/** Macro to check position */
|
||||
#define PARAM_POSITION(n) (n<512)
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup CAN_Public_Types CAN Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** CAN configuration structure */
|
||||
/***********************************************************************
|
||||
* CAN device configuration commands (IOCTL commands and arguments)
|
||||
**********************************************************************/
|
||||
/**
|
||||
* @brief CAN ID format definition
|
||||
*/
|
||||
typedef enum {
|
||||
STD_ID_FORMAT = 0, /**< Use standard ID format (11 bit ID) */
|
||||
EXT_ID_FORMAT = 1 /**< Use extended ID format (29 bit ID) */
|
||||
} CAN_ID_FORMAT_Type;
|
||||
|
||||
/**
|
||||
* @brief AFLUT Entry type definition
|
||||
*/
|
||||
typedef enum {
|
||||
FULLCAN_ENTRY = 0,
|
||||
EXPLICIT_STANDARD_ENTRY,
|
||||
GROUP_STANDARD_ENTRY,
|
||||
EXPLICIT_EXTEND_ENTRY,
|
||||
GROUP_EXTEND_ENTRY
|
||||
} AFLUT_ENTRY_Type;
|
||||
|
||||
/**
|
||||
* @brief Symbolic names for type of CAN message
|
||||
*/
|
||||
typedef enum {
|
||||
DATA_FRAME = 0, /**< Data frame */
|
||||
REMOTE_FRAME = 1 /**< Remote frame */
|
||||
} CAN_FRAME_Type;
|
||||
|
||||
/**
|
||||
* @brief CAN Control status definition
|
||||
*/
|
||||
typedef enum {
|
||||
CANCTRL_GLOBAL_STS = 0, /**< CAN Global Status */
|
||||
CANCTRL_INT_CAP, /**< CAN Interrupt and Capture */
|
||||
CANCTRL_ERR_WRN, /**< CAN Error Warning Limit */
|
||||
CANCTRL_STS /**< CAN Control Status */
|
||||
} CAN_CTRL_STS_Type;
|
||||
|
||||
/**
|
||||
* @brief Central CAN status type definition
|
||||
*/
|
||||
typedef enum {
|
||||
CANCR_TX_STS = 0, /**< Central CAN Tx Status */
|
||||
CANCR_RX_STS, /**< Central CAN Rx Status */
|
||||
CANCR_MS /**< Central CAN Miscellaneous Status */
|
||||
} CAN_CR_STS_Type;
|
||||
|
||||
/**
|
||||
* @brief FullCAN Interrupt Capture type definition
|
||||
*/
|
||||
typedef enum{
|
||||
FULLCAN_IC0, /**< FullCAN Interrupt and Capture 0 */
|
||||
FULLCAN_IC1 /**< FullCAN Interrupt and Capture 1 */
|
||||
}FullCAN_IC_Type;
|
||||
|
||||
/**
|
||||
* @brief CAN interrupt enable type definition
|
||||
*/
|
||||
typedef enum {
|
||||
CANINT_RIE = 0, /**< CAN Receiver Interrupt Enable */
|
||||
CANINT_TIE1, /**< CAN Transmit Interrupt Enable */
|
||||
CANINT_EIE, /**< CAN Error Warning Interrupt Enable */
|
||||
CANINT_DOIE, /**< CAN Data Overrun Interrupt Enable */
|
||||
CANINT_WUIE, /**< CAN Wake-Up Interrupt Enable */
|
||||
CANINT_EPIE, /**< CAN Error Passive Interrupt Enable */
|
||||
CANINT_ALIE, /**< CAN Arbitration Lost Interrupt Enable */
|
||||
CANINT_BEIE, /**< CAN Bus Error Inter rupt Enable */
|
||||
CANINT_IDIE, /**< CAN ID Ready Interrupt Enable */
|
||||
CANINT_TIE2, /**< CAN Transmit Interrupt Enable for Buffer2 */
|
||||
CANINT_TIE3, /**< CAN Transmit Interrupt Enable for Buffer3 */
|
||||
CANINT_FCE /**< FullCAN Interrupt Enable */
|
||||
} CAN_INT_EN_Type;
|
||||
|
||||
/**
|
||||
* @brief Acceptance Filter Mode type definition
|
||||
*/
|
||||
typedef enum {
|
||||
CAN_Normal = 0, /**< Normal Mode */
|
||||
CAN_AccOff, /**< Acceptance Filter Off Mode */
|
||||
CAN_AccBP, /**< Acceptance Fileter Bypass Mode */
|
||||
CAN_eFCAN /**< FullCAN Mode Enhancement */
|
||||
} CAN_AFMODE_Type;
|
||||
|
||||
/**
|
||||
* @brief CAN Mode Type definition
|
||||
*/
|
||||
typedef enum {
|
||||
CAN_OPERATING_MODE = 0, /**< Operating Mode */
|
||||
CAN_RESET_MODE, /**< Reset Mode */
|
||||
CAN_LISTENONLY_MODE, /**< Listen Only Mode */
|
||||
CAN_SELFTEST_MODE, /**< Seft Test Mode */
|
||||
CAN_TXPRIORITY_MODE, /**< Transmit Priority Mode */
|
||||
CAN_SLEEP_MODE, /**< Sleep Mode */
|
||||
CAN_RXPOLARITY_MODE, /**< Receive Polarity Mode */
|
||||
CAN_TEST_MODE /**< Test Mode */
|
||||
} CAN_MODE_Type;
|
||||
|
||||
/**
|
||||
* @brief Error values that functions can return
|
||||
*/
|
||||
typedef enum {
|
||||
CAN_OK = 1, /**< No error */
|
||||
CAN_OBJECTS_FULL_ERROR, /**< No more rx or tx objects available */
|
||||
CAN_FULL_OBJ_NOT_RCV, /**< Full CAN object not received */
|
||||
CAN_NO_RECEIVE_DATA, /**< No have receive data available */
|
||||
CAN_AF_ENTRY_ERROR, /**< Entry load in AFLUT is unvalid */
|
||||
CAN_CONFLICT_ID_ERROR, /**< Conflict ID occur */
|
||||
CAN_ENTRY_NOT_EXIT_ERROR /**< Entry remove outo AFLUT is not exit */
|
||||
} CAN_ERROR;
|
||||
|
||||
/**
|
||||
* @brief Pin Configuration structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t RD; /**< Serial Inputs, from CAN transceivers, should be:
|
||||
** For CAN1:
|
||||
- CAN_RD1_P0_0: RD pin is on P0.0
|
||||
- CAN_RD1_P0_21 : RD pin is on P0.21
|
||||
** For CAN2:
|
||||
- CAN_RD2_P0_4: RD pin is on P0.4
|
||||
- CAN_RD2_P2_7: RD pin is on P2.7
|
||||
*/
|
||||
uint8_t TD; /**< Serial Outputs, To CAN transceivers, should be:
|
||||
** For CAN1:
|
||||
- CAN_TD1_P0_1: TD pin is on P0.1
|
||||
- CAN_TD1_P0_22: TD pin is on P0.22
|
||||
** For CAN2:
|
||||
- CAN_TD2_P0_5: TD pin is on P0.5
|
||||
- CAN_TD2_P2_8: TD pin is on P2.8
|
||||
*/
|
||||
} CAN_PinCFG_Type;
|
||||
|
||||
/**
|
||||
* @brief CAN message object structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t id; /**< 29 bit identifier, it depend on "format" value
|
||||
- if format = STD_ID_FORMAT, id should be 11 bit identifier
|
||||
- if format = EXT_ID_FORMAT, id should be 29 bit identifier
|
||||
*/
|
||||
uint8_t dataA[4]; /**< Data field A */
|
||||
uint8_t dataB[4]; /**< Data field B */
|
||||
uint8_t len; /**< Length of data field in bytes, should be:
|
||||
- 0000b-0111b: 0-7 bytes
|
||||
- 1xxxb: 8 bytes
|
||||
*/
|
||||
uint8_t format; /**< Identifier Format, should be:
|
||||
- STD_ID_FORMAT: Standard ID - 11 bit format
|
||||
- EXT_ID_FORMAT: Extended ID - 29 bit format
|
||||
*/
|
||||
uint8_t type; /**< Remote Frame transmission, should be:
|
||||
- DATA_FRAME: the number of data bytes called out by the DLC
|
||||
field are send from the CANxTDA and CANxTDB registers
|
||||
- REMOTE_FRAME: Remote Frame is sent
|
||||
*/
|
||||
} CAN_MSG_Type;
|
||||
|
||||
/**
|
||||
* @brief FullCAN Entry structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t controller; /**< CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint8_t disable; /**< Disable bit, should be:
|
||||
- MSG_ENABLE: disable bit = 0
|
||||
- MSG_DISABLE: disable bit = 1
|
||||
*/
|
||||
uint16_t id_11; /**< Standard ID, should be 11-bit value */
|
||||
} FullCAN_Entry;
|
||||
|
||||
/**
|
||||
* @brief Standard ID Frame Format Entry structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t controller; /**< CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint8_t disable; /**< Disable bit, should be:
|
||||
- MSG_ENABLE: disable bit = 0
|
||||
- MSG_DISABLE: disable bit = 1
|
||||
*/
|
||||
uint16_t id_11; /**< Standard ID, should be 11-bit value */
|
||||
} SFF_Entry;
|
||||
|
||||
/**
|
||||
* @brief Group of Standard ID Frame Format Entry structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t controller1; /**< First CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint8_t disable1; /**< First Disable bit, should be:
|
||||
- MSG_ENABLE: disable bit = 0)
|
||||
- MSG_DISABLE: disable bit = 1
|
||||
*/
|
||||
uint16_t lowerID; /**< ID lower bound, should be 11-bit value */
|
||||
uint8_t controller2; /**< Second CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint8_t disable2; /**< Second Disable bit, should be:
|
||||
- MSG_ENABLE: disable bit = 0
|
||||
- MSG_DISABLE: disable bit = 1
|
||||
*/
|
||||
uint16_t upperID; /**< ID upper bound, should be 11-bit value and
|
||||
equal or greater than lowerID
|
||||
*/
|
||||
} SFF_GPR_Entry;
|
||||
|
||||
/**
|
||||
* @brief Extended ID Frame Format Entry structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t controller; /**< CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint32_t ID_29; /**< Extend ID, shoud be 29-bit value */
|
||||
} EFF_Entry;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Group of Extended ID Frame Format Entry structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t controller1; /**< First CAN Controller, should be:
|
||||
- CAN1_CTRL: CAN1 Controller
|
||||
- CAN2_CTRL: CAN2 Controller
|
||||
*/
|
||||
uint8_t controller2; /**< Second Disable bit, should be:
|
||||
- MSG_ENABLE: disable bit = 0(default)
|
||||
- MSG_DISABLE: disable bit = 1
|
||||
*/
|
||||
uint32_t lowerEID; /**< Extended ID lower bound, should be 29-bit value */
|
||||
uint32_t upperEID; /**< Extended ID upper bound, should be 29-bit value */
|
||||
} EFF_GPR_Entry;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Acceptance Filter Section Table structure
|
||||
*/
|
||||
typedef struct {
|
||||
FullCAN_Entry* FullCAN_Sec; /**< The pointer point to FullCAN_Entry */
|
||||
uint8_t FC_NumEntry; /**< FullCAN Entry Number */
|
||||
SFF_Entry* SFF_Sec; /**< The pointer point to SFF_Entry */
|
||||
uint8_t SFF_NumEntry; /**< Standard ID Entry Number */
|
||||
SFF_GPR_Entry* SFF_GPR_Sec; /**< The pointer point to SFF_GPR_Entry */
|
||||
uint8_t SFF_GPR_NumEntry; /**< Group Standard ID Entry Number */
|
||||
EFF_Entry* EFF_Sec; /**< The pointer point to EFF_Entry */
|
||||
uint8_t EFF_NumEntry; /**< Extended ID Entry Number */
|
||||
EFF_GPR_Entry* EFF_GPR_Sec; /**< The pointer point to EFF_GPR_Entry */
|
||||
uint8_t EFF_GPR_NumEntry; /**< Group Extended ID Entry Number */
|
||||
} AF_SectionDef;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup CAN_Public_Functions CAN Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Init/DeInit CAN peripheral -----------*/
|
||||
void CAN_Init(LPC_CAN_TypeDef *CANx, uint32_t baudrate);
|
||||
void CAN_DeInit(LPC_CAN_TypeDef *CANx);
|
||||
|
||||
/* CAN messages functions ---------------*/
|
||||
Status CAN_SendMsg(LPC_CAN_TypeDef *CANx, CAN_MSG_Type *CAN_Msg);
|
||||
Status CAN_ReceiveMsg(LPC_CAN_TypeDef *CANx, CAN_MSG_Type *CAN_Msg);
|
||||
CAN_ERROR FCAN_ReadObj(LPC_CANAF_TypeDef* CANAFx, CAN_MSG_Type *CAN_Msg);
|
||||
|
||||
/* CAN configure functions ---------------*/
|
||||
void CAN_ModeConfig(LPC_CAN_TypeDef* CANx, CAN_MODE_Type mode,
|
||||
FunctionalState NewState);
|
||||
void CAN_SetAFMode(LPC_CANAF_TypeDef* CANAFx, CAN_AFMODE_Type AFmode);
|
||||
void CAN_SetCommand(LPC_CAN_TypeDef* CANx, uint32_t CMRType);
|
||||
|
||||
/* AFLUT functions ---------------------- */
|
||||
CAN_ERROR CAN_SetupAFLUT(LPC_CANAF_TypeDef* CANAFx, AF_SectionDef* AFSection);
|
||||
CAN_ERROR CAN_LoadFullCANEntry(LPC_CAN_TypeDef* CANx, uint16_t ID);
|
||||
CAN_ERROR CAN_LoadExplicitEntry(LPC_CAN_TypeDef* CANx, uint32_t ID,
|
||||
CAN_ID_FORMAT_Type format);
|
||||
CAN_ERROR CAN_LoadGroupEntry(LPC_CAN_TypeDef* CANx, uint32_t lowerID,
|
||||
uint32_t upperID, CAN_ID_FORMAT_Type format);
|
||||
CAN_ERROR CAN_RemoveEntry(AFLUT_ENTRY_Type EntryType, uint16_t position);
|
||||
|
||||
/* CAN interrupt functions -----------------*/
|
||||
void CAN_IRQCmd(LPC_CAN_TypeDef* CANx, CAN_INT_EN_Type arg, FunctionalState NewState);
|
||||
uint32_t CAN_IntGetStatus(LPC_CAN_TypeDef* CANx);
|
||||
|
||||
/* CAN get status functions ----------------*/
|
||||
IntStatus CAN_FullCANIntGetStatus (LPC_CANAF_TypeDef* CANAFx);
|
||||
uint32_t CAN_FullCANPendGetStatus (LPC_CANAF_TypeDef* CANAFx, FullCAN_IC_Type type);
|
||||
uint32_t CAN_GetCTRLStatus(LPC_CAN_TypeDef* CANx, CAN_CTRL_STS_Type arg);
|
||||
uint32_t CAN_GetCRStatus(LPC_CANCR_TypeDef* CANCRx, CAN_CR_STS_Type arg);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_CAN_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,406 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_clkpwr.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_clkpwr.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Clock and Power Control firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup CLKPWR CLKPWR (Clock Power)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_CLKPWR_H_
|
||||
#define LPC17XX_CLKPWR_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup CLKPWR_Public_Macros CLKPWR Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**********************************************************************
|
||||
* Peripheral Clock Selection Definitions
|
||||
**********************************************************************/
|
||||
/** Peripheral clock divider bit position for WDT */
|
||||
#define CLKPWR_PCLKSEL_WDT ((uint32_t)(0))
|
||||
/** Peripheral clock divider bit position for TIMER0 */
|
||||
#define CLKPWR_PCLKSEL_TIMER0 ((uint32_t)(2))
|
||||
/** Peripheral clock divider bit position for TIMER1 */
|
||||
#define CLKPWR_PCLKSEL_TIMER1 ((uint32_t)(4))
|
||||
/** Peripheral clock divider bit position for UART0 */
|
||||
#define CLKPWR_PCLKSEL_UART0 ((uint32_t)(6))
|
||||
/** Peripheral clock divider bit position for UART1 */
|
||||
#define CLKPWR_PCLKSEL_UART1 ((uint32_t)(8))
|
||||
/** Peripheral clock divider bit position for PWM1 */
|
||||
#define CLKPWR_PCLKSEL_PWM1 ((uint32_t)(12))
|
||||
/** Peripheral clock divider bit position for I2C0 */
|
||||
#define CLKPWR_PCLKSEL_I2C0 ((uint32_t)(14))
|
||||
/** Peripheral clock divider bit position for SPI */
|
||||
#define CLKPWR_PCLKSEL_SPI ((uint32_t)(16))
|
||||
/** Peripheral clock divider bit position for SSP1 */
|
||||
#define CLKPWR_PCLKSEL_SSP1 ((uint32_t)(20))
|
||||
/** Peripheral clock divider bit position for DAC */
|
||||
#define CLKPWR_PCLKSEL_DAC ((uint32_t)(22))
|
||||
/** Peripheral clock divider bit position for ADC */
|
||||
#define CLKPWR_PCLKSEL_ADC ((uint32_t)(24))
|
||||
/** Peripheral clock divider bit position for CAN1 */
|
||||
#define CLKPWR_PCLKSEL_CAN1 ((uint32_t)(26))
|
||||
/** Peripheral clock divider bit position for CAN2 */
|
||||
#define CLKPWR_PCLKSEL_CAN2 ((uint32_t)(28))
|
||||
/** Peripheral clock divider bit position for ACF */
|
||||
#define CLKPWR_PCLKSEL_ACF ((uint32_t)(30))
|
||||
/** Peripheral clock divider bit position for QEI */
|
||||
#define CLKPWR_PCLKSEL_QEI ((uint32_t)(32))
|
||||
/** Peripheral clock divider bit position for PCB */
|
||||
#define CLKPWR_PCLKSEL_PCB ((uint32_t)(36))
|
||||
/** Peripheral clock divider bit position for I2C1 */
|
||||
#define CLKPWR_PCLKSEL_I2C1 ((uint32_t)(38))
|
||||
/** Peripheral clock divider bit position for SSP0 */
|
||||
#define CLKPWR_PCLKSEL_SSP0 ((uint32_t)(42))
|
||||
/** Peripheral clock divider bit position for TIMER2 */
|
||||
#define CLKPWR_PCLKSEL_TIMER2 ((uint32_t)(44))
|
||||
/** Peripheral clock divider bit position for TIMER3 */
|
||||
#define CLKPWR_PCLKSEL_TIMER3 ((uint32_t)(46))
|
||||
/** Peripheral clock divider bit position for UART2 */
|
||||
#define CLKPWR_PCLKSEL_UART2 ((uint32_t)(48))
|
||||
/** Peripheral clock divider bit position for UART3 */
|
||||
#define CLKPWR_PCLKSEL_UART3 ((uint32_t)(50))
|
||||
/** Peripheral clock divider bit position for I2C2 */
|
||||
#define CLKPWR_PCLKSEL_I2C2 ((uint32_t)(52))
|
||||
/** Peripheral clock divider bit position for I2S */
|
||||
#define CLKPWR_PCLKSEL_I2S ((uint32_t)(54))
|
||||
/** Peripheral clock divider bit position for RIT */
|
||||
#define CLKPWR_PCLKSEL_RIT ((uint32_t)(58))
|
||||
/** Peripheral clock divider bit position for SYSCON */
|
||||
#define CLKPWR_PCLKSEL_SYSCON ((uint32_t)(60))
|
||||
/** Peripheral clock divider bit position for MC */
|
||||
#define CLKPWR_PCLKSEL_MC ((uint32_t)(62))
|
||||
|
||||
/** Macro for Peripheral Clock Selection register bit values
|
||||
* Note: When CCLK_DIV_8, Peripheral<EFBFBD>s clock is selected to
|
||||
* PCLK_xyz = CCLK/8 except for CAN1, CAN2, and CAN filtering
|
||||
* when <EFBFBD>11<EFBFBD>selects PCLK_xyz = CCLK/6 */
|
||||
/* Peripheral clock divider is set to 4 from CCLK */
|
||||
#define CLKPWR_PCLKSEL_CCLK_DIV_4 ((uint32_t)(0))
|
||||
/** Peripheral clock divider is the same with CCLK */
|
||||
#define CLKPWR_PCLKSEL_CCLK_DIV_1 ((uint32_t)(1))
|
||||
/** Peripheral clock divider is set to 2 from CCLK */
|
||||
#define CLKPWR_PCLKSEL_CCLK_DIV_2 ((uint32_t)(2))
|
||||
|
||||
|
||||
/********************************************************************
|
||||
* Power Control for Peripherals Definitions
|
||||
**********************************************************************/
|
||||
/** Timer/Counter 0 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCTIM0 ((uint32_t)(1<<1))
|
||||
/* Timer/Counter 1 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCTIM1 ((uint32_t)(1<<2))
|
||||
/** UART0 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCUART0 ((uint32_t)(1<<3))
|
||||
/** UART1 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCUART1 ((uint32_t)(1<<4))
|
||||
/** PWM1 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCPWM1 ((uint32_t)(1<<6))
|
||||
/** The I2C0 interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCI2C0 ((uint32_t)(1<<7))
|
||||
/** The SPI interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCSPI ((uint32_t)(1<<8))
|
||||
/** The RTC power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCRTC ((uint32_t)(1<<9))
|
||||
/** The SSP1 interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCSSP1 ((uint32_t)(1<<10))
|
||||
/** A/D converter 0 (ADC0) power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCAD ((uint32_t)(1<<12))
|
||||
/** CAN Controller 1 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCAN1 ((uint32_t)(1<<13))
|
||||
/** CAN Controller 2 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCAN2 ((uint32_t)(1<<14))
|
||||
/** GPIO power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCGPIO ((uint32_t)(1<<15))
|
||||
/** Repetitive Interrupt Timer power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCRIT ((uint32_t)(1<<16))
|
||||
/** Motor Control PWM */
|
||||
#define CLKPWR_PCONP_PCMC ((uint32_t)(1<<17))
|
||||
/** Quadrature Encoder Interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCQEI ((uint32_t)(1<<18))
|
||||
/** The I2C1 interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCI2C1 ((uint32_t)(1<<19))
|
||||
/** The SSP0 interface power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCSSP0 ((uint32_t)(1<<21))
|
||||
/** Timer 2 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCTIM2 ((uint32_t)(1<<22))
|
||||
/** Timer 3 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCTIM3 ((uint32_t)(1<<23))
|
||||
/** UART 2 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCUART2 ((uint32_t)(1<<24))
|
||||
/** UART 3 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCUART3 ((uint32_t)(1<<25))
|
||||
/** I2C interface 2 power/clock control bit */
|
||||
#define CLKPWR_PCONP_PCI2C2 ((uint32_t)(1<<26))
|
||||
/** I2S interface power/clock control bit*/
|
||||
#define CLKPWR_PCONP_PCI2S ((uint32_t)(1<<27))
|
||||
/** GP DMA function power/clock control bit*/
|
||||
#define CLKPWR_PCONP_PCGPDMA ((uint32_t)(1<<29))
|
||||
/** Ethernet block power/clock control bit*/
|
||||
#define CLKPWR_PCONP_PCENET ((uint32_t)(1<<30))
|
||||
/** USB interface power/clock control bit*/
|
||||
#define CLKPWR_PCONP_PCUSB ((uint32_t)(1<<31))
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup CLKPWR_Private_Macros CLKPWR Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Clock Source Select Register
|
||||
**********************************************************************/
|
||||
/** Internal RC oscillator */
|
||||
#define CLKPWR_CLKSRCSEL_CLKSRC_IRC ((uint32_t)(0x00))
|
||||
/** Main oscillator */
|
||||
#define CLKPWR_CLKSRCSEL_CLKSRC_MAINOSC ((uint32_t)(0x01))
|
||||
/** RTC oscillator */
|
||||
#define CLKPWR_CLKSRCSEL_CLKSRC_RTC ((uint32_t)(0x02))
|
||||
/** Clock source selection bit mask */
|
||||
#define CLKPWR_CLKSRCSEL_BITMASK ((uint32_t)(0x03))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Clock Output Configuration Register
|
||||
**********************************************************************/
|
||||
/* Clock Output Configuration register definition */
|
||||
/** Selects the CPU clock as the CLKOUT source */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTSEL_CPU ((uint32_t)(0x00))
|
||||
/** Selects the main oscillator as the CLKOUT source */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTSEL_MAINOSC ((uint32_t)(0x01))
|
||||
/** Selects the Internal RC oscillator as the CLKOUT source */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTSEL_RC ((uint32_t)(0x02))
|
||||
/** Selects the USB clock as the CLKOUT source */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTSEL_USB ((uint32_t)(0x03))
|
||||
/** Selects the RTC oscillator as the CLKOUT source */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTSEL_RTC ((uint32_t)(0x04))
|
||||
/** Integer value to divide the output clock by, minus one */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUTDIV(n) ((uint32_t)((n&0x0F)<<4))
|
||||
/** CLKOUT enable control */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUT_EN ((uint32_t)(1<<8))
|
||||
/** CLKOUT activity indication */
|
||||
#define CLKPWR_CLKOUTCFG_CLKOUT_ACT ((uint32_t)(1<<9))
|
||||
/** Clock source selection bit mask */
|
||||
#define CLKPWR_CLKOUTCFG_BITMASK ((uint32_t)(0x3FF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PPL0 Control Register
|
||||
**********************************************************************/
|
||||
/** PLL 0 control enable */
|
||||
#define CLKPWR_PLL0CON_ENABLE ((uint32_t)(0x01))
|
||||
/** PLL 0 control connect */
|
||||
#define CLKPWR_PLL0CON_CONNECT ((uint32_t)(0x02))
|
||||
/** PLL 0 control bit mask */
|
||||
#define CLKPWR_PLL0CON_BITMASK ((uint32_t)(0x03))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PPL0 Configuration Register
|
||||
**********************************************************************/
|
||||
/** PLL 0 Configuration MSEL field */
|
||||
#define CLKPWR_PLL0CFG_MSEL(n) ((uint32_t)(n&0x7FFF))
|
||||
/** PLL 0 Configuration NSEL field */
|
||||
#define CLKPWR_PLL0CFG_NSEL(n) ((uint32_t)((n<<16)&0xFF0000))
|
||||
/** PLL 0 Configuration bit mask */
|
||||
#define CLKPWR_PLL0CFG_BITMASK ((uint32_t)(0xFF7FFF))
|
||||
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PPL0 Status Register
|
||||
**********************************************************************/
|
||||
/** PLL 0 MSEL value */
|
||||
#define CLKPWR_PLL0STAT_MSEL(n) ((uint32_t)(n&0x7FFF))
|
||||
/** PLL NSEL get value */
|
||||
#define CLKPWR_PLL0STAT_NSEL(n) ((uint32_t)((n>>16)&0xFF))
|
||||
/** PLL status enable bit */
|
||||
#define CLKPWR_PLL0STAT_PLLE ((uint32_t)(1<<24))
|
||||
/** PLL status Connect bit */
|
||||
#define CLKPWR_PLL0STAT_PLLC ((uint32_t)(1<<25))
|
||||
/** PLL status lock */
|
||||
#define CLKPWR_PLL0STAT_PLOCK ((uint32_t)(1<<26))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PPL0 Feed Register
|
||||
**********************************************************************/
|
||||
/** PLL0 Feed bit mask */
|
||||
#define CLKPWR_PLL0FEED_BITMASK ((uint32_t)0xFF)
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PLL1 Control Register
|
||||
**********************************************************************/
|
||||
/** USB PLL control enable */
|
||||
#define CLKPWR_PLL1CON_ENABLE ((uint32_t)(0x01))
|
||||
/** USB PLL control connect */
|
||||
#define CLKPWR_PLL1CON_CONNECT ((uint32_t)(0x02))
|
||||
/** USB PLL control bit mask */
|
||||
#define CLKPWR_PLL1CON_BITMASK ((uint32_t)(0x03))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PLL1 Configuration Register
|
||||
**********************************************************************/
|
||||
/** USB PLL MSEL set value */
|
||||
#define CLKPWR_PLL1CFG_MSEL(n) ((uint32_t)(n&0x1F))
|
||||
/** USB PLL PSEL set value */
|
||||
#define CLKPWR_PLL1CFG_PSEL(n) ((uint32_t)((n&0x03)<<5))
|
||||
/** USB PLL configuration bit mask */
|
||||
#define CLKPWR_PLL1CFG_BITMASK ((uint32_t)(0x7F))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PLL1 Status Register
|
||||
**********************************************************************/
|
||||
/** USB PLL MSEL get value */
|
||||
#define CLKPWR_PLL1STAT_MSEL(n) ((uint32_t)(n&0x1F))
|
||||
/** USB PLL PSEL get value */
|
||||
#define CLKPWR_PLL1STAT_PSEL(n) ((uint32_t)((n>>5)&0x03))
|
||||
/** USB PLL status enable bit */
|
||||
#define CLKPWR_PLL1STAT_PLLE ((uint32_t)(1<<8))
|
||||
/** USB PLL status Connect bit */
|
||||
#define CLKPWR_PLL1STAT_PLLC ((uint32_t)(1<<9))
|
||||
/** USB PLL status lock */
|
||||
#define CLKPWR_PLL1STAT_PLOCK ((uint32_t)(1<<10))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PLL1 Feed Register
|
||||
**********************************************************************/
|
||||
/** PLL1 Feed bit mask */
|
||||
#define CLKPWR_PLL1FEED_BITMASK ((uint32_t)0xFF)
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for CPU Clock Configuration Register
|
||||
**********************************************************************/
|
||||
/** CPU Clock configuration bit mask */
|
||||
#define CLKPWR_CCLKCFG_BITMASK ((uint32_t)(0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for USB Clock Configuration Register
|
||||
**********************************************************************/
|
||||
/** USB Clock Configuration bit mask */
|
||||
#define CLKPWR_USBCLKCFG_BITMASK ((uint32_t)(0x0F))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for IRC Trim Register
|
||||
**********************************************************************/
|
||||
/** IRC Trim bit mask */
|
||||
#define CLKPWR_IRCTRIM_BITMASK ((uint32_t)(0x0F))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Peripheral Clock Selection Register 0 and 1
|
||||
**********************************************************************/
|
||||
/** Peripheral Clock Selection 0 mask bit */
|
||||
#define CLKPWR_PCLKSEL0_BITMASK ((uint32_t)(0xFFF3F3FF))
|
||||
/** Peripheral Clock Selection 1 mask bit */
|
||||
#define CLKPWR_PCLKSEL1_BITMASK ((uint32_t)(0xFCF3F0F3))
|
||||
/** Macro to set peripheral clock of each type
|
||||
* p: position of two bits that hold divider of peripheral clock
|
||||
* n: value of divider of peripheral clock to be set */
|
||||
#define CLKPWR_PCLKSEL_SET(p,n) _SBF(p,n)
|
||||
/** Macro to mask peripheral clock of each type */
|
||||
#define CLKPWR_PCLKSEL_BITMASK(p) _SBF(p,0x03)
|
||||
/** Macro to get peripheral clock of each type */
|
||||
#define CLKPWR_PCLKSEL_GET(p, n) ((uint32_t)((n>>p)&0x03))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Power Mode Control Register
|
||||
**********************************************************************/
|
||||
/** Power mode control bit 0 */
|
||||
#define CLKPWR_PCON_PM0 ((uint32_t)(1<<0))
|
||||
/** Power mode control bit 1 */
|
||||
#define CLKPWR_PCON_PM1 ((uint32_t)(1<<1))
|
||||
/** Brown-Out Reduced Power Mode */
|
||||
#define CLKPWR_PCON_BODPDM ((uint32_t)(1<<2))
|
||||
/** Brown-Out Global Disable */
|
||||
#define CLKPWR_PCON_BOGD ((uint32_t)(1<<3))
|
||||
/** Brown Out Reset Disable */
|
||||
#define CLKPWR_PCON_BORD ((uint32_t)(1<<4))
|
||||
/** Sleep Mode entry flag */
|
||||
#define CLKPWR_PCON_SMFLAG ((uint32_t)(1<<8))
|
||||
/** Deep Sleep entry flag */
|
||||
#define CLKPWR_PCON_DSFLAG ((uint32_t)(1<<9))
|
||||
/** Power-down entry flag */
|
||||
#define CLKPWR_PCON_PDFLAG ((uint32_t)(1<<10))
|
||||
/** Deep Power-down entry flag */
|
||||
#define CLKPWR_PCON_DPDFLAG ((uint32_t)(1<<11))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Power Control for Peripheral Register
|
||||
**********************************************************************/
|
||||
/** Power Control for Peripherals bit mask */
|
||||
#define CLKPWR_PCONP_BITMASK 0xEFEFF7DE
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup CLKPWR_Public_Functions CLKPWR Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void CLKPWR_SetPCLKDiv (uint32_t ClkType, uint32_t DivVal);
|
||||
uint32_t CLKPWR_GetPCLKSEL (uint32_t ClkType);
|
||||
uint32_t CLKPWR_GetPCLK (uint32_t ClkType);
|
||||
void CLKPWR_ConfigPPWR (uint32_t PPType, FunctionalState NewState);
|
||||
void CLKPWR_Sleep(void);
|
||||
void CLKPWR_DeepSleep(void);
|
||||
void CLKPWR_PowerDown(void);
|
||||
void CLKPWR_DeepPowerDown(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_CLKPWR_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,154 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_dac.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_dac.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Clock and Power Control firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup DAC DAC (Digital-to-Analog Controller)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_DAC_H_
|
||||
#define LPC17XX_DAC_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup DAC_Private_Macros DAC Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** After the selected settling time after this field is written with a
|
||||
new VALUE, the voltage on the AOUT pin (with respect to VSSA)
|
||||
is VALUE/1024 × VREF */
|
||||
#define DAC_VALUE(n) ((uint32_t)((n&0x3FF)<<6))
|
||||
/** If this bit = 0: The settling time of the DAC is 1 microsecond max,
|
||||
* and the maximum current is 700 microAmpere
|
||||
* If this bit = 1: The settling time of the DAC is 2.5 microsecond
|
||||
* and the maximum current is 350 microAmpere */
|
||||
#define DAC_BIAS_EN ((uint32_t)(1<<16))
|
||||
/** Value to reload interrupt DMA counter */
|
||||
#define DAC_CCNT_VALUE(n) ((uint32_t)(n&0xffff))
|
||||
|
||||
/** DCAR double buffering */
|
||||
#define DAC_DBLBUF_ENA ((uint32_t)(1<<1))
|
||||
/** DCAR Time out count enable */
|
||||
#define DAC_CNT_ENA ((uint32_t)(1<<2))
|
||||
/** DCAR DMA access */
|
||||
#define DAC_DMA_ENA ((uint32_t)(1<<3))
|
||||
/** DCAR DACCTRL mask bit */
|
||||
#define DAC_DACCTRL_MASK ((uint32_t)(0x0F))
|
||||
|
||||
/** Macro to determine if it is valid DAC peripheral */
|
||||
#define PARAM_DACx(n) (((uint32_t *)n)==((uint32_t *)LPC_DAC))
|
||||
|
||||
/** Macro to check DAC current optional parameter */
|
||||
#define PARAM_DAC_CURRENT_OPT(OPTION) ((OPTION == DAC_MAX_CURRENT_700uA)\
|
||||
||(OPTION == DAC_MAX_CURRENT_350uA))
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup DAC_Public_Types DAC Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Current option in DAC configuration option */
|
||||
typedef enum
|
||||
{
|
||||
DAC_MAX_CURRENT_700uA = 0, /*!< The settling time of the DAC is 1 us max,
|
||||
and the maximum current is 700 uA */
|
||||
DAC_MAX_CURRENT_350uA /*!< The settling time of the DAC is 2.5 us
|
||||
and the maximum current is 350 uA */
|
||||
} DAC_CURRENT_OPT;
|
||||
|
||||
/**
|
||||
* @brief Configuration for DAC converter control register */
|
||||
typedef struct
|
||||
{
|
||||
|
||||
uint8_t DBLBUF_ENA; /**<
|
||||
-0: Disable DACR double buffering
|
||||
-1: when bit CNT_ENA, enable DACR double buffering feature
|
||||
*/
|
||||
uint8_t CNT_ENA; /*!<
|
||||
-0: Time out counter is disable
|
||||
-1: Time out conter is enable
|
||||
*/
|
||||
uint8_t DMA_ENA; /*!<
|
||||
-0: DMA access is disable
|
||||
-1: DMA burst request
|
||||
*/
|
||||
uint8_t RESERVED;
|
||||
|
||||
} DAC_CONVERTER_CFG_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup DAC_Public_Functions DAC Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void DAC_Init(LPC_DAC_TypeDef *DACx);
|
||||
void DAC_UpdateValue (LPC_DAC_TypeDef *DACx, uint32_t dac_value);
|
||||
void DAC_SetBias (LPC_DAC_TypeDef *DACx,uint32_t bias);
|
||||
void DAC_ConfigDAConverterControl (LPC_DAC_TypeDef *DACx,DAC_CONVERTER_CFG_Type *DAC_ConverterConfigStruct);
|
||||
void DAC_SetDMATimeOut(LPC_DAC_TypeDef *DACx,uint32_t time_out);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* LPC17XX_DAC_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,711 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_emac.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_emac.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Ethernet MAC firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup EMAC EMAC (Ethernet Media Access Controller)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_EMAC_H_
|
||||
#define LPC17XX_EMAC_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#define MCB_LPC_1768
|
||||
//#define IAR_LPC_1768
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup EMAC_Public_Macros EMAC Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/* EMAC PHY status type definitions */
|
||||
#define EMAC_PHY_STAT_LINK (0) /**< Link Status */
|
||||
#define EMAC_PHY_STAT_SPEED (1) /**< Speed Status */
|
||||
#define EMAC_PHY_STAT_DUP (2) /**< Duplex Status */
|
||||
|
||||
/* EMAC PHY device Speed definitions */
|
||||
#define EMAC_MODE_AUTO (0) /**< Auto-negotiation mode */
|
||||
#define EMAC_MODE_10M_FULL (1) /**< 10Mbps FullDuplex mode */
|
||||
#define EMAC_MODE_10M_HALF (2) /**< 10Mbps HalfDuplex mode */
|
||||
#define EMAC_MODE_100M_FULL (3) /**< 100Mbps FullDuplex mode */
|
||||
#define EMAC_MODE_100M_HALF (4) /**< 100Mbps HalfDuplex mode */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup EMAC_Private_Macros EMAC Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/* EMAC Memory Buffer configuration for 16K Ethernet RAM */
|
||||
#define EMAC_NUM_RX_FRAG 4 /**< Num.of RX Fragments 4*1536= 6.0kB */
|
||||
#define EMAC_NUM_TX_FRAG 3 /**< Num.of TX Fragments 3*1536= 4.6kB */
|
||||
#define EMAC_ETH_MAX_FLEN 1536 /**< Max. Ethernet Frame Size */
|
||||
#define EMAC_TX_FRAME_TOUT 0x00100000 /**< Frame Transmit timeout count */
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MAC Configuration Register 1
|
||||
**********************************************************************/
|
||||
#define EMAC_MAC1_REC_EN 0x00000001 /**< Receive Enable */
|
||||
#define EMAC_MAC1_PASS_ALL 0x00000002 /**< Pass All Receive Frames */
|
||||
#define EMAC_MAC1_RX_FLOWC 0x00000004 /**< RX Flow Control */
|
||||
#define EMAC_MAC1_TX_FLOWC 0x00000008 /**< TX Flow Control */
|
||||
#define EMAC_MAC1_LOOPB 0x00000010 /**< Loop Back Mode */
|
||||
#define EMAC_MAC1_RES_TX 0x00000100 /**< Reset TX Logic */
|
||||
#define EMAC_MAC1_RES_MCS_TX 0x00000200 /**< Reset MAC TX Control Sublayer */
|
||||
#define EMAC_MAC1_RES_RX 0x00000400 /**< Reset RX Logic */
|
||||
#define EMAC_MAC1_RES_MCS_RX 0x00000800 /**< Reset MAC RX Control Sublayer */
|
||||
#define EMAC_MAC1_SIM_RES 0x00004000 /**< Simulation Reset */
|
||||
#define EMAC_MAC1_SOFT_RES 0x00008000 /**< Soft Reset MAC */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MAC Configuration Register 2
|
||||
**********************************************************************/
|
||||
#define EMAC_MAC2_FULL_DUP 0x00000001 /**< Full-Duplex Mode */
|
||||
#define EMAC_MAC2_FRM_LEN_CHK 0x00000002 /**< Frame Length Checking */
|
||||
#define EMAC_MAC2_HUGE_FRM_EN 0x00000004 /**< Huge Frame Enable */
|
||||
#define EMAC_MAC2_DLY_CRC 0x00000008 /**< Delayed CRC Mode */
|
||||
#define EMAC_MAC2_CRC_EN 0x00000010 /**< Append CRC to every Frame */
|
||||
#define EMAC_MAC2_PAD_EN 0x00000020 /**< Pad all Short Frames */
|
||||
#define EMAC_MAC2_VLAN_PAD_EN 0x00000040 /**< VLAN Pad Enable */
|
||||
#define EMAC_MAC2_ADET_PAD_EN 0x00000080 /**< Auto Detect Pad Enable */
|
||||
#define EMAC_MAC2_PPREAM_ENF 0x00000100 /**< Pure Preamble Enforcement */
|
||||
#define EMAC_MAC2_LPREAM_ENF 0x00000200 /**< Long Preamble Enforcement */
|
||||
#define EMAC_MAC2_NO_BACKOFF 0x00001000 /**< No Backoff Algorithm */
|
||||
#define EMAC_MAC2_BACK_PRESSURE 0x00002000 /**< Backoff Presurre / No Backoff */
|
||||
#define EMAC_MAC2_EXCESS_DEF 0x00004000 /**< Excess Defer */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Back-to-Back Inter-Packet-Gap Register
|
||||
**********************************************************************/
|
||||
/** Programmable field representing the nibble time offset of the minimum possible period
|
||||
* between the end of any transmitted packet to the beginning of the next */
|
||||
#define EMAC_IPGT_BBIPG(n) (n&0x7F)
|
||||
/** Recommended value for Full Duplex of Programmable field representing the nibble time
|
||||
* offset of the minimum possible period between the end of any transmitted packet to the
|
||||
* beginning of the next */
|
||||
#define EMAC_IPGT_FULL_DUP (EMAC_IPGT_BBIPG(0x15))
|
||||
/** Recommended value for Half Duplex of Programmable field representing the nibble time
|
||||
* offset of the minimum possible period between the end of any transmitted packet to the
|
||||
* beginning of the next */
|
||||
#define EMAC_IPGT_HALF_DUP (EMAC_IPGT_BBIPG(0x12))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Non Back-to-Back Inter-Packet-Gap Register
|
||||
**********************************************************************/
|
||||
/** Programmable field representing the Non-Back-to-Back Inter-Packet-Gap */
|
||||
#define EMAC_IPGR_NBBIPG_P2(n) (n&0x7F)
|
||||
/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 1 */
|
||||
#define EMAC_IPGR_P2_DEF (EMAC_IPGR_NBBIPG_P2(0x12))
|
||||
/** Programmable field representing the optional carrierSense window referenced in
|
||||
* IEEE 802.3/4.2.3.2.1 'Carrier Deference' */
|
||||
#define EMAC_IPGR_NBBIPG_P1(n) ((n&0x7F)<<8)
|
||||
/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 2 */
|
||||
#define EMAC_IPGR_P1_DEF EMAC_IPGR_NBBIPG_P1(0x0C)
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Collision Window/Retry Register
|
||||
**********************************************************************/
|
||||
/** Programmable field specifying the number of retransmission attempts following a collision before
|
||||
* aborting the packet due to excessive collisions */
|
||||
#define EMAC_CLRT_MAX_RETX(n) (n&0x0F)
|
||||
/** Programmable field representing the slot time or collision window during which collisions occur
|
||||
* in properly configured networks */
|
||||
#define EMAC_CLRT_COLL(n) ((n&0x3F)<<8)
|
||||
/** Default value for Collision Window / Retry register */
|
||||
#define EMAC_CLRT_DEF ((EMAC_CLRT_MAX_RETX(0x0F))|(EMAC_CLRT_COLL(0x37)))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Maximum Frame Register
|
||||
**********************************************************************/
|
||||
/** Represents a maximum receive frame of 1536 octets */
|
||||
#define EMAC_MAXF_MAXFRMLEN(n) (n&0xFFFF)
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Support Register
|
||||
**********************************************************************/
|
||||
#define EMAC_SUPP_SPEED 0x00000100 /**< Reduced MII Logic Current Speed */
|
||||
//#define EMAC_SUPP_RES_RMII 0x00000800 /**< Reset Reduced MII Logic */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Test Register
|
||||
**********************************************************************/
|
||||
#define EMAC_TEST_SHCUT_PQUANTA 0x00000001 /**< Shortcut Pause Quanta */
|
||||
#define EMAC_TEST_TST_PAUSE 0x00000002 /**< Test Pause */
|
||||
#define EMAC_TEST_TST_BACKP 0x00000004 /**< Test Back Pressure */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Configuration Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MCFG_SCAN_INC 0x00000001 /**< Scan Increment PHY Address */
|
||||
#define EMAC_MCFG_SUPP_PREAM 0x00000002 /**< Suppress Preamble */
|
||||
#define EMAC_MCFG_CLK_SEL(n) ((n&0x0F)<<2) /**< Clock Select Field */
|
||||
#define EMAC_MCFG_RES_MII 0x00008000 /**< Reset MII Management Hardware */
|
||||
#define EMAC_MCFG_MII_MAXCLK 2500000UL /**< MII Clock max */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Command Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MCMD_READ 0x00000001 /**< MII Read */
|
||||
#define EMAC_MCMD_SCAN 0x00000002 /**< MII Scan continuously */
|
||||
|
||||
#define EMAC_MII_WR_TOUT 0x00050000 /**< MII Write timeout count */
|
||||
#define EMAC_MII_RD_TOUT 0x00050000 /**< MII Read timeout count */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Address Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MADR_REG_ADR(n) (n&0x1F) /**< MII Register Address field */
|
||||
#define EMAC_MADR_PHY_ADR(n) ((n&0x1F)<<8) /**< PHY Address Field */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Write Data Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MWTD_DATA(n) (n&0xFFFF) /**< Data field for MMI Management Write Data register */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Read Data Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MRDD_DATA(n) (n&0xFFFF) /**< Data field for MMI Management Read Data register */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MII Management Indicators Register
|
||||
**********************************************************************/
|
||||
#define EMAC_MIND_BUSY 0x00000001 /**< MII is Busy */
|
||||
#define EMAC_MIND_SCAN 0x00000002 /**< MII Scanning in Progress */
|
||||
#define EMAC_MIND_NOT_VAL 0x00000004 /**< MII Read Data not valid */
|
||||
#define EMAC_MIND_MII_LINK_FAIL 0x00000008 /**< MII Link Failed */
|
||||
|
||||
/* Station Address 0 Register */
|
||||
/* Station Address 1 Register */
|
||||
/* Station Address 2 Register */
|
||||
|
||||
|
||||
/* Control register definitions --------------------------------------------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Command Register
|
||||
**********************************************************************/
|
||||
#define EMAC_CR_RX_EN 0x00000001 /**< Enable Receive */
|
||||
#define EMAC_CR_TX_EN 0x00000002 /**< Enable Transmit */
|
||||
#define EMAC_CR_REG_RES 0x00000008 /**< Reset Host Registers */
|
||||
#define EMAC_CR_TX_RES 0x00000010 /**< Reset Transmit Datapath */
|
||||
#define EMAC_CR_RX_RES 0x00000020 /**< Reset Receive Datapath */
|
||||
#define EMAC_CR_PASS_RUNT_FRM 0x00000040 /**< Pass Runt Frames */
|
||||
#define EMAC_CR_PASS_RX_FILT 0x00000080 /**< Pass RX Filter */
|
||||
#define EMAC_CR_TX_FLOW_CTRL 0x00000100 /**< TX Flow Control */
|
||||
#define EMAC_CR_RMII 0x00000200 /**< Reduced MII Interface */
|
||||
#define EMAC_CR_FULL_DUP 0x00000400 /**< Full Duplex */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Status Register
|
||||
**********************************************************************/
|
||||
#define EMAC_SR_RX_EN 0x00000001 /**< Enable Receive */
|
||||
#define EMAC_SR_TX_EN 0x00000002 /**< Enable Transmit */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Transmit Status Vector 0 Register
|
||||
**********************************************************************/
|
||||
#define EMAC_TSV0_CRC_ERR 0x00000001 /**< CRC error */
|
||||
#define EMAC_TSV0_LEN_CHKERR 0x00000002 /**< Length Check Error */
|
||||
#define EMAC_TSV0_LEN_OUTRNG 0x00000004 /**< Length Out of Range */
|
||||
#define EMAC_TSV0_DONE 0x00000008 /**< Tramsmission Completed */
|
||||
#define EMAC_TSV0_MCAST 0x00000010 /**< Multicast Destination */
|
||||
#define EMAC_TSV0_BCAST 0x00000020 /**< Broadcast Destination */
|
||||
#define EMAC_TSV0_PKT_DEFER 0x00000040 /**< Packet Deferred */
|
||||
#define EMAC_TSV0_EXC_DEFER 0x00000080 /**< Excessive Packet Deferral */
|
||||
#define EMAC_TSV0_EXC_COLL 0x00000100 /**< Excessive Collision */
|
||||
#define EMAC_TSV0_LATE_COLL 0x00000200 /**< Late Collision Occured */
|
||||
#define EMAC_TSV0_GIANT 0x00000400 /**< Giant Frame */
|
||||
#define EMAC_TSV0_UNDERRUN 0x00000800 /**< Buffer Underrun */
|
||||
#define EMAC_TSV0_BYTES 0x0FFFF000 /**< Total Bytes Transferred */
|
||||
#define EMAC_TSV0_CTRL_FRAME 0x10000000 /**< Control Frame */
|
||||
#define EMAC_TSV0_PAUSE 0x20000000 /**< Pause Frame */
|
||||
#define EMAC_TSV0_BACK_PRESS 0x40000000 /**< Backpressure Method Applied */
|
||||
#define EMAC_TSV0_VLAN 0x80000000 /**< VLAN Frame */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Transmit Status Vector 1 Register
|
||||
**********************************************************************/
|
||||
#define EMAC_TSV1_BYTE_CNT 0x0000FFFF /**< Transmit Byte Count */
|
||||
#define EMAC_TSV1_COLL_CNT 0x000F0000 /**< Transmit Collision Count */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Receive Status Vector Register
|
||||
**********************************************************************/
|
||||
#define EMAC_RSV_BYTE_CNT 0x0000FFFF /**< Receive Byte Count */
|
||||
#define EMAC_RSV_PKT_IGNORED 0x00010000 /**< Packet Previously Ignored */
|
||||
#define EMAC_RSV_RXDV_SEEN 0x00020000 /**< RXDV Event Previously Seen */
|
||||
#define EMAC_RSV_CARR_SEEN 0x00040000 /**< Carrier Event Previously Seen */
|
||||
#define EMAC_RSV_REC_CODEV 0x00080000 /**< Receive Code Violation */
|
||||
#define EMAC_RSV_CRC_ERR 0x00100000 /**< CRC Error */
|
||||
#define EMAC_RSV_LEN_CHKERR 0x00200000 /**< Length Check Error */
|
||||
#define EMAC_RSV_LEN_OUTRNG 0x00400000 /**< Length Out of Range */
|
||||
#define EMAC_RSV_REC_OK 0x00800000 /**< Frame Received OK */
|
||||
#define EMAC_RSV_MCAST 0x01000000 /**< Multicast Frame */
|
||||
#define EMAC_RSV_BCAST 0x02000000 /**< Broadcast Frame */
|
||||
#define EMAC_RSV_DRIB_NIBB 0x04000000 /**< Dribble Nibble */
|
||||
#define EMAC_RSV_CTRL_FRAME 0x08000000 /**< Control Frame */
|
||||
#define EMAC_RSV_PAUSE 0x10000000 /**< Pause Frame */
|
||||
#define EMAC_RSV_UNSUPP_OPC 0x20000000 /**< Unsupported Opcode */
|
||||
#define EMAC_RSV_VLAN 0x40000000 /**< VLAN Frame */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Flow Control Counter Register
|
||||
**********************************************************************/
|
||||
#define EMAC_FCC_MIRR_CNT(n) (n&0xFFFF) /**< Mirror Counter */
|
||||
#define EMAC_FCC_PAUSE_TIM(n) ((n&0xFFFF)<<16) /**< Pause Timer */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Flow Control Status Register
|
||||
**********************************************************************/
|
||||
#define EMAC_FCS_MIRR_CNT(n) (n&0xFFFF) /**< Mirror Counter Current */
|
||||
|
||||
|
||||
/* Receive filter register definitions -------------------------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Receive Filter Control Register
|
||||
**********************************************************************/
|
||||
#define EMAC_RFC_UCAST_EN 0x00000001 /**< Accept Unicast Frames Enable */
|
||||
#define EMAC_RFC_BCAST_EN 0x00000002 /**< Accept Broadcast Frames Enable */
|
||||
#define EMAC_RFC_MCAST_EN 0x00000004 /**< Accept Multicast Frames Enable */
|
||||
#define EMAC_RFC_UCAST_HASH_EN 0x00000008 /**< Accept Unicast Hash Filter Frames */
|
||||
#define EMAC_RFC_MCAST_HASH_EN 0x00000010 /**< Accept Multicast Hash Filter Fram.*/
|
||||
#define EMAC_RFC_PERFECT_EN 0x00000020 /**< Accept Perfect Match Enable */
|
||||
#define EMAC_RFC_MAGP_WOL_EN 0x00001000 /**< Magic Packet Filter WoL Enable */
|
||||
#define EMAC_RFC_PFILT_WOL_EN 0x00002000 /**< Perfect Filter WoL Enable */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Receive Filter WoL Status/Clear Registers
|
||||
**********************************************************************/
|
||||
#define EMAC_WOL_UCAST 0x00000001 /**< Unicast Frame caused WoL */
|
||||
#define EMAC_WOL_BCAST 0x00000002 /**< Broadcast Frame caused WoL */
|
||||
#define EMAC_WOL_MCAST 0x00000004 /**< Multicast Frame caused WoL */
|
||||
#define EMAC_WOL_UCAST_HASH 0x00000008 /**< Unicast Hash Filter Frame WoL */
|
||||
#define EMAC_WOL_MCAST_HASH 0x00000010 /**< Multicast Hash Filter Frame WoL */
|
||||
#define EMAC_WOL_PERFECT 0x00000020 /**< Perfect Filter WoL */
|
||||
#define EMAC_WOL_RX_FILTER 0x00000080 /**< RX Filter caused WoL */
|
||||
#define EMAC_WOL_MAG_PACKET 0x00000100 /**< Magic Packet Filter caused WoL */
|
||||
#define EMAC_WOL_BITMASK 0x01BF /**< Receive Filter WoL Status/Clear bitmasl value */
|
||||
|
||||
|
||||
/* Module control register definitions ---------------------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Interrupt Status/Enable/Clear/Set Registers
|
||||
**********************************************************************/
|
||||
#define EMAC_INT_RX_OVERRUN 0x00000001 /**< Overrun Error in RX Queue */
|
||||
#define EMAC_INT_RX_ERR 0x00000002 /**< Receive Error */
|
||||
#define EMAC_INT_RX_FIN 0x00000004 /**< RX Finished Process Descriptors */
|
||||
#define EMAC_INT_RX_DONE 0x00000008 /**< Receive Done */
|
||||
#define EMAC_INT_TX_UNDERRUN 0x00000010 /**< Transmit Underrun */
|
||||
#define EMAC_INT_TX_ERR 0x00000020 /**< Transmit Error */
|
||||
#define EMAC_INT_TX_FIN 0x00000040 /**< TX Finished Process Descriptors */
|
||||
#define EMAC_INT_TX_DONE 0x00000080 /**< Transmit Done */
|
||||
#define EMAC_INT_SOFT_INT 0x00001000 /**< Software Triggered Interrupt */
|
||||
#define EMAC_INT_WAKEUP 0x00002000 /**< Wakeup Event Interrupt */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Power Down Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PD_POWER_DOWN 0x80000000 /**< Power Down MAC */
|
||||
|
||||
/* Descriptor and status formats ---------------------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for RX Descriptor Control Word
|
||||
**********************************************************************/
|
||||
#define EMAC_RCTRL_SIZE(n) (n&0x7FF) /**< Buffer size field */
|
||||
#define EMAC_RCTRL_INT 0x80000000 /**< Generate RxDone Interrupt */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for RX Status Hash CRC Word
|
||||
**********************************************************************/
|
||||
#define EMAC_RHASH_SA 0x000001FF /**< Hash CRC for Source Address */
|
||||
#define EMAC_RHASH_DA 0x001FF000 /**< Hash CRC for Destination Address */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for RX Status Information Word
|
||||
**********************************************************************/
|
||||
#define EMAC_RINFO_SIZE 0x000007FF /**< Data size in bytes */
|
||||
#define EMAC_RINFO_CTRL_FRAME 0x00040000 /**< Control Frame */
|
||||
#define EMAC_RINFO_VLAN 0x00080000 /**< VLAN Frame */
|
||||
#define EMAC_RINFO_FAIL_FILT 0x00100000 /**< RX Filter Failed */
|
||||
#define EMAC_RINFO_MCAST 0x00200000 /**< Multicast Frame */
|
||||
#define EMAC_RINFO_BCAST 0x00400000 /**< Broadcast Frame */
|
||||
#define EMAC_RINFO_CRC_ERR 0x00800000 /**< CRC Error in Frame */
|
||||
#define EMAC_RINFO_SYM_ERR 0x01000000 /**< Symbol Error from PHY */
|
||||
#define EMAC_RINFO_LEN_ERR 0x02000000 /**< Length Error */
|
||||
#define EMAC_RINFO_RANGE_ERR 0x04000000 /**< Range Error (exceeded max. size) */
|
||||
#define EMAC_RINFO_ALIGN_ERR 0x08000000 /**< Alignment Error */
|
||||
#define EMAC_RINFO_OVERRUN 0x10000000 /**< Receive overrun */
|
||||
#define EMAC_RINFO_NO_DESCR 0x20000000 /**< No new Descriptor available */
|
||||
#define EMAC_RINFO_LAST_FLAG 0x40000000 /**< Last Fragment in Frame */
|
||||
#define EMAC_RINFO_ERR 0x80000000 /**< Error Occured (OR of all errors) */
|
||||
#define EMAC_RINFO_ERR_MASK (EMAC_RINFO_FAIL_FILT | EMAC_RINFO_CRC_ERR | EMAC_RINFO_SYM_ERR | \
|
||||
EMAC_RINFO_LEN_ERR | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_OVERRUN)
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for TX Descriptor Control Word
|
||||
**********************************************************************/
|
||||
#define EMAC_TCTRL_SIZE 0x000007FF /**< Size of data buffer in bytes */
|
||||
#define EMAC_TCTRL_OVERRIDE 0x04000000 /**< Override Default MAC Registers */
|
||||
#define EMAC_TCTRL_HUGE 0x08000000 /**< Enable Huge Frame */
|
||||
#define EMAC_TCTRL_PAD 0x10000000 /**< Pad short Frames to 64 bytes */
|
||||
#define EMAC_TCTRL_CRC 0x20000000 /**< Append a hardware CRC to Frame */
|
||||
#define EMAC_TCTRL_LAST 0x40000000 /**< Last Descriptor for TX Frame */
|
||||
#define EMAC_TCTRL_INT 0x80000000 /**< Generate TxDone Interrupt */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for TX Status Information Word
|
||||
**********************************************************************/
|
||||
#define EMAC_TINFO_COL_CNT 0x01E00000 /**< Collision Count */
|
||||
#define EMAC_TINFO_DEFER 0x02000000 /**< Packet Deferred (not an error) */
|
||||
#define EMAC_TINFO_EXCESS_DEF 0x04000000 /**< Excessive Deferral */
|
||||
#define EMAC_TINFO_EXCESS_COL 0x08000000 /**< Excessive Collision */
|
||||
#define EMAC_TINFO_LATE_COL 0x10000000 /**< Late Collision Occured */
|
||||
#define EMAC_TINFO_UNDERRUN 0x20000000 /**< Transmit Underrun */
|
||||
#define EMAC_TINFO_NO_DESCR 0x40000000 /**< No new Descriptor available */
|
||||
#define EMAC_TINFO_ERR 0x80000000 /**< Error Occured (OR of all errors) */
|
||||
|
||||
#ifdef MCB_LPC_1768
|
||||
/* DP83848C PHY definition ------------------------------------------------------------ */
|
||||
|
||||
/** PHY device reset time out definition */
|
||||
#define EMAC_PHY_RESP_TOUT 0x100000UL
|
||||
|
||||
/* ENET Device Revision ID */
|
||||
#define EMAC_OLD_EMAC_MODULE_ID 0x39022000 /**< Rev. ID for first rev '-' */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DP83848C PHY Registers
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_REG_BMCR 0x00 /**< Basic Mode Control Register */
|
||||
#define EMAC_PHY_REG_BMSR 0x01 /**< Basic Mode Status Register */
|
||||
#define EMAC_PHY_REG_IDR1 0x02 /**< PHY Identifier 1 */
|
||||
#define EMAC_PHY_REG_IDR2 0x03 /**< PHY Identifier 2 */
|
||||
#define EMAC_PHY_REG_ANAR 0x04 /**< Auto-Negotiation Advertisement */
|
||||
#define EMAC_PHY_REG_ANLPAR 0x05 /**< Auto-Neg. Link Partner Abitily */
|
||||
#define EMAC_PHY_REG_ANER 0x06 /**< Auto-Neg. Expansion Register */
|
||||
#define EMAC_PHY_REG_ANNPTR 0x07 /**< Auto-Neg. Next Page TX */
|
||||
#define EMAC_PHY_REG_LPNPA 0x08
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Extended Registers
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_REG_STS 0x10 /**< Status Register */
|
||||
#define EMAC_PHY_REG_MICR 0x11 /**< MII Interrupt Control Register */
|
||||
#define EMAC_PHY_REG_MISR 0x12 /**< MII Interrupt Status Register */
|
||||
#define EMAC_PHY_REG_FCSCR 0x14 /**< False Carrier Sense Counter */
|
||||
#define EMAC_PHY_REG_RECR 0x15 /**< Receive Error Counter */
|
||||
#define EMAC_PHY_REG_PCSR 0x16 /**< PCS Sublayer Config. and Status */
|
||||
#define EMAC_PHY_REG_RBR 0x17 /**< RMII and Bypass Register */
|
||||
#define EMAC_PHY_REG_LEDCR 0x18 /**< LED Direct Control Register */
|
||||
#define EMAC_PHY_REG_PHYCR 0x19 /**< PHY Control Register */
|
||||
#define EMAC_PHY_REG_10BTSCR 0x1A /**< 10Base-T Status/Control Register */
|
||||
#define EMAC_PHY_REG_CDCTRL1 0x1B /**< CD Test Control and BIST Extens. */
|
||||
#define EMAC_PHY_REG_EDCR 0x1D /**< Energy Detect Control Register */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Basic Mode Control Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_BMCR_RESET (1<<15) /**< Reset bit */
|
||||
#define EMAC_PHY_BMCR_LOOPBACK (1<<14) /**< Loop back */
|
||||
#define EMAC_PHY_BMCR_SPEED_SEL (1<<13) /**< Speed selection */
|
||||
#define EMAC_PHY_BMCR_AN (1<<12) /**< Auto Negotiation */
|
||||
#define EMAC_PHY_BMCR_POWERDOWN (1<<11) /**< Power down mode */
|
||||
#define EMAC_PHY_BMCR_ISOLATE (1<<10) /**< Isolate */
|
||||
#define EMAC_PHY_BMCR_RE_AN (1<<9) /**< Restart auto negotiation */
|
||||
#define EMAC_PHY_BMCR_DUPLEX (1<<8) /**< Duplex mode */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Basic Mode Status Status Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_BMSR_100BE_T4 (1<<15) /**< 100 base T4 */
|
||||
#define EMAC_PHY_BMSR_100TX_FULL (1<<14) /**< 100 base full duplex */
|
||||
#define EMAC_PHY_BMSR_100TX_HALF (1<<13) /**< 100 base half duplex */
|
||||
#define EMAC_PHY_BMSR_10BE_FULL (1<<12) /**< 10 base T full duplex */
|
||||
#define EMAC_PHY_BMSR_10BE_HALF (1<<11) /**< 10 base T half duplex */
|
||||
#define EMAC_PHY_BMSR_NOPREAM (1<<6) /**< MF Preamable Supress */
|
||||
#define EMAC_PHY_BMSR_AUTO_DONE (1<<5) /**< Auto negotiation complete */
|
||||
#define EMAC_PHY_BMSR_REMOTE_FAULT (1<<4) /**< Remote fault */
|
||||
#define EMAC_PHY_BMSR_NO_AUTO (1<<3) /**< Auto Negotiation ability */
|
||||
#define EMAC_PHY_BMSR_LINK_ESTABLISHED (1<<2) /**< Link status */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Status Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_SR_REMOTE_FAULT (1<<6) /**< Remote Fault */
|
||||
#define EMAC_PHY_SR_JABBER (1<<5) /**< Jabber detect */
|
||||
#define EMAC_PHY_SR_AUTO_DONE (1<<4) /**< Auto Negotiation complete */
|
||||
#define EMAC_PHY_SR_LOOPBACK (1<<3) /**< Loop back status */
|
||||
#define EMAC_PHY_SR_DUP (1<<2) /**< Duplex status */
|
||||
#define EMAC_PHY_SR_SPEED (1<<1) /**< Speed status */
|
||||
#define EMAC_PHY_SR_LINK (1<<0) /**< Link Status */
|
||||
|
||||
#define EMAC_PHY_FULLD_100M 0x2100 /**< Full Duplex 100Mbit */
|
||||
#define EMAC_PHY_HALFD_100M 0x2000 /**< Half Duplex 100Mbit */
|
||||
#define EMAC_PHY_FULLD_10M 0x0100 /**< Full Duplex 10Mbit */
|
||||
#define EMAC_PHY_HALFD_10M 0x0000 /**< Half Duplex 10MBit */
|
||||
#define EMAC_PHY_AUTO_NEG 0x3000 /**< Select Auto Negotiation */
|
||||
|
||||
#define EMAC_DEF_ADR 0x0100 /**< Default PHY device address */
|
||||
#define EMAC_DP83848C_ID 0x20005C90 /**< PHY Identifier */
|
||||
|
||||
#define EMAC_PHY_SR_100_SPEED ((1<<14)|(1<<13))
|
||||
#define EMAC_PHY_SR_FULL_DUP ((1<<14)|(1<<12))
|
||||
#define EMAC_PHY_BMSR_LINK_STATUS (1<<2) /**< Link status */
|
||||
|
||||
#elif defined(IAR_LPC_1768)
|
||||
/* KSZ8721BL PHY definition ------------------------------------------------------------ */
|
||||
/** PHY device reset time out definition */
|
||||
#define EMAC_PHY_RESP_TOUT 0x100000UL
|
||||
|
||||
/* ENET Device Revision ID */
|
||||
#define EMAC_OLD_EMAC_MODULE_ID 0x39022000 /**< Rev. ID for first rev '-' */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for KSZ8721BL PHY Registers
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_REG_BMCR 0x00 /**< Basic Mode Control Register */
|
||||
#define EMAC_PHY_REG_BMSR 0x01 /**< Basic Mode Status Register */
|
||||
#define EMAC_PHY_REG_IDR1 0x02 /**< PHY Identifier 1 */
|
||||
#define EMAC_PHY_REG_IDR2 0x03 /**< PHY Identifier 2 */
|
||||
#define EMAC_PHY_REG_ANAR 0x04 /**< Auto-Negotiation Advertisement */
|
||||
#define EMAC_PHY_REG_ANLPAR 0x05 /**< Auto-Neg. Link Partner Abitily */
|
||||
#define EMAC_PHY_REG_ANER 0x06 /**< Auto-Neg. Expansion Register */
|
||||
#define EMAC_PHY_REG_ANNPTR 0x07 /**< Auto-Neg. Next Page TX */
|
||||
#define EMAC_PHY_REG_LPNPA 0x08 /**< Link Partner Next Page Ability */
|
||||
#define EMAC_PHY_REG_REC 0x15 /**< RXError Counter Register */
|
||||
#define EMAC_PHY_REG_ISC 0x1b /**< Interrupt Control/Status Register */
|
||||
#define EMAC_PHY_REG_100BASE 0x1f /**< 100BASE-TX PHY Control Register */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Basic Mode Control Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_BMCR_RESET (1<<15) /**< Reset bit */
|
||||
#define EMAC_PHY_BMCR_LOOPBACK (1<<14) /**< Loop back */
|
||||
#define EMAC_PHY_BMCR_SPEED_SEL (1<<13) /**< Speed selection */
|
||||
#define EMAC_PHY_BMCR_AN (1<<12) /**< Auto Negotiation */
|
||||
#define EMAC_PHY_BMCR_POWERDOWN (1<<11) /**< Power down mode */
|
||||
#define EMAC_PHY_BMCR_ISOLATE (1<<10) /**< Isolate */
|
||||
#define EMAC_PHY_BMCR_RE_AN (1<<9) /**< Restart auto negotiation */
|
||||
#define EMAC_PHY_BMCR_DUPLEX (1<<8) /**< Duplex mode */
|
||||
#define EMAC_PHY_BMCR_COLLISION (1<<7) /**< Collision test */
|
||||
#define EMAC_PHY_BMCR_TXDIS (1<<0) /**< Disable transmit */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Basic Mode Status Register
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_BMSR_100BE_T4 (1<<15) /**< 100 base T4 */
|
||||
#define EMAC_PHY_BMSR_100TX_FULL (1<<14) /**< 100 base full duplex */
|
||||
#define EMAC_PHY_BMSR_100TX_HALF (1<<13) /**< 100 base half duplex */
|
||||
#define EMAC_PHY_BMSR_10BE_FULL (1<<12) /**< 10 base T full duplex */
|
||||
#define EMAC_PHY_BMSR_10BE_HALF (1<<11) /**< 10 base T half duplex */
|
||||
#define EMAC_PHY_BMSR_NOPREAM (1<<6) /**< MF Preamable Supress */
|
||||
#define EMAC_PHY_BMSR_AUTO_DONE (1<<5) /**< Auto negotiation complete */
|
||||
#define EMAC_PHY_BMSR_REMOTE_FAULT (1<<4) /**< Remote fault */
|
||||
#define EMAC_PHY_BMSR_NO_AUTO (1<<3) /**< Auto Negotiation ability */
|
||||
#define EMAC_PHY_BMSR_LINK_STATUS (1<<2) /**< Link status */
|
||||
#define EMAC_PHY_BMSR_JABBER_DETECT (1<<1) /**< Jabber detect */
|
||||
#define EMAC_PHY_BMSR_EXTEND (1<<0) /**< Extended support */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for PHY Identifier
|
||||
**********************************************************************/
|
||||
/* PHY Identifier 1 bitmap definitions */
|
||||
#define EMAC_PHY_IDR1(n) (n & 0xFFFF) /**< PHY ID1 Number */
|
||||
|
||||
/* PHY Identifier 2 bitmap definitions */
|
||||
#define EMAC_PHY_IDR2(n) (n & 0xFFFF) /**< PHY ID2 Number */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for Auto-Negotiation Advertisement
|
||||
**********************************************************************/
|
||||
#define EMAC_PHY_AN_NEXTPAGE (1<<15) /**< Next page capable */
|
||||
#define EMAC_PHY_AN_REMOTE_FAULT (1<<13) /**< Remote Fault support */
|
||||
#define EMAC_PHY_AN_PAUSE (1<<10) /**< Pause support */
|
||||
#define EMAC_PHY_AN_100BASE_T4 (1<<9) /**< T4 capable */
|
||||
#define EMAC_PHY_AN_100BASE_TX_FD (1<<8) /**< TX with Full-duplex capable */
|
||||
#define EMAC_PHY_AN_100BASE_TX (1<<7) /**< TX capable */
|
||||
#define EMAC_PHY_AN_10BASE_T_FD (1<<6) /**< 10Mbps with full-duplex capable */
|
||||
#define EMAC_PHY_AN_10BASE_T (1<<5) /**< 10Mbps capable */
|
||||
#define EMAC_PHY_AN_FIELD(n) (n & 0x1F) /**< Selector Field */
|
||||
|
||||
#define EMAC_PHY_FULLD_100M 0x2100 /**< Full Duplex 100Mbit */
|
||||
#define EMAC_PHY_HALFD_100M 0x2000 /**< Half Duplex 100Mbit */
|
||||
#define EMAC_PHY_FULLD_10M 0x0100 /**< Full Duplex 10Mbit */
|
||||
#define EMAC_PHY_HALFD_10M 0x0000 /**< Half Duplex 10MBit */
|
||||
#define EMAC_PHY_AUTO_NEG 0x3000 /**< Select Auto Negotiation */
|
||||
|
||||
#define EMAC_PHY_SR_100_SPEED ((1<<14)|(1<<13))
|
||||
#define EMAC_PHY_SR_FULL_DUP ((1<<14)|(1<<12))
|
||||
|
||||
#define EMAC_DEF_ADR (0x01<<8) /**< Default PHY device address */
|
||||
#define EMAC_KSZ8721BL_ID ((0x22 << 16) | 0x1619 ) /**< PHY Identifier */
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup EMAC_Public_Types EMAC Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Descriptor and status formats ---------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @brief RX Descriptor structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t Packet; /**< Receive Packet Descriptor */
|
||||
uint32_t Ctrl; /**< Receive Control Descriptor */
|
||||
} RX_Desc;
|
||||
|
||||
/**
|
||||
* @brief RX Status structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t Info; /**< Receive Information Status */
|
||||
uint32_t HashCRC; /**< Receive Hash CRC Status */
|
||||
} RX_Stat;
|
||||
|
||||
/**
|
||||
* @brief TX Descriptor structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t Packet; /**< Transmit Packet Descriptor */
|
||||
uint32_t Ctrl; /**< Transmit Control Descriptor */
|
||||
} TX_Desc;
|
||||
|
||||
/**
|
||||
* @brief TX Status structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t Info; /**< Transmit Information Status */
|
||||
} TX_Stat;
|
||||
|
||||
|
||||
/**
|
||||
* @brief TX Data Buffer structure definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t ulDataLen; /**< Data length */
|
||||
uint32_t *pbDataBuf; /**< A word-align data pointer to data buffer */
|
||||
} EMAC_PACKETBUF_Type;
|
||||
|
||||
/**
|
||||
* @brief EMAC configuration structure definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t Mode; /**< Supported EMAC PHY device speed, should be one of the following:
|
||||
- EMAC_MODE_AUTO
|
||||
- EMAC_MODE_10M_FULL
|
||||
- EMAC_MODE_10M_HALF
|
||||
- EMAC_MODE_100M_FULL
|
||||
- EMAC_MODE_100M_HALF
|
||||
*/
|
||||
uint8_t *pbEMAC_Addr; /**< Pointer to EMAC Station address that contains 6-bytes
|
||||
of MAC address, it must be sorted in order (bEMAC_Addr[0]..[5])
|
||||
*/
|
||||
} EMAC_CFG_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup EMAC_Public_Functions EMAC Public Functions
|
||||
* @{
|
||||
*/
|
||||
/* Init/DeInit EMAC peripheral */
|
||||
Status EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct);
|
||||
void EMAC_DeInit(void);
|
||||
|
||||
/* PHY functions --------------*/
|
||||
int32_t EMAC_CheckPHYStatus(uint32_t ulPHYState);
|
||||
int32_t EMAC_SetPHYMode(uint32_t ulPHYMode);
|
||||
int32_t EMAC_UpdatePHYStatus(void);
|
||||
|
||||
/* Filter functions ----------*/
|
||||
void EMAC_SetHashFilter(uint8_t dstMAC_addr[], FunctionalState NewState);
|
||||
void EMAC_SetFilterMode(uint32_t ulFilterMode, FunctionalState NewState);
|
||||
|
||||
/* EMAC Packet Buffer functions */
|
||||
void EMAC_WritePacketBuffer(EMAC_PACKETBUF_Type *pDataStruct);
|
||||
void EMAC_ReadPacketBuffer(EMAC_PACKETBUF_Type *pDataStruct);
|
||||
|
||||
/* EMAC Interrupt functions -------*/
|
||||
void EMAC_IntCmd(uint32_t ulIntType, FunctionalState NewState);
|
||||
IntStatus EMAC_IntGetStatus(uint32_t ulIntType);
|
||||
|
||||
/* EMAC Index functions -----------*/
|
||||
Bool EMAC_CheckReceiveIndex(void);
|
||||
Bool EMAC_CheckTransmitIndex(void);
|
||||
void EMAC_UpdateRxConsumeIndex(void);
|
||||
void EMAC_UpdateTxProduceIndex(void);
|
||||
|
||||
FlagStatus EMAC_CheckReceiveDataStatus(uint32_t ulRxStatType);
|
||||
uint32_t EMAC_GetReceiveDataSize(void);
|
||||
FlagStatus EMAC_GetWoLStatus(uint32_t ulWoLMode);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_EMAC_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,155 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_exti.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_exti.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for External interrupt firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup EXTI EXTI (External Interrupt)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_EXTI_H_
|
||||
#define LPC17XX_EXTI_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup EXTI_Private_Macros EXTI Private Macros
|
||||
* @{
|
||||
*/
|
||||
/*********************************************************************//**
|
||||
* Macro defines for EXTI control register
|
||||
**********************************************************************/
|
||||
#define EXTI_EINT0_BIT_MARK 0x01
|
||||
#define EXTI_EINT1_BIT_MARK 0x02
|
||||
#define EXTI_EINT2_BIT_MARK 0x04
|
||||
#define EXTI_EINT3_BIT_MARK 0x08
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup EXTI_Public_Types EXTI Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief EXTI external interrupt line option
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
EXTI_EINT0, /*!< External interrupt 0, P2.10 */
|
||||
EXTI_EINT1, /*!< External interrupt 0, P2.11 */
|
||||
EXTI_EINT2, /*!< External interrupt 0, P2.12 */
|
||||
EXTI_EINT3 /*!< External interrupt 0, P2.13 */
|
||||
} EXTI_LINE_ENUM;
|
||||
|
||||
/**
|
||||
* @brief EXTI mode option
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
EXTI_MODE_LEVEL_SENSITIVE, /*!< Level sensitivity is selected */
|
||||
EXTI_MODE_EDGE_SENSITIVE /*!< Edge sensitivity is selected */
|
||||
} EXTI_MODE_ENUM;
|
||||
|
||||
/**
|
||||
* @brief EXTI polarity option
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE, /*!< Low active or falling edge sensitive
|
||||
depending on pin mode */
|
||||
EXTI_POLARITY_HIGH_ACTIVE_OR_RISING_EDGE /*!< High active or rising edge sensitive
|
||||
depending on pin mode */
|
||||
} EXTI_POLARITY_ENUM;
|
||||
|
||||
/**
|
||||
* @brief EXTI Initialize structure
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
EXTI_LINE_ENUM EXTI_Line; /*!<Select external interrupt pin (EINT0, EINT1, EINT 2, EINT3) */
|
||||
|
||||
EXTI_MODE_ENUM EXTI_Mode; /*!< Choose between Level-sensitivity or Edge sensitivity */
|
||||
|
||||
EXTI_POLARITY_ENUM EXTI_polarity; /*!< If EXTI mode is level-sensitive: this element use to select low or high active level
|
||||
if EXTI mode is polarity-sensitive: this element use to select falling or rising edge */
|
||||
|
||||
}EXTI_InitTypeDef;
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup EXTI_Public_Functions EXTI Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void EXTI_Init(void);
|
||||
void EXTI_DeInit(void);
|
||||
|
||||
void EXTI_Config(EXTI_InitTypeDef *EXTICfg);
|
||||
void EXTI_SetMode(EXTI_LINE_ENUM EXTILine, EXTI_MODE_ENUM mode);
|
||||
void EXTI_SetPolarity(EXTI_LINE_ENUM EXTILine, EXTI_POLARITY_ENUM polarity);
|
||||
void EXTI_ClearEXTIFlag(EXTI_LINE_ENUM EXTILine);
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* LPC17XX_EXTI_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,429 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_gpdma.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_gpdma.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for GPDMA firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup GPDMA GPDMA (General Purpose Direct Memory Access)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_GPDMA_H_
|
||||
#define LPC17XX_GPDMA_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup GPDMA_Public_Macros GPDMA Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** DMA Connection number definitions */
|
||||
#define GPDMA_CONN_SSP0_Tx ((0UL)) /**< SSP0 Tx */
|
||||
#define GPDMA_CONN_SSP0_Rx ((1UL)) /**< SSP0 Rx */
|
||||
#define GPDMA_CONN_SSP1_Tx ((2UL)) /**< SSP1 Tx */
|
||||
#define GPDMA_CONN_SSP1_Rx ((3UL)) /**< SSP1 Rx */
|
||||
#define GPDMA_CONN_ADC ((4UL)) /**< ADC */
|
||||
#define GPDMA_CONN_I2S_Channel_0 ((5UL)) /**< I2S channel 0 */
|
||||
#define GPDMA_CONN_I2S_Channel_1 ((6UL)) /**< I2S channel 1 */
|
||||
#define GPDMA_CONN_DAC ((7UL)) /**< DAC */
|
||||
#define GPDMA_CONN_UART0_Tx ((8UL)) /**< UART0 Tx */
|
||||
#define GPDMA_CONN_UART0_Rx ((9UL)) /**< UART0 Rx */
|
||||
#define GPDMA_CONN_UART1_Tx ((10UL)) /**< UART1 Tx */
|
||||
#define GPDMA_CONN_UART1_Rx ((11UL)) /**< UART1 Rx */
|
||||
#define GPDMA_CONN_UART2_Tx ((12UL)) /**< UART2 Tx */
|
||||
#define GPDMA_CONN_UART2_Rx ((13UL)) /**< UART2 Rx */
|
||||
#define GPDMA_CONN_UART3_Tx ((14UL)) /**< UART3 Tx */
|
||||
#define GPDMA_CONN_UART3_Rx ((15UL)) /**< UART3 Rx */
|
||||
#define GPDMA_CONN_MAT0_0 ((16UL)) /**< MAT0.0 */
|
||||
#define GPDMA_CONN_MAT0_1 ((17UL)) /**< MAT0.1 */
|
||||
#define GPDMA_CONN_MAT1_0 ((18UL)) /**< MAT1.0 */
|
||||
#define GPDMA_CONN_MAT1_1 ((19UL)) /**< MAT1.1 */
|
||||
#define GPDMA_CONN_MAT2_0 ((20UL)) /**< MAT2.0 */
|
||||
#define GPDMA_CONN_MAT2_1 ((21UL)) /**< MAT2.1 */
|
||||
#define GPDMA_CONN_MAT3_0 ((22UL)) /**< MAT3.0 */
|
||||
#define GPDMA_CONN_MAT3_1 ((23UL)) /**< MAT3.1 */
|
||||
|
||||
/** GPDMA Transfer type definitions */
|
||||
#define GPDMA_TRANSFERTYPE_M2M ((0UL)) /**< Memory to memory - DMA control */
|
||||
#define GPDMA_TRANSFERTYPE_M2P ((1UL)) /**< Memory to peripheral - DMA control */
|
||||
#define GPDMA_TRANSFERTYPE_P2M ((2UL)) /**< Peripheral to memory - DMA control */
|
||||
#define GPDMA_TRANSFERTYPE_P2P ((3UL)) /**< Source peripheral to destination peripheral - DMA control */
|
||||
|
||||
/** Burst size in Source and Destination definitions */
|
||||
#define GPDMA_BSIZE_1 ((0UL)) /**< Burst size = 1 */
|
||||
#define GPDMA_BSIZE_4 ((1UL)) /**< Burst size = 4 */
|
||||
#define GPDMA_BSIZE_8 ((2UL)) /**< Burst size = 8 */
|
||||
#define GPDMA_BSIZE_16 ((3UL)) /**< Burst size = 16 */
|
||||
#define GPDMA_BSIZE_32 ((4UL)) /**< Burst size = 32 */
|
||||
#define GPDMA_BSIZE_64 ((5UL)) /**< Burst size = 64 */
|
||||
#define GPDMA_BSIZE_128 ((6UL)) /**< Burst size = 128 */
|
||||
#define GPDMA_BSIZE_256 ((7UL)) /**< Burst size = 256 */
|
||||
|
||||
/** Width in Source transfer width and Destination transfer width definitions */
|
||||
#define GPDMA_WIDTH_BYTE ((0UL)) /**< Width = 1 byte */
|
||||
#define GPDMA_WIDTH_HALFWORD ((1UL)) /**< Width = 2 bytes */
|
||||
#define GPDMA_WIDTH_WORD ((2UL)) /**< Width = 4 bytes */
|
||||
|
||||
/** DMA Request Select Mode definitions */
|
||||
#define GPDMA_REQSEL_UART ((0UL)) /**< UART TX/RX is selected */
|
||||
#define GPDMA_REQSEL_TIMER ((1UL)) /**< Timer match is selected */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup GPDMA_Private_Macros GPDMA Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Interrupt Status register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACIntStat_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACIntStat_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Interrupt Terminal Count Request Status register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACIntTCStat_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACIntTCStat_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Interrupt Terminal Count Request Clear register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACIntTCClear_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACIntTCClear_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Interrupt Error Status register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACIntErrStat_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACIntErrStat_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Interrupt Error Clear register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACIntErrClr_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACIntErrClr_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Raw Interrupt Terminal Count Status register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACRawIntTCStat_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACRawIntTCStat_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Raw Error Interrupt Status register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACRawIntErrStat_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACRawIntErrStat_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Enabled Channel register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACEnbldChns_Ch(n) (((1UL<<n)&0xFF))
|
||||
#define GPDMA_DMACEnbldChns_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Software Burst Request register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACSoftBReq_Src(n) (((1UL<<n)&0xFFFF))
|
||||
#define GPDMA_DMACSoftBReq_BITMASK ((0xFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Software Single Request register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACSoftSReq_Src(n) (((1UL<<n)&0xFFFF))
|
||||
#define GPDMA_DMACSoftSReq_BITMASK ((0xFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Software Last Burst Request register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACSoftLBReq_Src(n) (((1UL<<n)&0xFFFF))
|
||||
#define GPDMA_DMACSoftLBReq_BITMASK ((0xFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Software Last Single Request register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACSoftLSReq_Src(n) (((1UL<<n)&0xFFFF))
|
||||
#define GPDMA_DMACSoftLSReq_BITMASK ((0xFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Configuration register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACConfig_E ((0x01)) /**< DMA Controller enable*/
|
||||
#define GPDMA_DMACConfig_M ((0x02)) /**< AHB Master endianness configuration*/
|
||||
#define GPDMA_DMACConfig_BITMASK ((0x03))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Synchronization register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACSync_Src(n) (((1UL<<n)&0xFFFF))
|
||||
#define GPDMA_DMACSync_BITMASK ((0xFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Request Select register
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMAReqSel_Input(n) (((1UL<<(n-8))&0xFF))
|
||||
#define GPDMA_DMAReqSel_BITMASK ((0xFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Channel Linked List Item registers
|
||||
**********************************************************************/
|
||||
/** DMA Channel Linked List Item registers bit mask*/
|
||||
#define GPDMA_DMACCxLLI_BITMASK ((0xFFFFFFFC))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA channel control registers
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACCxControl_TransferSize(n) (((n&0xFFF)<<0)) /**< Transfer size*/
|
||||
#define GPDMA_DMACCxControl_SBSize(n) (((n&0x07)<<12)) /**< Source burst size*/
|
||||
#define GPDMA_DMACCxControl_DBSize(n) (((n&0x07)<<15)) /**< Destination burst size*/
|
||||
#define GPDMA_DMACCxControl_SWidth(n) (((n&0x07)<<18)) /**< Source transfer width*/
|
||||
#define GPDMA_DMACCxControl_DWidth(n) (((n&0x07)<<21)) /**< Destination transfer width*/
|
||||
#define GPDMA_DMACCxControl_SI ((1UL<<26)) /**< Source increment*/
|
||||
#define GPDMA_DMACCxControl_DI ((1UL<<27)) /**< Destination increment*/
|
||||
#define GPDMA_DMACCxControl_Prot1 ((1UL<<28)) /**< Indicates that the access is in user mode or privileged mode*/
|
||||
#define GPDMA_DMACCxControl_Prot2 ((1UL<<29)) /**< Indicates that the access is bufferable or not bufferable*/
|
||||
#define GPDMA_DMACCxControl_Prot3 ((1UL<<30)) /**< Indicates that the access is cacheable or not cacheable*/
|
||||
#define GPDMA_DMACCxControl_I ((1UL<<31)) /**< Terminal count interrupt enable bit */
|
||||
/** DMA channel control registers bit mask */
|
||||
#define GPDMA_DMACCxControl_BITMASK ((0xFCFFFFFF))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA Channel Configuration registers
|
||||
**********************************************************************/
|
||||
#define GPDMA_DMACCxConfig_E ((1UL<<0)) /**< DMA control enable*/
|
||||
#define GPDMA_DMACCxConfig_SrcPeripheral(n) (((n&0x1F)<<1)) /**< Source peripheral*/
|
||||
#define GPDMA_DMACCxConfig_DestPeripheral(n) (((n&0x1F)<<6)) /**< Destination peripheral*/
|
||||
#define GPDMA_DMACCxConfig_TransferType(n) (((n&0x7)<<11)) /**< This value indicates the type of transfer*/
|
||||
#define GPDMA_DMACCxConfig_IE ((1UL<<14)) /**< Interrupt error mask*/
|
||||
#define GPDMA_DMACCxConfig_ITC ((1UL<<15)) /**< Terminal count interrupt mask*/
|
||||
#define GPDMA_DMACCxConfig_L ((1UL<<16)) /**< Lock*/
|
||||
#define GPDMA_DMACCxConfig_A ((1UL<<17)) /**< Active*/
|
||||
#define GPDMA_DMACCxConfig_H ((1UL<<18)) /**< Halt*/
|
||||
/** DMA Channel Configuration registers bit mask */
|
||||
#define GPDMA_DMACCxConfig_BITMASK ((0x7FFFF))
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/* Macros check GPDMA channel */
|
||||
#define PARAM_GPDMA_CHANNEL(n) (n<=7)
|
||||
|
||||
/* Macros check GPDMA connection type */
|
||||
#define PARAM_GPDMA_CONN(n) ((n==GPDMA_CONN_SSP0_Tx) || (n==GPDMA_CONN_SSP0_Rx) \
|
||||
|| (n==GPDMA_CONN_SSP1_Tx) || (n==GPDMA_CONN_SSP1_Rx) \
|
||||
|| (n==GPDMA_CONN_ADC) || (n==GPDMA_CONN_I2S_Channel_0) \
|
||||
|| (n==GPDMA_CONN_I2S_Channel_1) || (n==GPDMA_CONN_DAC) \
|
||||
|| (n==GPDMA_CONN_UART0_Tx) || (n==GPDMA_CONN_UART0_Rx) \
|
||||
|| (n==GPDMA_CONN_UART1_Tx) || (n==GPDMA_CONN_UART1_Rx) \
|
||||
|| (n==GPDMA_CONN_UART2_Tx) || (n==GPDMA_CONN_UART2_Rx) \
|
||||
|| (n==GPDMA_CONN_UART3_Tx) || (n==GPDMA_CONN_UART3_Rx) \
|
||||
|| (n==GPDMA_CONN_MAT0_0) || (n==GPDMA_CONN_MAT0_1) \
|
||||
|| (n==GPDMA_CONN_MAT1_0) || (n==GPDMA_CONN_MAT1_1) \
|
||||
|| (n==GPDMA_CONN_MAT2_0) || (n==GPDMA_CONN_MAT2_1) \
|
||||
|| (n==GPDMA_CONN_MAT3_0) || (n==GPDMA_CONN_MAT3_1))
|
||||
|
||||
/* Macros check GPDMA burst size type */
|
||||
#define PARAM_GPDMA_BSIZE(n) ((n==GPDMA_BSIZE_1) || (n==GPDMA_BSIZE_4) \
|
||||
|| (n==GPDMA_BSIZE_8) || (n==GPDMA_BSIZE_16) \
|
||||
|| (n==GPDMA_BSIZE_32) || (n==GPDMA_BSIZE_64) \
|
||||
|| (n==GPDMA_BSIZE_128) || (n==GPDMA_BSIZE_256))
|
||||
|
||||
/* Macros check GPDMA width type */
|
||||
#define PARAM_GPDMA_WIDTH(n) ((n==GPDMA_WIDTH_BYTE) || (n==GPDMA_WIDTH_HALFWORD) \
|
||||
|| (n==GPDMA_WIDTH_WORD))
|
||||
|
||||
/* Macros check GPDMA status type */
|
||||
#define PARAM_GPDMA_STAT(n) ((n==GPDMA_STAT_INT) || (n==GPDMA_STAT_INTTC) \
|
||||
|| (n==GPDMA_STAT_INTERR) || (n==GPDMA_STAT_RAWINTTC) \
|
||||
|| (n==GPDMA_STAT_RAWINTERR) || (n==GPDMA_STAT_ENABLED_CH))
|
||||
|
||||
/* Macros check GPDMA transfer type */
|
||||
#define PARAM_GPDMA_TRANSFERTYPE(n) ((n==GPDMA_TRANSFERTYPE_M2M)||(n==GPDMA_TRANSFERTYPE_M2P) \
|
||||
||(n==GPDMA_TRANSFERTYPE_P2M)||(n==GPDMA_TRANSFERTYPE_P2P))
|
||||
|
||||
/* Macros check GPDMA state clear type */
|
||||
#define PARAM_GPDMA_STATCLR(n) ((n==GPDMA_STATCLR_INTTC) || (n==GPDMA_STATCLR_INTERR))
|
||||
|
||||
/* Macros check GPDMA request select type */
|
||||
#define PARAM_GPDMA_REQSEL(n) ((n==GPDMA_REQSEL_UART) || (n==GPDMA_REQSEL_TIMER))
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup GPDMA_Public_Types GPDMA Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief GPDMA Status enumeration
|
||||
*/
|
||||
typedef enum {
|
||||
GPDMA_STAT_INT, /**< GPDMA Interrupt Status */
|
||||
GPDMA_STAT_INTTC, /**< GPDMA Interrupt Terminal Count Request Status */
|
||||
GPDMA_STAT_INTERR, /**< GPDMA Interrupt Error Status */
|
||||
GPDMA_STAT_RAWINTTC, /**< GPDMA Raw Interrupt Terminal Count Status */
|
||||
GPDMA_STAT_RAWINTERR, /**< GPDMA Raw Error Interrupt Status */
|
||||
GPDMA_STAT_ENABLED_CH /**< GPDMA Enabled Channel Status */
|
||||
} GPDMA_Status_Type;
|
||||
|
||||
/**
|
||||
* @brief GPDMA Interrupt clear status enumeration
|
||||
*/
|
||||
typedef enum{
|
||||
GPDMA_STATCLR_INTTC, /**< GPDMA Interrupt Terminal Count Request Clear */
|
||||
GPDMA_STATCLR_INTERR /**< GPDMA Interrupt Error Clear */
|
||||
}GPDMA_StateClear_Type;
|
||||
|
||||
/**
|
||||
* @brief GPDMA Channel configuration structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t ChannelNum; /**< DMA channel number, should be in
|
||||
range from 0 to 7.
|
||||
Note: DMA channel 0 has the highest priority
|
||||
and DMA channel 7 the lowest priority.
|
||||
*/
|
||||
uint32_t TransferSize; /**< Length/Size of transfer */
|
||||
uint32_t TransferWidth; /**< Transfer width - used for TransferType is GPDMA_TRANSFERTYPE_M2M only */
|
||||
uint32_t SrcMemAddr; /**< Physical Source Address, used in case TransferType is chosen as
|
||||
GPDMA_TRANSFERTYPE_M2M or GPDMA_TRANSFERTYPE_M2P */
|
||||
uint32_t DstMemAddr; /**< Physical Destination Address, used in case TransferType is chosen as
|
||||
GPDMA_TRANSFERTYPE_M2M or GPDMA_TRANSFERTYPE_P2M */
|
||||
uint32_t TransferType; /**< Transfer Type, should be one of the following:
|
||||
- GPDMA_TRANSFERTYPE_M2M: Memory to memory - DMA control
|
||||
- GPDMA_TRANSFERTYPE_M2P: Memory to peripheral - DMA control
|
||||
- GPDMA_TRANSFERTYPE_P2M: Peripheral to memory - DMA control
|
||||
- GPDMA_TRANSFERTYPE_P2P: Source peripheral to destination peripheral - DMA control
|
||||
*/
|
||||
uint32_t SrcConn; /**< Peripheral Source Connection type, used in case TransferType is chosen as
|
||||
GPDMA_TRANSFERTYPE_P2M or GPDMA_TRANSFERTYPE_P2P, should be one of
|
||||
following:
|
||||
- GPDMA_CONN_SSP0_Tx: SSP0, Tx
|
||||
- GPDMA_CONN_SSP0_Rx: SSP0, Rx
|
||||
- GPDMA_CONN_SSP1_Tx: SSP1, Tx
|
||||
- GPDMA_CONN_SSP1_Rx: SSP1, Rx
|
||||
- GPDMA_CONN_ADC: ADC
|
||||
- GPDMA_CONN_I2S_Channel_0: I2S Channel 0
|
||||
- GPDMA_CONN_I2S_Channel_1: I2S Channel 1
|
||||
- GPDMA_CONN_DAC: DAC
|
||||
- GPDMA_CONN_UART0_Tx_MAT0_0: UART0 Tx / MAT0.0
|
||||
- GPDMA_CONN_UART0_Rx_MAT0_1: UART0 Rx / MAT0.1
|
||||
- GPDMA_CONN_UART1_Tx_MAT1_0: UART1 Tx / MAT1.0
|
||||
- GPDMA_CONN_UART1_Rx_MAT1_1: UART1 Rx / MAT1.1
|
||||
- GPDMA_CONN_UART2_Tx_MAT2_0: UART2 Tx / MAT2.0
|
||||
- GPDMA_CONN_UART2_Rx_MAT2_1: UART2 Rx / MAT2.1
|
||||
- GPDMA_CONN_UART3_Tx_MAT3_0: UART3 Tx / MAT3.0
|
||||
- GPDMA_CONN_UART3_Rx_MAT3_1: UART3 Rx / MAT3.1
|
||||
*/
|
||||
uint32_t DstConn; /**< Peripheral Destination Connection type, used in case TransferType is chosen as
|
||||
GPDMA_TRANSFERTYPE_M2P or GPDMA_TRANSFERTYPE_P2P, should be one of
|
||||
following:
|
||||
- GPDMA_CONN_SSP0_Tx: SSP0, Tx
|
||||
- GPDMA_CONN_SSP0_Rx: SSP0, Rx
|
||||
- GPDMA_CONN_SSP1_Tx: SSP1, Tx
|
||||
- GPDMA_CONN_SSP1_Rx: SSP1, Rx
|
||||
- GPDMA_CONN_ADC: ADC
|
||||
- GPDMA_CONN_I2S_Channel_0: I2S Channel 0
|
||||
- GPDMA_CONN_I2S_Channel_1: I2S Channel 1
|
||||
- GPDMA_CONN_DAC: DAC
|
||||
- GPDMA_CONN_UART0_Tx_MAT0_0: UART0 Tx / MAT0.0
|
||||
- GPDMA_CONN_UART0_Rx_MAT0_1: UART0 Rx / MAT0.1
|
||||
- GPDMA_CONN_UART1_Tx_MAT1_0: UART1 Tx / MAT1.0
|
||||
- GPDMA_CONN_UART1_Rx_MAT1_1: UART1 Rx / MAT1.1
|
||||
- GPDMA_CONN_UART2_Tx_MAT2_0: UART2 Tx / MAT2.0
|
||||
- GPDMA_CONN_UART2_Rx_MAT2_1: UART2 Rx / MAT2.1
|
||||
- GPDMA_CONN_UART3_Tx_MAT3_0: UART3 Tx / MAT3.0
|
||||
- GPDMA_CONN_UART3_Rx_MAT3_1: UART3 Rx / MAT3.1
|
||||
*/
|
||||
uint32_t DMALLI; /**< Linker List Item structure data address
|
||||
if there's no Linker List, set as '0'
|
||||
*/
|
||||
} GPDMA_Channel_CFG_Type;
|
||||
|
||||
/**
|
||||
* @brief GPDMA Linker List Item structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t SrcAddr; /**< Source Address */
|
||||
uint32_t DstAddr; /**< Destination address */
|
||||
uint32_t NextLLI; /**< Next LLI address, otherwise set to '0' */
|
||||
uint32_t Control; /**< GPDMA Control of this LLI */
|
||||
} GPDMA_LLI_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup GPDMA_Public_Functions GPDMA Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void GPDMA_Init(void);
|
||||
//Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig, fnGPDMACbs_Type *pfnGPDMACbs);
|
||||
Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig);
|
||||
IntStatus GPDMA_IntGetStatus(GPDMA_Status_Type type, uint8_t channel);
|
||||
void GPDMA_ClearIntPending(GPDMA_StateClear_Type type, uint8_t channel);
|
||||
void GPDMA_ChannelCmd(uint8_t channelNum, FunctionalState NewState);
|
||||
//void GPDMA_IntHandler(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_GPDMA_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,177 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_gpio.h 2010-06-18
|
||||
*//**
|
||||
* @file lpc17xx_gpio.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for GPDMA firmware library on LPC17xx
|
||||
* @version 3.0
|
||||
* @date 18. June. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup GPIO GPIO (General Purpose Input/Output)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_GPIO_H_
|
||||
#define LPC17XX_GPIO_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup GPIO_Public_Macros GPIO Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** Fast GPIO port 0 byte accessible definition */
|
||||
#define GPIO0_Byte ((GPIO_Byte_TypeDef *)(LPC_GPIO0_BASE))
|
||||
/** Fast GPIO port 1 byte accessible definition */
|
||||
#define GPIO1_Byte ((GPIO_Byte_TypeDef *)(LPC_GPIO1_BASE))
|
||||
/** Fast GPIO port 2 byte accessible definition */
|
||||
#define GPIO2_Byte ((GPIO_Byte_TypeDef *)(LPC_GPIO2_BASE))
|
||||
/** Fast GPIO port 3 byte accessible definition */
|
||||
#define GPIO3_Byte ((GPIO_Byte_TypeDef *)(LPC_GPIO3_BASE))
|
||||
/** Fast GPIO port 4 byte accessible definition */
|
||||
#define GPIO4_Byte ((GPIO_Byte_TypeDef *)(LPC_GPIO4_BASE))
|
||||
|
||||
|
||||
/** Fast GPIO port 0 half-word accessible definition */
|
||||
#define GPIO0_HalfWord ((GPIO_HalfWord_TypeDef *)(LPC_GPIO0_BASE))
|
||||
/** Fast GPIO port 1 half-word accessible definition */
|
||||
#define GPIO1_HalfWord ((GPIO_HalfWord_TypeDef *)(LPC_GPIO1_BASE))
|
||||
/** Fast GPIO port 2 half-word accessible definition */
|
||||
#define GPIO2_HalfWord ((GPIO_HalfWord_TypeDef *)(LPC_GPIO2_BASE))
|
||||
/** Fast GPIO port 3 half-word accessible definition */
|
||||
#define GPIO3_HalfWord ((GPIO_HalfWord_TypeDef *)(LPC_GPIO3_BASE))
|
||||
/** Fast GPIO port 4 half-word accessible definition */
|
||||
#define GPIO4_HalfWord ((GPIO_HalfWord_TypeDef *)(LPC_GPIO4_BASE))
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup GPIO_Public_Types GPIO Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Fast GPIO port byte type definition
|
||||
*/
|
||||
typedef struct {
|
||||
__IO uint8_t FIODIR[4]; /**< FIO direction register in byte-align */
|
||||
uint32_t RESERVED0[3]; /**< Reserved */
|
||||
__IO uint8_t FIOMASK[4]; /**< FIO mask register in byte-align */
|
||||
__IO uint8_t FIOPIN[4]; /**< FIO pin register in byte align */
|
||||
__IO uint8_t FIOSET[4]; /**< FIO set register in byte-align */
|
||||
__O uint8_t FIOCLR[4]; /**< FIO clear register in byte-align */
|
||||
} GPIO_Byte_TypeDef;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Fast GPIO port half-word type definition
|
||||
*/
|
||||
typedef struct {
|
||||
__IO uint16_t FIODIRL; /**< FIO direction register lower halfword part */
|
||||
__IO uint16_t FIODIRU; /**< FIO direction register upper halfword part */
|
||||
uint32_t RESERVED0[3]; /**< Reserved */
|
||||
__IO uint16_t FIOMASKL; /**< FIO mask register lower halfword part */
|
||||
__IO uint16_t FIOMASKU; /**< FIO mask register upper halfword part */
|
||||
__IO uint16_t FIOPINL; /**< FIO pin register lower halfword part */
|
||||
__IO uint16_t FIOPINU; /**< FIO pin register upper halfword part */
|
||||
__IO uint16_t FIOSETL; /**< FIO set register lower halfword part */
|
||||
__IO uint16_t FIOSETU; /**< FIO set register upper halfword part */
|
||||
__O uint16_t FIOCLRL; /**< FIO clear register lower halfword part */
|
||||
__O uint16_t FIOCLRU; /**< FIO clear register upper halfword part */
|
||||
} GPIO_HalfWord_TypeDef;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup GPIO_Public_Functions GPIO Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* GPIO style ------------------------------- */
|
||||
void GPIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir);
|
||||
void GPIO_SetValue(uint8_t portNum, uint32_t bitValue);
|
||||
void GPIO_ClearValue(uint8_t portNum, uint32_t bitValue);
|
||||
uint32_t GPIO_ReadValue(uint8_t portNum);
|
||||
void GPIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState);
|
||||
FunctionalState GPIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState);
|
||||
void GPIO_ClearInt(uint8_t portNum, uint32_t bitValue);
|
||||
|
||||
/* FIO (word-accessible) style ------------------------------- */
|
||||
void FIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir);
|
||||
void FIO_SetValue(uint8_t portNum, uint32_t bitValue);
|
||||
void FIO_ClearValue(uint8_t portNum, uint32_t bitValue);
|
||||
uint32_t FIO_ReadValue(uint8_t portNum);
|
||||
void FIO_SetMask(uint8_t portNum, uint32_t bitValue, uint8_t maskValue);
|
||||
void FIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState);
|
||||
FunctionalState FIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState);
|
||||
void FIO_ClearInt(uint8_t portNum, uint32_t pinNum);
|
||||
|
||||
/* FIO (halfword-accessible) style ------------------------------- */
|
||||
void FIO_HalfWordSetDir(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t dir);
|
||||
void FIO_HalfWordSetMask(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t maskValue);
|
||||
void FIO_HalfWordSetValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue);
|
||||
void FIO_HalfWordClearValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue);
|
||||
uint16_t FIO_HalfWordReadValue(uint8_t portNum, uint8_t halfwordNum);
|
||||
|
||||
/* FIO (byte-accessible) style ------------------------------- */
|
||||
void FIO_ByteSetDir(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t dir);
|
||||
void FIO_ByteSetMask(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t maskValue);
|
||||
void FIO_ByteSetValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue);
|
||||
void FIO_ByteClearValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue);
|
||||
uint8_t FIO_ByteReadValue(uint8_t portNum, uint8_t byteNum);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_GPIO_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,434 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_i2c.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_i2c.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for I2C firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup I2C I2C (Inter-IC Control bus)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_I2C_H_
|
||||
#define LPC17XX_I2C_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup I2C_Private_Macros I2C Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*******************************************************************//**
|
||||
* I2C Control Set register description
|
||||
*********************************************************************/
|
||||
#define I2C_I2CONSET_AA ((0x04)) /*!< Assert acknowledge flag */
|
||||
#define I2C_I2CONSET_SI ((0x08)) /*!< I2C interrupt flag */
|
||||
#define I2C_I2CONSET_STO ((0x10)) /*!< STOP flag */
|
||||
#define I2C_I2CONSET_STA ((0x20)) /*!< START flag */
|
||||
#define I2C_I2CONSET_I2EN ((0x40)) /*!< I2C interface enable */
|
||||
|
||||
/*******************************************************************//**
|
||||
* I2C Control Clear register description
|
||||
*********************************************************************/
|
||||
/** Assert acknowledge Clear bit */
|
||||
#define I2C_I2CONCLR_AAC ((1<<2))
|
||||
/** I2C interrupt Clear bit */
|
||||
#define I2C_I2CONCLR_SIC ((1<<3))
|
||||
/** I2C STOP Clear bit */
|
||||
#define I2C_I2CONCLR_STOC ((1<<4))
|
||||
/** START flag Clear bit */
|
||||
#define I2C_I2CONCLR_STAC ((1<<5))
|
||||
/** I2C interface Disable bit */
|
||||
#define I2C_I2CONCLR_I2ENC ((1<<6))
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Status Code definition (I2C Status register)
|
||||
*********************************************************************/
|
||||
/* Return Code in I2C status register */
|
||||
#define I2C_STAT_CODE_BITMASK ((0xF8))
|
||||
|
||||
/* I2C return status code definitions ----------------------------- */
|
||||
|
||||
/** No relevant information */
|
||||
#define I2C_I2STAT_NO_INF ((0xF8))
|
||||
|
||||
/** Bus Error */
|
||||
#define I2C_I2STAT_BUS_ERROR ((0x00))
|
||||
|
||||
/* Master transmit mode -------------------------------------------- */
|
||||
/** A start condition has been transmitted */
|
||||
#define I2C_I2STAT_M_TX_START ((0x08))
|
||||
|
||||
/** A repeat start condition has been transmitted */
|
||||
#define I2C_I2STAT_M_TX_RESTART ((0x10))
|
||||
|
||||
/** SLA+W has been transmitted, ACK has been received */
|
||||
#define I2C_I2STAT_M_TX_SLAW_ACK ((0x18))
|
||||
|
||||
/** SLA+W has been transmitted, NACK has been received */
|
||||
#define I2C_I2STAT_M_TX_SLAW_NACK ((0x20))
|
||||
|
||||
/** Data has been transmitted, ACK has been received */
|
||||
#define I2C_I2STAT_M_TX_DAT_ACK ((0x28))
|
||||
|
||||
/** Data has been transmitted, NACK has been received */
|
||||
#define I2C_I2STAT_M_TX_DAT_NACK ((0x30))
|
||||
|
||||
/** Arbitration lost in SLA+R/W or Data bytes */
|
||||
#define I2C_I2STAT_M_TX_ARB_LOST ((0x38))
|
||||
|
||||
/* Master receive mode -------------------------------------------- */
|
||||
/** A start condition has been transmitted */
|
||||
#define I2C_I2STAT_M_RX_START ((0x08))
|
||||
|
||||
/** A repeat start condition has been transmitted */
|
||||
#define I2C_I2STAT_M_RX_RESTART ((0x10))
|
||||
|
||||
/** Arbitration lost */
|
||||
#define I2C_I2STAT_M_RX_ARB_LOST ((0x38))
|
||||
|
||||
/** SLA+R has been transmitted, ACK has been received */
|
||||
#define I2C_I2STAT_M_RX_SLAR_ACK ((0x40))
|
||||
|
||||
/** SLA+R has been transmitted, NACK has been received */
|
||||
#define I2C_I2STAT_M_RX_SLAR_NACK ((0x48))
|
||||
|
||||
/** Data has been received, ACK has been returned */
|
||||
#define I2C_I2STAT_M_RX_DAT_ACK ((0x50))
|
||||
|
||||
/** Data has been received, NACK has been return */
|
||||
#define I2C_I2STAT_M_RX_DAT_NACK ((0x58))
|
||||
|
||||
/* Slave receive mode -------------------------------------------- */
|
||||
/** Own slave address has been received, ACK has been returned */
|
||||
#define I2C_I2STAT_S_RX_SLAW_ACK ((0x60))
|
||||
|
||||
/** Arbitration lost in SLA+R/W as master */
|
||||
#define I2C_I2STAT_S_RX_ARB_LOST_M_SLA ((0x68))
|
||||
|
||||
/** General call address has been received, ACK has been returned */
|
||||
#define I2C_I2STAT_S_RX_GENCALL_ACK ((0x70))
|
||||
|
||||
/** Arbitration lost in SLA+R/W (GENERAL CALL) as master */
|
||||
#define I2C_I2STAT_S_RX_ARB_LOST_M_GENCALL ((0x78))
|
||||
|
||||
/** Previously addressed with own SLV address;
|
||||
* Data has been received, ACK has been return */
|
||||
#define I2C_I2STAT_S_RX_PRE_SLA_DAT_ACK ((0x80))
|
||||
|
||||
/** Previously addressed with own SLA;
|
||||
* Data has been received and NOT ACK has been return */
|
||||
#define I2C_I2STAT_S_RX_PRE_SLA_DAT_NACK ((0x88))
|
||||
|
||||
/** Previously addressed with General Call;
|
||||
* Data has been received and ACK has been return */
|
||||
#define I2C_I2STAT_S_RX_PRE_GENCALL_DAT_ACK ((0x90))
|
||||
|
||||
/** Previously addressed with General Call;
|
||||
* Data has been received and NOT ACK has been return */
|
||||
#define I2C_I2STAT_S_RX_PRE_GENCALL_DAT_NACK ((0x98))
|
||||
|
||||
/** A STOP condition or repeated START condition has
|
||||
* been received while still addressed as SLV/REC
|
||||
* (Slave Receive) or SLV/TRX (Slave Transmit) */
|
||||
#define I2C_I2STAT_S_RX_STA_STO_SLVREC_SLVTRX ((0xA0))
|
||||
|
||||
/** Slave transmit mode */
|
||||
/** Own SLA+R has been received, ACK has been returned */
|
||||
#define I2C_I2STAT_S_TX_SLAR_ACK ((0xA8))
|
||||
|
||||
/** Arbitration lost in SLA+R/W as master */
|
||||
#define I2C_I2STAT_S_TX_ARB_LOST_M_SLA ((0xB0))
|
||||
|
||||
/** Data has been transmitted, ACK has been received */
|
||||
#define I2C_I2STAT_S_TX_DAT_ACK ((0xB8))
|
||||
|
||||
/** Data has been transmitted, NACK has been received */
|
||||
#define I2C_I2STAT_S_TX_DAT_NACK ((0xC0))
|
||||
|
||||
/** Last data byte in I2DAT has been transmitted (AA = 0);
|
||||
ACK has been received */
|
||||
#define I2C_I2STAT_S_TX_LAST_DAT_ACK ((0xC8))
|
||||
|
||||
/** Time out in case of using I2C slave mode */
|
||||
#define I2C_SLAVE_TIME_OUT 0x10000UL
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Data register definition
|
||||
*********************************************************************/
|
||||
/** Mask for I2DAT register*/
|
||||
#define I2C_I2DAT_BITMASK ((0xFF))
|
||||
|
||||
/** Idle data value will be send out in slave mode in case of the actual
|
||||
* expecting data requested from the master is greater than its sending data
|
||||
* length that can be supported */
|
||||
#define I2C_I2DAT_IDLE_CHAR (0xFF)
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Monitor mode control register description
|
||||
*********************************************************************/
|
||||
#define I2C_I2MMCTRL_MM_ENA ((1<<0)) /**< Monitor mode enable */
|
||||
#define I2C_I2MMCTRL_ENA_SCL ((1<<1)) /**< SCL output enable */
|
||||
#define I2C_I2MMCTRL_MATCH_ALL ((1<<2)) /**< Select interrupt register match */
|
||||
#define I2C_I2MMCTRL_BITMASK ((0x07)) /**< Mask for I2MMCTRL register */
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Data buffer register description
|
||||
*********************************************************************/
|
||||
/** I2C Data buffer register bit mask */
|
||||
#define I2DATA_BUFFER_BITMASK ((0xFF))
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Slave Address registers definition
|
||||
*********************************************************************/
|
||||
/** General Call enable bit */
|
||||
#define I2C_I2ADR_GC ((1<<0))
|
||||
|
||||
/** I2C Slave Address registers bit mask */
|
||||
#define I2C_I2ADR_BITMASK ((0xFF))
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C Mask Register definition
|
||||
*********************************************************************/
|
||||
/** I2C Mask Register mask field */
|
||||
#define I2C_I2MASK_MASK(n) ((n&0xFE))
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C SCL HIGH duty cycle Register definition
|
||||
*********************************************************************/
|
||||
/** I2C SCL HIGH duty cycle Register bit mask */
|
||||
#define I2C_I2SCLH_BITMASK ((0xFFFF))
|
||||
|
||||
/********************************************************************//**
|
||||
* I2C SCL LOW duty cycle Register definition
|
||||
*********************************************************************/
|
||||
/** I2C SCL LOW duty cycle Register bit mask */
|
||||
#define I2C_I2SCLL_BITMASK ((0xFFFF))
|
||||
|
||||
|
||||
/* I2C status values */
|
||||
#define I2C_SETUP_STATUS_ARBF (1<<8) /**< Arbitration false */
|
||||
#define I2C_SETUP_STATUS_NOACKF (1<<9) /**< No ACK returned */
|
||||
#define I2C_SETUP_STATUS_DONE (1<<10) /**< Status DONE */
|
||||
|
||||
/*********************************************************************//**
|
||||
* I2C monitor control configuration defines
|
||||
**********************************************************************/
|
||||
#define I2C_MONITOR_CFG_SCL_OUTPUT I2C_I2MMCTRL_ENA_SCL /**< SCL output enable */
|
||||
#define I2C_MONITOR_CFG_MATCHALL I2C_I2MMCTRL_MATCH_ALL /**< Select interrupt register match */
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/* Macros check I2C slave address */
|
||||
#define PARAM_I2C_SLAVEADDR_CH(n) (n<=3)
|
||||
|
||||
/** Macro to determine if it is valid SSP port number */
|
||||
#define PARAM_I2Cx(n) ((((uint32_t *)n)==((uint32_t *)LPC_I2C0)) \
|
||||
|| (((uint32_t *)n)==((uint32_t *)LPC_I2C1)) \
|
||||
|| (((uint32_t *)n)==((uint32_t *)LPC_I2C2)))
|
||||
|
||||
/* Macros check I2C monitor configuration type */
|
||||
#define PARAM_I2C_MONITOR_CFG(n) ((n==I2C_MONITOR_CFG_SCL_OUTPUT) || (I2C_MONITOR_CFG_MATCHALL))
|
||||
|
||||
/* I2C state handle return values */
|
||||
#define I2C_OK 0x00
|
||||
#define I2C_BYTE_SENT 0x01
|
||||
#define I2C_BYTE_RECV 0x02
|
||||
#define I2C_LAST_BYTE_RECV 0x04
|
||||
#define I2C_SEND_END 0x08
|
||||
#define I2C_RECV_END 0x10
|
||||
#define I2C_STA_STO_RECV 0x20
|
||||
|
||||
#define I2C_ERR (0x10000000)
|
||||
#define I2C_NAK_RECV (0x10000000 |0x01)
|
||||
|
||||
#define I2C_CheckError(ErrorCode) (ErrorCode & 0x10000000)
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup I2C_Public_Types I2C Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef enum
|
||||
{
|
||||
I2C_0 = 0,
|
||||
I2C_1,
|
||||
I2C_2
|
||||
} en_I2C_unitId;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
I2C_MASTER_MODE,
|
||||
I2C_SLAVE_MODE,
|
||||
I2C_GENERAL_MODE,
|
||||
} en_I2C_Mode;
|
||||
/**
|
||||
* @brief I2C Own slave address setting structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t SlaveAddrChannel; /**< Slave Address channel in I2C control,
|
||||
should be in range from 0..3
|
||||
*/
|
||||
uint8_t SlaveAddr_7bit; /**< Value of 7-bit slave address */
|
||||
uint8_t GeneralCallState; /**< Enable/Disable General Call Functionality
|
||||
when I2C control being in Slave mode, should be:
|
||||
- ENABLE: Enable General Call function.
|
||||
- DISABLE: Disable General Call function.
|
||||
*/
|
||||
uint8_t SlaveAddrMaskValue; /**< Any bit in this 8-bit value (bit 7:1)
|
||||
which is set to '1' will cause an automatic compare on
|
||||
the corresponding bit of the received address when it
|
||||
is compared to the SlaveAddr_7bit value associated with this
|
||||
mask register. In other words, bits in SlaveAddr_7bit value
|
||||
which are masked are not taken into account in determining
|
||||
an address match
|
||||
*/
|
||||
} I2C_OWNSLAVEADDR_CFG_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Master transfer setup data structure definitions
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t sl_addr7bit; /**< Slave address in 7bit mode */
|
||||
__IO uint8_t* tx_data; /**< Pointer to Transmit data - NULL if data transmit
|
||||
is not used */
|
||||
uint32_t tx_length; /**< Transmit data length - 0 if data transmit
|
||||
is not used*/
|
||||
__IO uint32_t tx_count; /**< Current Transmit data counter */
|
||||
__IO uint8_t* rx_data; /**< Pointer to Receive data - NULL if data receive
|
||||
is not used */
|
||||
uint32_t rx_length; /**< Receive data length - 0 if data receive is
|
||||
not used */
|
||||
__IO uint32_t rx_count; /**< Current Receive data counter */
|
||||
uint32_t retransmissions_max; /**< Max Re-Transmission value */
|
||||
uint32_t retransmissions_count; /**< Current Re-Transmission counter */
|
||||
__IO uint32_t status; /**< Current status of I2C activity */
|
||||
void (*callback)(void); /**< Pointer to Call back function when transmission complete
|
||||
used in interrupt transfer mode */
|
||||
} I2C_M_SETUP_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Slave transfer setup data structure definitions
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
__IO uint8_t* tx_data;
|
||||
uint32_t tx_length;
|
||||
__IO uint32_t tx_count;
|
||||
__IO uint8_t* rx_data;
|
||||
uint32_t rx_length;
|
||||
__IO uint32_t rx_count;
|
||||
__IO uint32_t status;
|
||||
void (*callback)(void);
|
||||
} I2C_S_SETUP_Type;
|
||||
|
||||
/**
|
||||
* @brief Transfer option type definitions
|
||||
*/
|
||||
typedef enum {
|
||||
I2C_TRANSFER_POLLING = 0, /**< Transfer in polling mode */
|
||||
I2C_TRANSFER_INTERRUPT /**< Transfer in interrupt mode */
|
||||
} I2C_TRANSFER_OPT_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup I2C_Public_Functions I2C Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* I2C Init/DeInit functions ---------- */
|
||||
void I2C_Init(LPC_I2C_TypeDef *I2Cx, uint32_t clockrate);
|
||||
void I2C_DeInit(LPC_I2C_TypeDef* I2Cx);
|
||||
void I2C_Cmd(LPC_I2C_TypeDef* I2Cx, en_I2C_Mode Mode, FunctionalState NewState);
|
||||
|
||||
/* I2C transfer data functions -------- */
|
||||
Status I2C_MasterTransferData(LPC_I2C_TypeDef *I2Cx, \
|
||||
I2C_M_SETUP_Type *TransferCfg, I2C_TRANSFER_OPT_Type Opt);
|
||||
Status I2C_SlaveTransferData(LPC_I2C_TypeDef *I2Cx, \
|
||||
I2C_S_SETUP_Type *TransferCfg, I2C_TRANSFER_OPT_Type Opt);
|
||||
uint32_t I2C_MasterTransferComplete(LPC_I2C_TypeDef *I2Cx);
|
||||
uint32_t I2C_SlaveTransferComplete(LPC_I2C_TypeDef *I2Cx);
|
||||
|
||||
|
||||
void I2C_SetOwnSlaveAddr(LPC_I2C_TypeDef *I2Cx, I2C_OWNSLAVEADDR_CFG_Type *OwnSlaveAddrConfigStruct);
|
||||
uint8_t I2C_GetLastStatusCode(LPC_I2C_TypeDef* I2Cx);
|
||||
|
||||
/* I2C Monitor functions ---------------*/
|
||||
void I2C_MonitorModeConfig(LPC_I2C_TypeDef *I2Cx, uint32_t MonitorCfgType, FunctionalState NewState);
|
||||
void I2C_MonitorModeCmd(LPC_I2C_TypeDef *I2Cx, FunctionalState NewState);
|
||||
uint8_t I2C_MonitorGetDatabuffer(LPC_I2C_TypeDef *I2Cx);
|
||||
BOOL_8 I2C_MonitorHandler(LPC_I2C_TypeDef *I2Cx, uint8_t *buffer, uint32_t size);
|
||||
|
||||
/* I2C Interrupt handler functions ------*/
|
||||
void I2C_IntCmd (LPC_I2C_TypeDef *I2Cx, Bool NewState);
|
||||
void I2C_MasterHandler (LPC_I2C_TypeDef *I2Cx);
|
||||
void I2C_SlaveHandler (LPC_I2C_TypeDef *I2Cx);
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_I2C_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,384 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_i2s.h 2011-06-06
|
||||
*//**
|
||||
* @file lpc17xx_i2s.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for I2S firmware library on LPC17xx
|
||||
* @version 3.1
|
||||
* @date 06. June. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup I2S I2S (Inter-IC Sound bus)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_I2S_H_
|
||||
#define LPC17XX_I2S_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup I2S_Public_Macros I2S Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* I2S configuration parameter defines
|
||||
**********************************************************************/
|
||||
/** I2S Wordwidth bit */
|
||||
#define I2S_WORDWIDTH_8 ((uint32_t)(0))
|
||||
#define I2S_WORDWIDTH_16 ((uint32_t)(1))
|
||||
#define I2S_WORDWIDTH_32 ((uint32_t)(3))
|
||||
/** I2S Channel bit */
|
||||
#define I2S_STEREO ((uint32_t)(0))
|
||||
#define I2S_MONO ((uint32_t)(1))
|
||||
/** I2S Master/Slave mode bit */
|
||||
#define I2S_MASTER_MODE ((uint8_t)(0))
|
||||
#define I2S_SLAVE_MODE ((uint8_t)(1))
|
||||
/** I2S Stop bit */
|
||||
#define I2S_STOP_ENABLE ((uint8_t)(1))
|
||||
#define I2S_STOP_DISABLE ((uint8_t)(0))
|
||||
/** I2S Reset bit */
|
||||
#define I2S_RESET_ENABLE ((uint8_t)(1))
|
||||
#define I2S_RESET_DISABLE ((uint8_t)(0))
|
||||
/** I2S Mute bit */
|
||||
#define I2S_MUTE_ENABLE ((uint8_t)(1))
|
||||
#define I2S_MUTE_DISABLE ((uint8_t)(0))
|
||||
/** I2S Transmit/Receive bit */
|
||||
#define I2S_TX_MODE ((uint8_t)(0))
|
||||
#define I2S_RX_MODE ((uint8_t)(1))
|
||||
/** I2S Clock Select bit */
|
||||
#define I2S_CLKSEL_FRDCLK ((uint8_t)(0))
|
||||
#define I2S_CLKSEL_MCLK ((uint8_t)(2))
|
||||
/** I2S 4-pin Mode bit */
|
||||
#define I2S_4PIN_ENABLE ((uint8_t)(1))
|
||||
#define I2S_4PIN_DISABLE ((uint8_t)(0))
|
||||
/** I2S MCLK Enable bit */
|
||||
#define I2S_MCLK_ENABLE ((uint8_t)(1))
|
||||
#define I2S_MCLK_DISABLE ((uint8_t)(0))
|
||||
/** I2S select DMA bit */
|
||||
#define I2S_DMA_1 ((uint8_t)(0))
|
||||
#define I2S_DMA_2 ((uint8_t)(1))
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup I2S_Private_Macros I2S Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DAO-Digital Audio Output register
|
||||
**********************************************************************/
|
||||
/** I2S wordwide - the number of bytes in data*/
|
||||
#define I2S_DAO_WORDWIDTH_8 ((uint32_t)(0)) /** 8 bit */
|
||||
#define I2S_DAO_WORDWIDTH_16 ((uint32_t)(1)) /** 16 bit */
|
||||
#define I2S_DAO_WORDWIDTH_32 ((uint32_t)(3)) /** 32 bit */
|
||||
/** I2S control mono or stereo format */
|
||||
#define I2S_DAO_MONO ((uint32_t)(1<<2))
|
||||
/** I2S control stop mode */
|
||||
#define I2S_DAO_STOP ((uint32_t)(1<<3))
|
||||
/** I2S control reset mode */
|
||||
#define I2S_DAO_RESET ((uint32_t)(1<<4))
|
||||
/** I2S control master/slave mode */
|
||||
#define I2S_DAO_SLAVE ((uint32_t)(1<<5))
|
||||
/** I2S word select half period minus one */
|
||||
#define I2S_DAO_WS_HALFPERIOD(n) ((uint32_t)(n<<6))
|
||||
/** I2S control mute mode */
|
||||
#define I2S_DAO_MUTE ((uint32_t)(1<<15))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DAI-Digital Audio Input register
|
||||
**********************************************************************/
|
||||
/** I2S wordwide - the number of bytes in data*/
|
||||
#define I2S_DAI_WORDWIDTH_8 ((uint32_t)(0)) /** 8 bit */
|
||||
#define I2S_DAI_WORDWIDTH_16 ((uint32_t)(1)) /** 16 bit */
|
||||
#define I2S_DAI_WORDWIDTH_32 ((uint32_t)(3)) /** 32 bit */
|
||||
/** I2S control mono or stereo format */
|
||||
#define I2S_DAI_MONO ((uint32_t)(1<<2))
|
||||
/** I2S control stop mode */
|
||||
#define I2S_DAI_STOP ((uint32_t)(1<<3))
|
||||
/** I2S control reset mode */
|
||||
#define I2S_DAI_RESET ((uint32_t)(1<<4))
|
||||
/** I2S control master/slave mode */
|
||||
#define I2S_DAI_SLAVE ((uint32_t)(1<<5))
|
||||
/** I2S word select half period minus one (9 bits)*/
|
||||
#define I2S_DAI_WS_HALFPERIOD(n) ((uint32_t)((n&0x1FF)<<6))
|
||||
/** I2S control mute mode */
|
||||
#define I2S_DAI_MUTE ((uint32_t)(1<<15))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for STAT register (Status Feedback register)
|
||||
**********************************************************************/
|
||||
/** I2S Status Receive or Transmit Interrupt */
|
||||
#define I2S_STATE_IRQ ((uint32_t)(1))
|
||||
/** I2S Status Receive or Transmit DMA1 */
|
||||
#define I2S_STATE_DMA1 ((uint32_t)(1<<1))
|
||||
/** I2S Status Receive or Transmit DMA2 */
|
||||
#define I2S_STATE_DMA2 ((uint32_t)(1<<2))
|
||||
/** I2S Status Current level of the Receive FIFO (5 bits)*/
|
||||
#define I2S_STATE_RX_LEVEL(n) ((uint32_t)((n&1F)<<8))
|
||||
/** I2S Status Current level of the Transmit FIFO (5 bits)*/
|
||||
#define I2S_STATE_TX_LEVEL(n) ((uint32_t)((n&1F)<<16))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA1 register (DMA1 Configuration register)
|
||||
**********************************************************************/
|
||||
/** I2S control DMA1 for I2S receive */
|
||||
#define I2S_DMA1_RX_ENABLE ((uint32_t)(1))
|
||||
/** I2S control DMA1 for I2S transmit */
|
||||
#define I2S_DMA1_TX_ENABLE ((uint32_t)(1<<1))
|
||||
/** I2S set FIFO level that trigger a receive DMA request on DMA1 */
|
||||
#define I2S_DMA1_RX_DEPTH(n) ((uint32_t)((n&0x1F)<<8))
|
||||
/** I2S set FIFO level that trigger a transmit DMA request on DMA1 */
|
||||
#define I2S_DMA1_TX_DEPTH(n) ((uint32_t)((n&0x1F)<<16))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for DMA2 register (DMA2 Configuration register)
|
||||
**********************************************************************/
|
||||
/** I2S control DMA2 for I2S receive */
|
||||
#define I2S_DMA2_RX_ENABLE ((uint32_t)(1))
|
||||
/** I2S control DMA1 for I2S transmit */
|
||||
#define I2S_DMA2_TX_ENABLE ((uint32_t)(1<<1))
|
||||
/** I2S set FIFO level that trigger a receive DMA request on DMA1 */
|
||||
#define I2S_DMA2_RX_DEPTH(n) ((uint32_t)((n&0x1F)<<8))
|
||||
/** I2S set FIFO level that trigger a transmit DMA request on DMA1 */
|
||||
#define I2S_DMA2_TX_DEPTH(n) ((uint32_t)((n&0x1F)<<16))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for IRQ register (Interrupt Request Control register)
|
||||
**********************************************************************/
|
||||
/** I2S control I2S receive interrupt */
|
||||
#define I2S_IRQ_RX_ENABLE ((uint32_t)(1))
|
||||
/** I2S control I2S transmit interrupt */
|
||||
#define I2S_IRQ_TX_ENABLE ((uint32_t)(1<<1))
|
||||
/** I2S set the FIFO level on which to create an irq request */
|
||||
#define I2S_IRQ_RX_DEPTH(n) ((uint32_t)((n&0x1F)<<8))
|
||||
/** I2S set the FIFO level on which to create an irq request */
|
||||
#define I2S_IRQ_TX_DEPTH(n) ((uint32_t)((n&0x1F)<<16))
|
||||
|
||||
/********************************************************************************//**
|
||||
* Macro defines for TXRATE/RXRATE register (Transmit/Receive Clock Rate register)
|
||||
*********************************************************************************/
|
||||
/** I2S Transmit MCLK rate denominator */
|
||||
#define I2S_TXRATE_Y_DIVIDER(n) ((uint32_t)(n&0xFF))
|
||||
/** I2S Transmit MCLK rate denominator */
|
||||
#define I2S_TXRATE_X_DIVIDER(n) ((uint32_t)((n&0xFF)<<8))
|
||||
/** I2S Receive MCLK rate denominator */
|
||||
#define I2S_RXRATE_Y_DIVIDER(n) ((uint32_t)(n&0xFF))
|
||||
/** I2S Receive MCLK rate denominator */
|
||||
#define I2S_RXRATE_X_DIVIDER(n) ((uint32_t)((n&0xFF)<<8))
|
||||
|
||||
/*************************************************************************************//**
|
||||
* Macro defines for TXBITRATE & RXBITRATE register (Transmit/Receive Bit Rate register)
|
||||
**************************************************************************************/
|
||||
#define I2S_TXBITRATE(n) ((uint32_t)(n&0x3F))
|
||||
#define I2S_RXBITRATE(n) ((uint32_t)(n&0x3F))
|
||||
|
||||
/**********************************************************************************//**
|
||||
* Macro defines for TXMODE/RXMODE register (Transmit/Receive Mode Control register)
|
||||
************************************************************************************/
|
||||
/** I2S Transmit select clock source (2 bits)*/
|
||||
#define I2S_TXMODE_CLKSEL(n) ((uint32_t)(n&0x03))
|
||||
/** I2S Transmit control 4-pin mode */
|
||||
#define I2S_TXMODE_4PIN_ENABLE ((uint32_t)(1<<2))
|
||||
/** I2S Transmit control the TX_MCLK output */
|
||||
#define I2S_TXMODE_MCENA ((uint32_t)(1<<3))
|
||||
/** I2S Receive select clock source */
|
||||
#define I2S_RXMODE_CLKSEL(n) ((uint32_t)(n&0x03))
|
||||
/** I2S Receive control 4-pin mode */
|
||||
#define I2S_RXMODE_4PIN_ENABLE ((uint32_t)(1<<2))
|
||||
/** I2S Receive control the TX_MCLK output */
|
||||
#define I2S_RXMODE_MCENA ((uint32_t)(1<<3))
|
||||
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/** Macro to determine if it is valid I2S peripheral */
|
||||
#define PARAM_I2Sx(n) (((uint32_t *)n)==((uint32_t *)LPC_I2S))
|
||||
/** Macro to check Data to send valid */
|
||||
#define PRAM_I2S_FREQ(freq) ((freq>=16000)&&(freq <= 96000))
|
||||
/* Macro check I2S word width type */
|
||||
#define PARAM_I2S_WORDWIDTH(n) ((n==I2S_WORDWIDTH_8)||(n==I2S_WORDWIDTH_16)\
|
||||
||(n==I2S_WORDWIDTH_32))
|
||||
/* Macro check I2S channel type */
|
||||
#define PARAM_I2S_CHANNEL(n) ((n==I2S_STEREO)||(n==I2S_MONO))
|
||||
/* Macro check I2S master/slave mode */
|
||||
#define PARAM_I2S_WS_SEL(n) ((n==I2S_MASTER_MODE)||(n==I2S_SLAVE_MODE))
|
||||
/* Macro check I2S stop mode */
|
||||
#define PARAM_I2S_STOP(n) ((n==I2S_STOP_ENABLE)||(n==I2S_STOP_DISABLE))
|
||||
/* Macro check I2S reset mode */
|
||||
#define PARAM_I2S_RESET(n) ((n==I2S_RESET_ENABLE)||(n==I2S_RESET_DISABLE))
|
||||
/* Macro check I2S reset mode */
|
||||
#define PARAM_I2S_MUTE(n) ((n==I2S_MUTE_ENABLE)||(n==I2S_MUTE_DISABLE))
|
||||
/* Macro check I2S transmit/receive mode */
|
||||
#define PARAM_I2S_TRX(n) ((n==I2S_TX_MODE)||(n==I2S_RX_MODE))
|
||||
/* Macro check I2S clock select mode */
|
||||
#define PARAM_I2S_CLKSEL(n) ((n==I2S_CLKSEL_FRDCLK)||(n==I2S_CLKSEL_MCLK))
|
||||
/* Macro check I2S 4-pin mode */
|
||||
#define PARAM_I2S_4PIN(n) ((n==I2S_4PIN_ENABLE)||(n==I2S_4PIN_DISABLE))
|
||||
/* Macro check I2S MCLK mode */
|
||||
#define PARAM_I2S_MCLK(n) ((n==I2S_MCLK_ENABLE)||(n==I2S_MCLK_DISABLE))
|
||||
/* Macro check I2S DMA mode */
|
||||
#define PARAM_I2S_DMA(n) ((n==I2S_DMA_1)||(n==I2S_DMA_2))
|
||||
/* Macro check I2S DMA depth value */
|
||||
#define PARAM_I2S_DMA_DEPTH(n) (n<=31)
|
||||
/* Macro check I2S irq level value */
|
||||
#define PARAM_I2S_IRQ_LEVEL(n) (n<=31)
|
||||
/* Macro check I2S half-period value */
|
||||
#define PARAM_I2S_HALFPERIOD(n) (n<512)
|
||||
/* Macro check I2S bit-rate value */
|
||||
#define PARAM_I2S_BITRATE(n) (n<=63)
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup I2S_Public_Types I2S Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief I2S configuration structure definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t wordwidth; /** the number of bytes in data as follow:
|
||||
-I2S_WORDWIDTH_8: 8 bit data
|
||||
-I2S_WORDWIDTH_16: 16 bit data
|
||||
-I2S_WORDWIDTH_32: 32 bit data */
|
||||
uint8_t mono; /** Set mono/stereo mode, should be:
|
||||
- I2S_STEREO: stereo mode
|
||||
- I2S_MONO: mono mode */
|
||||
uint8_t stop; /** Disables accesses on FIFOs, should be:
|
||||
- I2S_STOP_ENABLE: enable stop mode
|
||||
- I2S_STOP_DISABLE: disable stop mode */
|
||||
uint8_t reset; /** Asynchronously reset tje transmit channel and FIFO, should be:
|
||||
- I2S_RESET_ENABLE: enable reset mode
|
||||
- I2S_RESET_DISABLE: disable reset mode */
|
||||
uint8_t ws_sel; /** Set Master/Slave mode, should be:
|
||||
- I2S_MASTER_MODE: I2S master mode
|
||||
- I2S_SLAVE_MODE: I2S slave mode */
|
||||
uint8_t mute; /** MUTE mode: when true, the transmit channel sends only zeroes, shoule be:
|
||||
- I2S_MUTE_ENABLE: enable mute mode
|
||||
- I2S_MUTE_DISABLE: disable mute mode */
|
||||
uint8_t Reserved0[2];
|
||||
} I2S_CFG_Type;
|
||||
|
||||
/**
|
||||
* @brief I2S DMA configuration structure definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t DMAIndex; /** Select DMA1 or DMA2, should be:
|
||||
- I2S_DMA_1: DMA1
|
||||
- I2S_DMA_2: DMA2 */
|
||||
uint8_t depth; /** FIFO level that triggers a DMA request */
|
||||
uint8_t Reserved0[2];
|
||||
}I2S_DMAConf_Type;
|
||||
|
||||
/**
|
||||
* @brief I2S mode configuration structure definition
|
||||
*/
|
||||
typedef struct{
|
||||
uint8_t clksel; /** Clock source selection, should be:
|
||||
- I2S_CLKSEL_FRDCLK: Select the fractional rate divider clock output
|
||||
- I2S_CLKSEL_MCLK: Select the MCLK signal as the clock source */
|
||||
uint8_t fpin; /** Select four pin mode, should be:
|
||||
- I2S_4PIN_ENABLE: 4-pin enable
|
||||
- I2S_4PIN_DISABLE: 4-pin disable */
|
||||
uint8_t mcena; /** Select MCLK mode, should be:
|
||||
- I2S_MCLK_ENABLE: MCLK enable for output
|
||||
- I2S_MCLK_DISABLE: MCLK disable for output */
|
||||
uint8_t Reserved;
|
||||
}I2S_MODEConf_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup I2S_Public_Functions I2S Public Functions
|
||||
* @{
|
||||
*/
|
||||
/* I2S Init/DeInit functions ---------*/
|
||||
void I2S_Init(LPC_I2S_TypeDef *I2Sx);
|
||||
void I2S_DeInit(LPC_I2S_TypeDef *I2Sx);
|
||||
|
||||
/* I2S configuration functions --------*/
|
||||
void I2S_Config(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, I2S_CFG_Type* ConfigStruct);
|
||||
Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode);
|
||||
void I2S_SetBitRate(LPC_I2S_TypeDef *I2Sx, uint8_t bitrate, uint8_t TRMode);
|
||||
void I2S_ModeConfig(LPC_I2S_TypeDef *I2Sx, I2S_MODEConf_Type* ModeConfig, uint8_t TRMode);
|
||||
uint8_t I2S_GetLevel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
|
||||
/* I2S operate functions -------------*/
|
||||
void I2S_Send(LPC_I2S_TypeDef *I2Sx, uint32_t BufferData);
|
||||
uint32_t I2S_Receive(LPC_I2S_TypeDef* I2Sx);
|
||||
void I2S_Start(LPC_I2S_TypeDef *I2Sx);
|
||||
void I2S_Pause(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
void I2S_Mute(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
void I2S_Stop(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
|
||||
|
||||
/* I2S DMA functions ----------------*/
|
||||
void I2S_DMAConfig(LPC_I2S_TypeDef *I2Sx, I2S_DMAConf_Type* DMAConfig, uint8_t TRMode);
|
||||
void I2S_DMACmd(LPC_I2S_TypeDef *I2Sx, uint8_t DMAIndex,uint8_t TRMode, FunctionalState NewState);
|
||||
|
||||
/* I2S IRQ functions ----------------*/
|
||||
void I2S_IRQCmd(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode, FunctionalState NewState);
|
||||
void I2S_IRQConfig(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, uint8_t level);
|
||||
FunctionalState I2S_GetIRQStatus(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode);
|
||||
uint8_t I2S_GetIRQDepth(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* LPC17XX_SSP_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,153 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_iap.h 2012-04-18
|
||||
*//**
|
||||
* @file lpc17xx_iap.h
|
||||
* @brief Contains all functions support for IAP
|
||||
* on lpc17xx
|
||||
* @version 1.0
|
||||
* @date 18. April. 2012
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
#ifndef _LPC17xx_IAP_H
|
||||
#define _LPC17xx_IAP_H
|
||||
#include "lpc_types.h"
|
||||
|
||||
/** @defgroup IAP IAP (In Application Programming)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup IAP_Public_Macros IAP Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** IAP entry location */
|
||||
#define IAP_LOCATION (0x1FFF1FF1UL)
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup IAP_Public_Types IAP Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief IAP command code definitions
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
IAP_PREPARE = 50, // Prepare sector(s) for write operation
|
||||
IAP_COPY_RAM2FLASH = 51, // Copy RAM to Flash
|
||||
IAP_ERASE = 52, // Erase sector(s)
|
||||
IAP_BLANK_CHECK = 53, // Blank check sector(s)
|
||||
IAP_READ_PART_ID = 54, // Read chip part ID
|
||||
IAP_READ_BOOT_VER = 55, // Read chip boot code version
|
||||
IAP_COMPARE = 56, // Compare memory areas
|
||||
IAP_REINVOKE_ISP = 57, // Reinvoke ISP
|
||||
IAP_READ_SERIAL_NUMBER = 58, // Read serial number
|
||||
} IAP_COMMAND_CODE;
|
||||
|
||||
/**
|
||||
* @brief IAP status code definitions
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
CMD_SUCCESS, // Command is executed successfully.
|
||||
INVALID_COMMAND, // Invalid command.
|
||||
SRC_ADDR_ERROR, // Source address is not on a word boundary.
|
||||
DST_ADDR_ERROR, // Destination address is not on a correct boundary.
|
||||
SRC_ADDR_NOT_MAPPED, // Source address is not mapped in the memory map.
|
||||
DST_ADDR_NOT_MAPPED, // Destination address is not mapped in the memory map.
|
||||
COUNT_ERROR, // Byte count is not multiple of 4 or is not a permitted value.
|
||||
INVALID_SECTOR, // Sector number is invalid.
|
||||
SECTOR_NOT_BLANK, // Sector is not blank.
|
||||
SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION, // Command to prepare sector for write operation was not executed.
|
||||
COMPARE_ERROR, // Source and destination data is not same.
|
||||
BUSY, // Flash programming hardware interface is busy.
|
||||
} IAP_STATUS_CODE;
|
||||
|
||||
/**
|
||||
* @brief IAP write length definitions
|
||||
*/
|
||||
typedef enum {
|
||||
IAP_WRITE_256 = 256,
|
||||
IAP_WRITE_512 = 512,
|
||||
IAP_WRITE_1024 = 1024,
|
||||
IAP_WRITE_4096 = 4096,
|
||||
} IAP_WRITE_SIZE;
|
||||
|
||||
/**
|
||||
* @brief IAP command structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t cmd; // Command
|
||||
uint32_t param[4]; // Parameters
|
||||
uint32_t status; // status code
|
||||
uint32_t result[4]; // Result
|
||||
} IAP_COMMAND_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup IAP_Public_Functions IAP Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** Get sector number of an address */
|
||||
uint32_t GetSecNum (uint32_t adr);
|
||||
/** Prepare sector(s) for write operation */
|
||||
IAP_STATUS_CODE PrepareSector(uint32_t start_sec, uint32_t end_sec);
|
||||
/** Copy RAM to Flash */
|
||||
IAP_STATUS_CODE CopyRAM2Flash(uint8_t * dest, uint8_t* source, IAP_WRITE_SIZE size);
|
||||
/** Prepare sector(s) for write operation */
|
||||
IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec);
|
||||
/** Blank check sectors */
|
||||
IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
|
||||
uint32_t *first_nblank_loc,
|
||||
uint32_t *first_nblank_val);
|
||||
/** Read part identification number */
|
||||
IAP_STATUS_CODE ReadPartID(uint32_t *partID);
|
||||
/** Read boot code version */
|
||||
IAP_STATUS_CODE ReadBootCodeVer(uint8_t *major, uint8_t* minor);
|
||||
/** Read Device serial number */
|
||||
IAP_STATUS_CODE ReadDeviceSerialNum(uint32_t *uid);
|
||||
/** Compare memory */
|
||||
IAP_STATUS_CODE Compare(uint8_t *addr1, uint8_t *addr2, uint32_t size);
|
||||
/** Invoke ISP */
|
||||
void InvokeISP(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /*_LPC17xx_IAP_H*/
|
||||
|
|
@ -1,181 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_libcfg_default.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_libcfg_default.h
|
||||
* @brief Default Library configuration header file
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Library Configuration group ----------------------------------------------------------- */
|
||||
/** @defgroup LIBCFG_DEFAULT LIBCFG_DEFAULT (Default Library Configuration)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_LIBCFG_DEFAULT_H_
|
||||
#define LPC17XX_LIBCFG_DEFAULT_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup LIBCFG_DEFAULT_Public_Macros LIBCFG_DEFAULT Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/************************** DEBUG MODE DEFINITIONS *********************************/
|
||||
/* Un-comment the line below to compile the library in DEBUG mode, this will expanse
|
||||
the "CHECK_PARAM" macro in the FW library code */
|
||||
//#define DEBUG
|
||||
|
||||
|
||||
/******************* PERIPHERAL FW LIBRARY CONFIGURATION DEFINITIONS ***********************/
|
||||
/* Comment the line below to disable the specific peripheral inclusion */
|
||||
|
||||
/* DEBUG_FRAMWORK ------------------------------ */
|
||||
#define _DBGFWK
|
||||
|
||||
/* GPIO ------------------------------- */
|
||||
#define _GPIO
|
||||
|
||||
/* EXTI ------------------------------- */
|
||||
#define _EXTI
|
||||
|
||||
/* UART ------------------------------- */
|
||||
#define _UART
|
||||
#define _UART0
|
||||
#define _UART1
|
||||
#define _UART2
|
||||
#define _UART3
|
||||
|
||||
/* SPI ------------------------------- */
|
||||
#define _SPI
|
||||
|
||||
/* SYSTICK --------------------------- */
|
||||
#define _SYSTICK
|
||||
|
||||
/* SSP ------------------------------- */
|
||||
#define _SSP
|
||||
#define _SSP0
|
||||
#define _SSP1
|
||||
|
||||
|
||||
/* I2C ------------------------------- */
|
||||
#define _I2C
|
||||
#define _I2C0
|
||||
#define _I2C1
|
||||
#define _I2C2
|
||||
|
||||
/* TIMER ------------------------------- */
|
||||
#define _TIM
|
||||
|
||||
/* WDT ------------------------------- */
|
||||
#define _WDT
|
||||
|
||||
|
||||
/* GPDMA ------------------------------- */
|
||||
#define _GPDMA
|
||||
|
||||
|
||||
/* DAC ------------------------------- */
|
||||
#define _DAC
|
||||
|
||||
/* DAC ------------------------------- */
|
||||
#define _ADC
|
||||
|
||||
|
||||
/* PWM ------------------------------- */
|
||||
#define _PWM
|
||||
#define _PWM1
|
||||
|
||||
/* RTC ------------------------------- */
|
||||
#define _RTC
|
||||
|
||||
/* I2S ------------------------------- */
|
||||
#define _I2S
|
||||
|
||||
/* USB device ------------------------------- */
|
||||
#define _USBDEV
|
||||
#define _USB_DMA
|
||||
|
||||
/* QEI ------------------------------- */
|
||||
#define _QEI
|
||||
|
||||
/* MCPWM ------------------------------- */
|
||||
#define _MCPWM
|
||||
|
||||
/* CAN--------------------------------*/
|
||||
#define _CAN
|
||||
|
||||
/* RIT ------------------------------- */
|
||||
#define _RIT
|
||||
|
||||
/* EMAC ------------------------------ */
|
||||
#define _EMAC
|
||||
|
||||
/************************** GLOBAL/PUBLIC MACRO DEFINITIONS *********************************/
|
||||
|
||||
#ifdef DEBUG
|
||||
/*******************************************************************************
|
||||
* @brief The CHECK_PARAM macro is used for function's parameters check.
|
||||
* It is used only if the library is compiled in DEBUG mode.
|
||||
* @param[in] expr - If expr is false, it calls check_failed() function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* - If expr is true, it returns no value.
|
||||
* @return None
|
||||
*******************************************************************************/
|
||||
#define CHECK_PARAM(expr) ((expr) ? (void)0 : check_failed((uint8_t *)__FILE__, __LINE__))
|
||||
#else
|
||||
#define CHECK_PARAM(expr)
|
||||
#endif /* DEBUG */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup LIBCFG_DEFAULT_Public_Functions LIBCFG_DEFAULT Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifdef DEBUG
|
||||
void check_failed(uint8_t *file, uint32_t line);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* LPC17XX_LIBCFG_DEFAULT_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,329 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_mcpwm.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_mcpwm.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Motor Control PWM firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup MCPWM MCPWM (Motor Control PWM)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_MCPWM_H_
|
||||
#define LPC17XX_MCPWM_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup MCPWM_Public_Macros MCPWM Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** Edge aligned mode for channel in MCPWM */
|
||||
#define MCPWM_CHANNEL_EDGE_MODE ((uint32_t)(0))
|
||||
/** Center aligned mode for channel in MCPWM */
|
||||
#define MCPWM_CHANNEL_CENTER_MODE ((uint32_t)(1))
|
||||
|
||||
/** Polarity of the MCOA and MCOB pins: Passive state is LOW, active state is HIGH */
|
||||
#define MCPWM_CHANNEL_PASSIVE_LO ((uint32_t)(0))
|
||||
/** Polarity of the MCOA and MCOB pins: Passive state is HIGH, active state is LOW */
|
||||
#define MCPWM_CHANNEL_PASSIVE_HI ((uint32_t)(1))
|
||||
|
||||
/* Output Patent in 3-phase DC mode, the internal MCOA0 signal is routed to any or all of
|
||||
* the six output pins under the control of the bits in this register */
|
||||
#define MCPWM_PATENT_A0 ((uint32_t)(1<<0)) /**< MCOA0 tracks internal MCOA0 */
|
||||
#define MCPWM_PATENT_B0 ((uint32_t)(1<<1)) /**< MCOB0 tracks internal MCOA0 */
|
||||
#define MCPWM_PATENT_A1 ((uint32_t)(1<<2)) /**< MCOA1 tracks internal MCOA0 */
|
||||
#define MCPWM_PATENT_B1 ((uint32_t)(1<<3)) /**< MCOB1 tracks internal MCOA0 */
|
||||
#define MCPWM_PATENT_A2 ((uint32_t)(1<<4)) /**< MCOA2 tracks internal MCOA0 */
|
||||
#define MCPWM_PATENT_B2 ((uint32_t)(1<<5)) /**< MCOB2 tracks internal MCOA0 */
|
||||
|
||||
/* Interrupt type in MCPWM */
|
||||
/** Limit interrupt for channel (0) */
|
||||
#define MCPWM_INTFLAG_LIM0 MCPWM_INT_ILIM(0)
|
||||
/** Match interrupt for channel (0) */
|
||||
#define MCPWM_INTFLAG_MAT0 MCPWM_INT_IMAT(0)
|
||||
/** Capture interrupt for channel (0) */
|
||||
#define MCPWM_INTFLAG_CAP0 MCPWM_INT_ICAP(0)
|
||||
|
||||
/** Limit interrupt for channel (1) */
|
||||
#define MCPWM_INTFLAG_LIM1 MCPWM_INT_ILIM(1)
|
||||
/** Match interrupt for channel (1) */
|
||||
#define MCPWM_INTFLAG_MAT1 MCPWM_INT_IMAT(1)
|
||||
/** Capture interrupt for channel (1) */
|
||||
#define MCPWM_INTFLAG_CAP1 MCPWM_INT_ICAP(1)
|
||||
|
||||
/** Limit interrupt for channel (2) */
|
||||
#define MCPWM_INTFLAG_LIM2 MCPWM_INT_ILIM(2)
|
||||
/** Match interrupt for channel (2) */
|
||||
#define MCPWM_INTFLAG_MAT2 MCPWM_INT_IMAT(2)
|
||||
/** Capture interrupt for channel (2) */
|
||||
#define MCPWM_INTFLAG_CAP2 MCPWM_INT_ICAP(2)
|
||||
|
||||
/** Fast abort interrupt */
|
||||
#define MCPWM_INTFLAG_ABORT MCPWM_INT_ABORT
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup MCPWM_Private_Macros MCPWM Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Control register
|
||||
**********************************************************************/
|
||||
/* MCPWM Control register, these macro definitions below can be applied for these
|
||||
* register type:
|
||||
* - MCPWM Control read address
|
||||
* - MCPWM Control set address
|
||||
* - MCPWM Control clear address
|
||||
*/
|
||||
#define MCPWM_CON_RUN(n) ((n<=2) ? ((uint32_t)(1<<((n*8)+0))) : (0)) /**< Stops/starts timer channel n */
|
||||
#define MCPWM_CON_CENTER(n) ((n<=2) ? ((uint32_t)(1<<((n*8)+1))) : (0)) /**< Edge/center aligned operation for channel n */
|
||||
#define MCPWM_CON_POLAR(n) ((n<=2) ? ((uint32_t)(1<<((n*8)+2))) : (0)) /**< Select polarity of the MCOAn and MCOBn pin */
|
||||
#define MCPWM_CON_DTE(n) ((n<=2) ? ((uint32_t)(1<<((n*8)+3))) : (0)) /**< Control the dead-time feature for channel n */
|
||||
#define MCPWM_CON_DISUP(n) ((n<=2) ? ((uint32_t)(1<<((n*8)+4))) : (0)) /**< Enable/Disable update of functional register for channel n */
|
||||
#define MCPWM_CON_INVBDC ((uint32_t)(1<<29)) /**< Control the polarity for all 3 channels */
|
||||
#define MCPWM_CON_ACMODE ((uint32_t)(1<<30)) /**< 3-phase AC mode select */
|
||||
#define MCPWM_CON_DCMODE ((uint32_t)(0x80000000)) /**< 3-phase DC mode select */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Capture Control register
|
||||
**********************************************************************/
|
||||
/* Capture Control register, these macro definitions below can be applied for these
|
||||
* register type:
|
||||
* - MCPWM Capture Control read address
|
||||
* - MCPWM Capture Control set address
|
||||
* - MCPWM Capture control clear address
|
||||
*/
|
||||
/** Enables/Disable channel (cap) capture event on a rising edge on MCI(mci) */
|
||||
#define MCPWM_CAPCON_CAPMCI_RE(cap,mci) (((cap<=2)&&(mci<=2)) ? ((uint32_t)(1<<((cap*6)+(mci*2)+0))) : (0))
|
||||
/** Enables/Disable channel (cap) capture event on a falling edge on MCI(mci) */
|
||||
#define MCPWM_CAPCON_CAPMCI_FE(cap,mci) (((cap<=2)&&(mci<=2)) ? ((uint32_t)(1<<((cap*6)+(mci*2)+1))) : (0))
|
||||
/** TC(n) is reset by channel (n) capture event */
|
||||
#define MCPWM_CAPCON_RT(n) ((n<=2) ? ((uint32_t)(1<<(18+(n)))) : (0))
|
||||
/** Hardware noise filter: channel (n) capture events are delayed */
|
||||
#define MCPWM_CAPCON_HNFCAP(n) ((n<=2) ? ((uint32_t)(1<<(21+(n)))) : (0))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Interrupt register
|
||||
**********************************************************************/
|
||||
/* Interrupt registers, these macro definitions below can be applied for these
|
||||
* register type:
|
||||
* - MCPWM Interrupt Enable read address
|
||||
* - MCPWM Interrupt Enable set address
|
||||
* - MCPWM Interrupt Enable clear address
|
||||
* - MCPWM Interrupt Flags read address
|
||||
* - MCPWM Interrupt Flags set address
|
||||
* - MCPWM Interrupt Flags clear address
|
||||
*/
|
||||
/** Limit interrupt for channel (n) */
|
||||
#define MCPWM_INT_ILIM(n) (((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+0))) : (0))
|
||||
/** Match interrupt for channel (n) */
|
||||
#define MCPWM_INT_IMAT(n) (((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+1))) : (0))
|
||||
/** Capture interrupt for channel (n) */
|
||||
#define MCPWM_INT_ICAP(n) (((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+2))) : (0))
|
||||
/** Fast abort interrupt */
|
||||
#define MCPWM_INT_ABORT ((uint32_t)(1<<15))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Count Control register
|
||||
**********************************************************************/
|
||||
/* MCPWM Count Control register, these macro definitions below can be applied for these
|
||||
* register type:
|
||||
* - MCPWM Count Control read address
|
||||
* - MCPWM Count Control set address
|
||||
* - MCPWM Count Control clear address
|
||||
*/
|
||||
/** Counter(tc) advances on a rising edge on MCI(mci) pin */
|
||||
#define MCPWM_CNTCON_TCMCI_RE(tc,mci) (((tc<=2)&&(mci<=2)) ? ((uint32_t)(1<<((6*tc)+(2*mci)+0))) : (0))
|
||||
/** Counter(cnt) advances on a falling edge on MCI(mci) pin */
|
||||
#define MCPWM_CNTCON_TCMCI_FE(tc,mci) (((tc<=2)&&(mci<=2)) ? ((uint32_t)(1<<((6*tc)+(2*mci)+1))) : (0))
|
||||
/** Channel (n) is in counter mode */
|
||||
#define MCPWM_CNTCON_CNTR(n) ((n<=2) ? ((uint32_t)(1<<(29+n))) : (0))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Dead-time register
|
||||
**********************************************************************/
|
||||
/** Dead time value x for channel n */
|
||||
#define MCPWM_DT(n,x) ((n<=2) ? ((uint32_t)((x&0x3FF)<<(n*10))) : (0))
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Communication Pattern register
|
||||
**********************************************************************/
|
||||
#define MCPWM_CP_A0 ((uint32_t)(1<<0)) /**< MCOA0 tracks internal MCOA0 */
|
||||
#define MCPWM_CP_B0 ((uint32_t)(1<<1)) /**< MCOB0 tracks internal MCOA0 */
|
||||
#define MCPWM_CP_A1 ((uint32_t)(1<<2)) /**< MCOA1 tracks internal MCOA0 */
|
||||
#define MCPWM_CP_B1 ((uint32_t)(1<<3)) /**< MCOB1 tracks internal MCOA0 */
|
||||
#define MCPWM_CP_A2 ((uint32_t)(1<<4)) /**< MCOA2 tracks internal MCOA0 */
|
||||
#define MCPWM_CP_B2 ((uint32_t)(1<<5)) /**< MCOB2 tracks internal MCOA0 */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for MCPWM Capture clear address register
|
||||
**********************************************************************/
|
||||
/** Clear the MCCAP (n) register */
|
||||
#define MCPWM_CAPCLR_CAP(n) ((n<=2) ? ((uint32_t)(1<<n)) : (0))
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup MCPWM_Public_Types MCPWM Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Motor Control PWM Channel Configuration structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t channelType; /**< Edge/center aligned mode for this channel,
|
||||
should be:
|
||||
- MCPWM_CHANNEL_EDGE_MODE: Channel is in Edge mode
|
||||
- MCPWM_CHANNEL_CENTER_MODE: Channel is in Center mode
|
||||
*/
|
||||
uint32_t channelPolarity; /**< Polarity of the MCOA and MCOB pins, should be:
|
||||
- MCPWM_CHANNEL_PASSIVE_LO: Passive state is LOW, active state is HIGH
|
||||
- MCPWM_CHANNEL_PASSIVE_HI: Passive state is HIGH, active state is LOW
|
||||
*/
|
||||
uint32_t channelDeadtimeEnable; /**< Enable/Disable DeadTime function for channel, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t channelDeadtimeValue; /**< DeadTime value, should be less than 0x3FF */
|
||||
uint32_t channelUpdateEnable; /**< Enable/Disable updates of functional registers,
|
||||
should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t channelTimercounterValue; /**< MCPWM Timer Counter value */
|
||||
uint32_t channelPeriodValue; /**< MCPWM Period value */
|
||||
uint32_t channelPulsewidthValue; /**< MCPWM Pulse Width value */
|
||||
} MCPWM_CHANNEL_CFG_Type;
|
||||
|
||||
/**
|
||||
* @brief MCPWM Capture Configuration type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t captureChannel; /**< Capture Channel Number, should be in range from 0 to 2 */
|
||||
uint32_t captureRising; /**< Enable/Disable Capture on Rising Edge event, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t captureFalling; /**< Enable/Disable Capture on Falling Edge event, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t timerReset; /**< Enable/Disable Timer reset function an capture, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t hnfEnable; /**< Enable/Disable Hardware noise filter function, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
} MCPWM_CAPTURE_CFG_Type;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPWM Count Control Configuration type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t counterChannel; /**< Counter Channel Number, should be in range from 0 to 2 */
|
||||
uint32_t countRising; /**< Enable/Disable Capture on Rising Edge event, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
uint32_t countFalling; /**< Enable/Disable Capture on Falling Edge event, should be:
|
||||
- ENABLE.
|
||||
- DISABLE.
|
||||
*/
|
||||
} MCPWM_COUNT_CFG_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup MCPWM_Public_Functions MCPWM Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void MCPWM_Init(LPC_MCPWM_TypeDef *MCPWMx);
|
||||
void MCPWM_ConfigChannel(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CHANNEL_CFG_Type * channelSetup);
|
||||
void MCPWM_WriteToShadow(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CHANNEL_CFG_Type *channelSetup);
|
||||
void MCPWM_ConfigCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
MCPWM_CAPTURE_CFG_Type *captureConfig);
|
||||
void MCPWM_ClearCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel);
|
||||
uint32_t MCPWM_GetCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel);
|
||||
void MCPWM_CountConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
|
||||
uint32_t countMode, MCPWM_COUNT_CFG_Type *countConfig);
|
||||
void MCPWM_Start(LPC_MCPWM_TypeDef *MCPWMx,uint32_t channel0, uint32_t channel1, uint32_t channel2);
|
||||
void MCPWM_Stop(LPC_MCPWM_TypeDef *MCPWMx,uint32_t channel0, uint32_t channel1, uint32_t channel2);
|
||||
void MCPWM_ACMode(LPC_MCPWM_TypeDef *MCPWMx,uint32_t acMode);
|
||||
void MCPWM_DCMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t dcMode,
|
||||
uint32_t outputInvered, uint32_t outputPattern);
|
||||
void MCPWM_IntConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType, FunctionalState NewState);
|
||||
void MCPWM_IntSet(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
|
||||
void MCPWM_IntClear(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
|
||||
FlagStatus MCPWM_GetIntStatus(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_MCPWM_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,76 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_nvic.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_nvic.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Nesting Vectored Interrupt firmware library
|
||||
* on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup NVIC NVIC (Nested Vectored Interrupt Controller)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_NVIC_H_
|
||||
#define LPC17XX_NVIC_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup NVIC_Public_Functions NVIC Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void NVIC_DeInit(void);
|
||||
void NVIC_SCBDeInit(void);
|
||||
void NVIC_SetVTOR(uint32_t offset);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_NVIC_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,203 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_pinsel.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_pinsel.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for Pin connect block firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup PINSEL PINSEL (Pin Selection)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_PINSEL_H_
|
||||
#define LPC17XX_PINSEL_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup PINSEL_Public_Macros PINSEL Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*********************************************************************//**
|
||||
*!< Macros define for PORT Selection
|
||||
***********************************************************************/
|
||||
#define PINSEL_PORT_0 ((0)) /**< PORT 0*/
|
||||
#define PINSEL_PORT_1 ((1)) /**< PORT 1*/
|
||||
#define PINSEL_PORT_2 ((2)) /**< PORT 2*/
|
||||
#define PINSEL_PORT_3 ((3)) /**< PORT 3*/
|
||||
#define PINSEL_PORT_4 ((4)) /**< PORT 4*/
|
||||
|
||||
/***********************************************************************
|
||||
* Macros define for Pin Function selection
|
||||
**********************************************************************/
|
||||
#define PINSEL_FUNC_0 ((0)) /**< default function*/
|
||||
#define PINSEL_FUNC_1 ((1)) /**< first alternate function*/
|
||||
#define PINSEL_FUNC_2 ((2)) /**< second alternate function*/
|
||||
#define PINSEL_FUNC_3 ((3)) /**< third or reserved alternate function*/
|
||||
|
||||
/***********************************************************************
|
||||
* Macros define for Pin Number of Port
|
||||
**********************************************************************/
|
||||
#define PINSEL_PIN_0 ((0)) /**< Pin 0 */
|
||||
#define PINSEL_PIN_1 ((1)) /**< Pin 1 */
|
||||
#define PINSEL_PIN_2 ((2)) /**< Pin 2 */
|
||||
#define PINSEL_PIN_3 ((3)) /**< Pin 3 */
|
||||
#define PINSEL_PIN_4 ((4)) /**< Pin 4 */
|
||||
#define PINSEL_PIN_5 ((5)) /**< Pin 5 */
|
||||
#define PINSEL_PIN_6 ((6)) /**< Pin 6 */
|
||||
#define PINSEL_PIN_7 ((7)) /**< Pin 7 */
|
||||
#define PINSEL_PIN_8 ((8)) /**< Pin 8 */
|
||||
#define PINSEL_PIN_9 ((9)) /**< Pin 9 */
|
||||
#define PINSEL_PIN_10 ((10)) /**< Pin 10 */
|
||||
#define PINSEL_PIN_11 ((11)) /**< Pin 11 */
|
||||
#define PINSEL_PIN_12 ((12)) /**< Pin 12 */
|
||||
#define PINSEL_PIN_13 ((13)) /**< Pin 13 */
|
||||
#define PINSEL_PIN_14 ((14)) /**< Pin 14 */
|
||||
#define PINSEL_PIN_15 ((15)) /**< Pin 15 */
|
||||
#define PINSEL_PIN_16 ((16)) /**< Pin 16 */
|
||||
#define PINSEL_PIN_17 ((17)) /**< Pin 17 */
|
||||
#define PINSEL_PIN_18 ((18)) /**< Pin 18 */
|
||||
#define PINSEL_PIN_19 ((19)) /**< Pin 19 */
|
||||
#define PINSEL_PIN_20 ((20)) /**< Pin 20 */
|
||||
#define PINSEL_PIN_21 ((21)) /**< Pin 21 */
|
||||
#define PINSEL_PIN_22 ((22)) /**< Pin 22 */
|
||||
#define PINSEL_PIN_23 ((23)) /**< Pin 23 */
|
||||
#define PINSEL_PIN_24 ((24)) /**< Pin 24 */
|
||||
#define PINSEL_PIN_25 ((25)) /**< Pin 25 */
|
||||
#define PINSEL_PIN_26 ((26)) /**< Pin 26 */
|
||||
#define PINSEL_PIN_27 ((27)) /**< Pin 27 */
|
||||
#define PINSEL_PIN_28 ((28)) /**< Pin 28 */
|
||||
#define PINSEL_PIN_29 ((29)) /**< Pin 29 */
|
||||
#define PINSEL_PIN_30 ((30)) /**< Pin 30 */
|
||||
#define PINSEL_PIN_31 ((31)) /**< Pin 31 */
|
||||
|
||||
/***********************************************************************
|
||||
* Macros define for Pin mode
|
||||
**********************************************************************/
|
||||
#define PINSEL_PINMODE_PULLUP ((0)) /**< Internal pull-up resistor*/
|
||||
#define PINSEL_PINMODE_TRISTATE ((2)) /**< Tri-state */
|
||||
#define PINSEL_PINMODE_PULLDOWN ((3)) /**< Internal pull-down resistor */
|
||||
|
||||
/***********************************************************************
|
||||
* Macros define for Pin mode (normal/open drain)
|
||||
**********************************************************************/
|
||||
#define PINSEL_PINMODE_NORMAL ((0)) /**< Pin is in the normal (not open drain) mode.*/
|
||||
#define PINSEL_PINMODE_OPENDRAIN ((1)) /**< Pin is in the open drain mode */
|
||||
|
||||
/***********************************************************************
|
||||
* Macros define for I2C mode
|
||||
***********************************************************************/
|
||||
#define PINSEL_I2C_Normal_Mode ((0)) /**< The standard drive mode */
|
||||
#define PINSEL_I2C_Fast_Mode ((1)) /**< Fast Mode Plus drive mode */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup PINSEL_Private_Macros PINSEL Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Pin selection define */
|
||||
/* I2C Pin Configuration register bit description */
|
||||
#define PINSEL_I2CPADCFG_SDADRV0 _BIT(0) /**< Drive mode control for the SDA0 pin, P0.27 */
|
||||
#define PINSEL_I2CPADCFG_SDAI2C0 _BIT(1) /**< I2C mode control for the SDA0 pin, P0.27 */
|
||||
#define PINSEL_I2CPADCFG_SCLDRV0 _BIT(2) /**< Drive mode control for the SCL0 pin, P0.28 */
|
||||
#define PINSEL_I2CPADCFG_SCLI2C0 _BIT(3) /**< I2C mode control for the SCL0 pin, P0.28 */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup PINSEL_Public_Types PINSEL Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Pin configuration structure */
|
||||
typedef struct
|
||||
{
|
||||
uint8_t Portnum; /**< Port Number, should be PINSEL_PORT_x,
|
||||
where x should be in range from 0 to 4 */
|
||||
uint8_t Pinnum; /**< Pin Number, should be PINSEL_PIN_x,
|
||||
where x should be in range from 0 to 31 */
|
||||
uint8_t Funcnum; /**< Function Number, should be PINSEL_FUNC_x,
|
||||
where x should be in range from 0 to 3 */
|
||||
uint8_t Pinmode; /**< Pin Mode, should be:
|
||||
- PINSEL_PINMODE_PULLUP: Internal pull-up resistor
|
||||
- PINSEL_PINMODE_TRISTATE: Tri-state
|
||||
- PINSEL_PINMODE_PULLDOWN: Internal pull-down resistor */
|
||||
uint8_t OpenDrain; /**< OpenDrain mode, should be:
|
||||
- PINSEL_PINMODE_NORMAL: Pin is in the normal (not open drain) mode
|
||||
- PINSEL_PINMODE_OPENDRAIN: Pin is in the open drain mode */
|
||||
} PINSEL_CFG_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup PINSEL_Public_Functions PINSEL Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void PINSEL_ConfigPin(PINSEL_CFG_Type *PinCfg);
|
||||
void PINSEL_ConfigTraceFunc (FunctionalState NewState);
|
||||
void PINSEL_SetI2C0Pins(uint8_t i2cPinMode, FunctionalState filterSlewRateEnable);
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_PINSEL_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
||||
|
|
@ -1,348 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_pwm.h 2011-03-31
|
||||
*//**
|
||||
* @file lpc17xx_pwm.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for PWM firmware library on LPC17xx
|
||||
* @version 2.1
|
||||
* @date 31. Mar. 2011
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2011, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup PWM PWM (Pulse Width Modulator)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_PWM_H_
|
||||
#define LPC17XX_PWM_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup PWM_Private_Macros PWM Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/**********************************************************************
|
||||
* IR register definitions
|
||||
**********************************************************************/
|
||||
/** Interrupt flag for PWM match channel for 6 channel */
|
||||
#define PWM_IR_PWMMRn(n) ((uint32_t)((n<4)?(1<<n):(1<<(n+4))))
|
||||
/** Interrupt flag for capture input */
|
||||
#define PWM_IR_PWMCAPn(n) ((uint32_t)(1<<(n+4)))
|
||||
/** IR register mask */
|
||||
#define PWM_IR_BITMASK ((uint32_t)(0x0000073F))
|
||||
|
||||
/**********************************************************************
|
||||
* TCR register definitions
|
||||
**********************************************************************/
|
||||
/** TCR register mask */
|
||||
#define PWM_TCR_BITMASK ((uint32_t)(0x0000000B))
|
||||
#define PWM_TCR_COUNTER_ENABLE ((uint32_t)(1<<0)) /*!< PWM Counter Enable */
|
||||
#define PWM_TCR_COUNTER_RESET ((uint32_t)(1<<1)) /*!< PWM Counter Reset */
|
||||
#define PWM_TCR_PWM_ENABLE ((uint32_t)(1<<3)) /*!< PWM Enable */
|
||||
|
||||
/**********************************************************************
|
||||
* CTCR register definitions
|
||||
**********************************************************************/
|
||||
/** CTCR register mask */
|
||||
#define PWM_CTCR_BITMASK ((uint32_t)(0x0000000F))
|
||||
/** PWM Counter-Timer Mode */
|
||||
#define PWM_CTCR_MODE(n) ((uint32_t)(n&0x03))
|
||||
/** PWM Capture input select */
|
||||
#define PWM_CTCR_SELECT_INPUT(n) ((uint32_t)((n&0x03)<<2))
|
||||
|
||||
/**********************************************************************
|
||||
* MCR register definitions
|
||||
**********************************************************************/
|
||||
/** MCR register mask */
|
||||
#define PWM_MCR_BITMASK ((uint32_t)(0x001FFFFF))
|
||||
/** generate a PWM interrupt when a MATCHn occurs */
|
||||
#define PWM_MCR_INT_ON_MATCH(n) ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07))))
|
||||
/** reset the PWM when a MATCHn occurs */
|
||||
#define PWM_MCR_RESET_ON_MATCH(n) ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07)+1)))
|
||||
/** stop the PWM when a MATCHn occurs */
|
||||
#define PWM_MCR_STOP_ON_MATCH(n) ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07)+2)))
|
||||
|
||||
/**********************************************************************
|
||||
* CCR register definitions
|
||||
**********************************************************************/
|
||||
/** CCR register mask */
|
||||
#define PWM_CCR_BITMASK ((uint32_t)(0x0000003F))
|
||||
/** PCAPn is rising edge sensitive */
|
||||
#define PWM_CCR_CAP_RISING(n) ((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1))))
|
||||
/** PCAPn is falling edge sensitive */
|
||||
#define PWM_CCR_CAP_FALLING(n) ((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1)+1)))
|
||||
/** PWM interrupt is generated on a PCAP event */
|
||||
#define PWM_CCR_INT_ON_CAP(n) ((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1)+2)))
|
||||
|
||||
/**********************************************************************
|
||||
* PCR register definitions
|
||||
**********************************************************************/
|
||||
/** PCR register mask */
|
||||
#define PWM_PCR_BITMASK (uint32_t)0x00007E7C
|
||||
/** PWM output n is a single edge controlled output */
|
||||
#define PWM_PCR_PWMSELn(n) ((uint32_t)(((n&0x7)<2) ? 0 : (1<<n)))
|
||||
/** enable PWM output n */
|
||||
#define PWM_PCR_PWMENAn(n) ((uint32_t)(((n&0x7)<1) ? 0 : (1<<(n+8))))
|
||||
|
||||
/**********************************************************************
|
||||
* LER register definitions
|
||||
**********************************************************************/
|
||||
/** LER register mask*/
|
||||
#define PWM_LER_BITMASK ((uint32_t)(0x0000007F))
|
||||
/** PWM MATCHn register update control */
|
||||
#define PWM_LER_EN_MATCHn_LATCH(n) ((uint32_t)((n<7) ? (1<<n) : 0))
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/** Macro to determine if it is valid PWM peripheral or not */
|
||||
#define PARAM_PWMx(n) (((uint32_t *)n)==((uint32_t *)LPC_PWM1))
|
||||
|
||||
/** Macro check PWM1 match channel value */
|
||||
#define PARAM_PWM1_MATCH_CHANNEL(n) (n<=6)
|
||||
|
||||
/** Macro check PWM1 channel value */
|
||||
#define PARAM_PWM1_CHANNEL(n) ((n>=1) && (n<=6))
|
||||
|
||||
/** Macro check PWM1 edge channel mode */
|
||||
#define PARAM_PWM1_EDGE_MODE_CHANNEL(n) ((n>=2) && (n<=6))
|
||||
|
||||
/** Macro check PWM1 capture channel mode */
|
||||
#define PARAM_PWM1_CAPTURE_CHANNEL(n) ((n==0) || (n==1))
|
||||
|
||||
/** Macro check PWM1 interrupt status type */
|
||||
#define PARAM_PWM_INTSTAT(n) ((n==PWM_INTSTAT_MR0) || (n==PWM_INTSTAT_MR1) || (n==PWM_INTSTAT_MR2) \
|
||||
|| (n==PWM_INTSTAT_MR3) || (n==PWM_INTSTAT_MR4) || (n==PWM_INTSTAT_MR5) \
|
||||
|| (n==PWM_INTSTAT_MR6) || (n==PWM_INTSTAT_CAP0) || (n==PWM_INTSTAT_CAP1))
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup PWM_Public_Types PWM Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Configuration structure in PWM TIMER mode */
|
||||
typedef struct {
|
||||
|
||||
uint8_t PrescaleOption; /**< Prescale option, should be:
|
||||
- PWM_TIMER_PRESCALE_TICKVAL: Prescale in absolute value
|
||||
- PWM_TIMER_PRESCALE_USVAL: Prescale in microsecond value
|
||||
*/
|
||||
uint8_t Reserved[3];
|
||||
uint32_t PrescaleValue; /**< Prescale value, 32-bit long, should be matched
|
||||
with PrescaleOption
|
||||
*/
|
||||
} PWM_TIMERCFG_Type;
|
||||
|
||||
/** @brief Configuration structure in PWM COUNTER mode */
|
||||
typedef struct {
|
||||
|
||||
uint8_t CounterOption; /**< Counter Option, should be:
|
||||
- PWM_COUNTER_RISING: Rising Edge
|
||||
- PWM_COUNTER_FALLING: Falling Edge
|
||||
- PWM_COUNTER_ANY: Both rising and falling mode
|
||||
*/
|
||||
uint8_t CountInputSelect; /**< Counter input select, should be:
|
||||
- PWM_COUNTER_PCAP1_0: PWM Counter input selected is PCAP1.0 pin
|
||||
- PWM_COUNTER_PCAP1_1: PWM Counter input selected is PCAP1.1 pin
|
||||
*/
|
||||
uint8_t Reserved[2];
|
||||
} PWM_COUNTERCFG_Type;
|
||||
|
||||
/** @brief PWM Match channel configuration structure */
|
||||
typedef struct {
|
||||
uint8_t MatchChannel; /**< Match channel, should be in range
|
||||
from 0..6 */
|
||||
uint8_t IntOnMatch; /**< Interrupt On match, should be:
|
||||
- ENABLE: Enable this function.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
uint8_t StopOnMatch; /**< Stop On match, should be:
|
||||
- ENABLE: Enable this function.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
uint8_t ResetOnMatch; /**< Reset On match, should be:
|
||||
- ENABLE: Enable this function.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
} PWM_MATCHCFG_Type;
|
||||
|
||||
|
||||
/** @brief PWM Capture Input configuration structure */
|
||||
typedef struct {
|
||||
uint8_t CaptureChannel; /**< Capture channel, should be in range
|
||||
from 0..1 */
|
||||
uint8_t RisingEdge; /**< caption rising edge, should be:
|
||||
- ENABLE: Enable rising edge.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
uint8_t FallingEdge; /**< caption falling edge, should be:
|
||||
- ENABLE: Enable falling edge.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
uint8_t IntOnCaption; /**< Interrupt On caption, should be:
|
||||
- ENABLE: Enable interrupt function.
|
||||
- DISABLE: Disable this function.
|
||||
*/
|
||||
} PWM_CAPTURECFG_Type;
|
||||
|
||||
/* Timer/Counter in PWM configuration type definition -----------------------------------*/
|
||||
|
||||
/** @brief PMW TC mode select option */
|
||||
typedef enum {
|
||||
PWM_MODE_TIMER = 0, /*!< PWM using Timer mode */
|
||||
PWM_MODE_COUNTER /*!< PWM using Counter mode */
|
||||
} PWM_TC_MODE_OPT;
|
||||
|
||||
#define PARAM_PWM_TC_MODE(n) ((n==PWM_MODE_TIMER) || (n==PWM_MODE_COUNTER))
|
||||
|
||||
|
||||
/** @brief PWM Timer/Counter prescale option */
|
||||
typedef enum
|
||||
{
|
||||
PWM_TIMER_PRESCALE_TICKVAL = 0, /*!< Prescale in absolute value */
|
||||
PWM_TIMER_PRESCALE_USVAL /*!< Prescale in microsecond value */
|
||||
} PWM_TIMER_PRESCALE_OPT;
|
||||
|
||||
#define PARAM_PWM_TIMER_PRESCALE(n) ((n==PWM_TIMER_PRESCALE_TICKVAL) || (n==PWM_TIMER_PRESCALE_USVAL))
|
||||
|
||||
|
||||
/** @brief PWM Input Select in counter mode */
|
||||
typedef enum {
|
||||
PWM_COUNTER_PCAP1_0 = 0, /*!< PWM Counter input selected is PCAP1.0 pin */
|
||||
PWM_COUNTER_PCAP1_1 /*!< PWM counter input selected is CAP1.1 pin */
|
||||
} PWM_COUNTER_INPUTSEL_OPT;
|
||||
|
||||
#define PARAM_PWM_COUNTER_INPUTSEL(n) ((n==PWM_COUNTER_PCAP1_0) || (n==PWM_COUNTER_PCAP1_1))
|
||||
|
||||
/** @brief PWM Input Edge Option in counter mode */
|
||||
typedef enum {
|
||||
PWM_COUNTER_RISING = 1, /*!< Rising edge mode */
|
||||
PWM_COUNTER_FALLING = 2, /*!< Falling edge mode */
|
||||
PWM_COUNTER_ANY = 3 /*!< Both rising and falling mode */
|
||||
} PWM_COUNTER_EDGE_OPT;
|
||||
|
||||
#define PARAM_PWM_COUNTER_EDGE(n) ((n==PWM_COUNTER_RISING) || (n==PWM_COUNTER_FALLING) \
|
||||
|| (n==PWM_COUNTER_ANY))
|
||||
|
||||
|
||||
/* PWM configuration type definition ----------------------------------------------------- */
|
||||
/** @brief PWM operating mode options */
|
||||
typedef enum {
|
||||
PWM_CHANNEL_SINGLE_EDGE, /*!< PWM Channel Single edge mode */
|
||||
PWM_CHANNEL_DUAL_EDGE /*!< PWM Channel Dual edge mode */
|
||||
} PWM_CHANNEL_EDGE_OPT;
|
||||
|
||||
#define PARAM_PWM_CHANNEL_EDGE(n) ((n==PWM_CHANNEL_SINGLE_EDGE) || (n==PWM_CHANNEL_DUAL_EDGE))
|
||||
|
||||
|
||||
/** @brief PWM update type */
|
||||
typedef enum {
|
||||
PWM_MATCH_UPDATE_NOW = 0, /**< PWM Match Channel Update Now */
|
||||
PWM_MATCH_UPDATE_NEXT_RST /**< PWM Match Channel Update on next
|
||||
PWM Counter resetting */
|
||||
} PWM_MATCH_UPDATE_OPT;
|
||||
|
||||
#define PARAM_PWM_MATCH_UPDATE(n) ((n==PWM_MATCH_UPDATE_NOW) || (n==PWM_MATCH_UPDATE_NEXT_RST))
|
||||
|
||||
|
||||
/** @brief PWM interrupt status type definition ----------------------------------------------------- */
|
||||
/** @brief PWM Interrupt status type */
|
||||
typedef enum
|
||||
{
|
||||
PWM_INTSTAT_MR0 = PWM_IR_PWMMRn(0), /**< Interrupt flag for PWM match channel 0 */
|
||||
PWM_INTSTAT_MR1 = PWM_IR_PWMMRn(1), /**< Interrupt flag for PWM match channel 1 */
|
||||
PWM_INTSTAT_MR2 = PWM_IR_PWMMRn(2), /**< Interrupt flag for PWM match channel 2 */
|
||||
PWM_INTSTAT_MR3 = PWM_IR_PWMMRn(3), /**< Interrupt flag for PWM match channel 3 */
|
||||
PWM_INTSTAT_CAP0 = PWM_IR_PWMCAPn(0), /**< Interrupt flag for capture input 0 */
|
||||
PWM_INTSTAT_CAP1 = PWM_IR_PWMCAPn(1), /**< Interrupt flag for capture input 1 */
|
||||
PWM_INTSTAT_MR4 = PWM_IR_PWMMRn(4), /**< Interrupt flag for PWM match channel 4 */
|
||||
PWM_INTSTAT_MR6 = PWM_IR_PWMMRn(5), /**< Interrupt flag for PWM match channel 5 */
|
||||
PWM_INTSTAT_MR5 = PWM_IR_PWMMRn(6) /**< Interrupt flag for PWM match channel 6 */
|
||||
}PWM_INTSTAT_TYPE;
|
||||
|
||||
/** @brief Match update structure */
|
||||
typedef struct
|
||||
{
|
||||
uint32_t Matchvalue;
|
||||
FlagStatus Status;
|
||||
}PWM_Match_T;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup PWM_Public_Functions PWM Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void PWM_PinConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWM_Channel, uint8_t PinselOption);
|
||||
IntStatus PWM_GetIntStatus(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag);
|
||||
void PWM_ClearIntPending(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag);
|
||||
void PWM_ConfigStructInit(uint8_t PWMTimerCounterMode, void *PWM_InitStruct);
|
||||
void PWM_Init(LPC_PWM_TypeDef *PWMx, uint32_t PWMTimerCounterMode, void *PWM_ConfigStruct);
|
||||
void PWM_DeInit (LPC_PWM_TypeDef *PWMx);
|
||||
void PWM_Cmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState);
|
||||
void PWM_CounterCmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState);
|
||||
void PWM_ResetCounter(LPC_PWM_TypeDef *PWMx);
|
||||
void PWM_ConfigMatch(LPC_PWM_TypeDef *PWMx, PWM_MATCHCFG_Type *PWM_MatchConfigStruct);
|
||||
void PWM_ConfigCapture(LPC_PWM_TypeDef *PWMx, PWM_CAPTURECFG_Type *PWM_CaptureConfigStruct);
|
||||
uint32_t PWM_GetCaptureValue(LPC_PWM_TypeDef *PWMx, uint8_t CaptureChannel);
|
||||
void PWM_MatchUpdate(LPC_PWM_TypeDef *PWMx, uint8_t MatchChannel, \
|
||||
uint32_t MatchValue, uint8_t UpdateType);
|
||||
void PWM_ChannelConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, uint8_t ModeOption);
|
||||
void PWM_ChannelCmd(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, FunctionalState NewState);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_PWM_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,424 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_qei.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_qei.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for QEI firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup QEI QEI (Quadrature Encoder Interface)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_QEI_H_
|
||||
#define LPC17XX_QEI_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/* Public Macros -------------------------------------------------------------- */
|
||||
/** @defgroup QEI_Public_Macros QEI Public Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* QEI Reset types */
|
||||
#define QEI_RESET_POS QEI_CON_RESP /**< Reset position counter */
|
||||
#define QEI_RESET_POSOnIDX QEI_CON_RESPI /**< Reset Posistion Counter on Index */
|
||||
#define QEI_RESET_VEL QEI_CON_RESV /**< Reset Velocity */
|
||||
#define QEI_RESET_IDX QEI_CON_RESI /**< Reset Index Counter */
|
||||
|
||||
/* QEI Direction Invert Type Option */
|
||||
#define QEI_DIRINV_NONE ((uint32_t)(0)) /**< Direction is not inverted */
|
||||
#define QEI_DIRINV_CMPL ((uint32_t)(1)) /**< Direction is complemented */
|
||||
|
||||
/* QEI Signal Mode Option */
|
||||
#define QEI_SIGNALMODE_QUAD ((uint32_t)(0)) /**< Signal operation: Quadrature phase mode */
|
||||
#define QEI_SIGNALMODE_CLKDIR ((uint32_t)(1)) /**< Signal operation: Clock/Direction mode */
|
||||
|
||||
/* QEI Capture Mode Option */
|
||||
#define QEI_CAPMODE_2X ((uint32_t)(0)) /**< Capture mode: Only Phase-A edges are counted (2X) */
|
||||
#define QEI_CAPMODE_4X ((uint32_t)(1)) /**< Capture mode: BOTH PhA and PhB edges are counted (4X)*/
|
||||
|
||||
/* QEI Invert Index Signal Option */
|
||||
#define QEI_INVINX_NONE ((uint32_t)(0)) /**< Invert Index signal option: None */
|
||||
#define QEI_INVINX_EN ((uint32_t)(1)) /**< Invert Index signal option: Enable */
|
||||
|
||||
/* QEI timer reload option */
|
||||
#define QEI_TIMERRELOAD_TICKVAL ((uint8_t)(0)) /**< Reload value in absolute value */
|
||||
#define QEI_TIMERRELOAD_USVAL ((uint8_t)(1)) /**< Reload value in microsecond value */
|
||||
|
||||
/* QEI Flag Status type */
|
||||
#define QEI_STATUS_DIR ((uint32_t)(1<<0)) /**< Direction status */
|
||||
|
||||
/* QEI Compare Position channel option */
|
||||
#define QEI_COMPPOS_CH_0 ((uint8_t)(0)) /**< QEI compare position channel 0 */
|
||||
#define QEI_COMPPOS_CH_1 ((uint8_t)(1)) /**< QEI compare position channel 1 */
|
||||
#define QEI_COMPPOS_CH_2 ((uint8_t)(2)) /**< QEI compare position channel 2 */
|
||||
|
||||
/* QEI interrupt flag type */
|
||||
#define QEI_INTFLAG_INX_Int ((uint32_t)(1<<0)) /**< index pulse was detected interrupt */
|
||||
#define QEI_INTFLAG_TIM_Int ((uint32_t)(1<<1)) /**< Velocity timer over flow interrupt */
|
||||
#define QEI_INTFLAG_VELC_Int ((uint32_t)(1<<2)) /**< Capture velocity is less than compare interrupt */
|
||||
#define QEI_INTFLAG_DIR_Int ((uint32_t)(1<<3)) /**< Change of direction interrupt */
|
||||
#define QEI_INTFLAG_ERR_Int ((uint32_t)(1<<4)) /**< An encoder phase error interrupt */
|
||||
#define QEI_INTFLAG_ENCLK_Int ((uint32_t)(1<<5)) /**< An encoder clock pulse was detected interrupt */
|
||||
#define QEI_INTFLAG_POS0_Int ((uint32_t)(1<<6)) /**< position 0 compare value is equal to the
|
||||
current position interrupt */
|
||||
#define QEI_INTFLAG_POS1_Int ((uint32_t)(1<<7)) /**< position 1 compare value is equal to the
|
||||
current position interrupt */
|
||||
#define QEI_INTFLAG_POS2_Int ((uint32_t)(1<<8)) /**< position 2 compare value is equal to the
|
||||
current position interrupt */
|
||||
#define QEI_INTFLAG_REV_Int ((uint32_t)(1<<9)) /**< Index compare value is equal to the current
|
||||
index count interrupt */
|
||||
#define QEI_INTFLAG_POS0REV_Int ((uint32_t)(1<<10)) /**< Combined position 0 and revolution count interrupt */
|
||||
#define QEI_INTFLAG_POS1REV_Int ((uint32_t)(1<<11)) /**< Combined position 1 and revolution count interrupt */
|
||||
#define QEI_INTFLAG_POS2REV_Int ((uint32_t)(1<<12)) /**< Combined position 2 and revolution count interrupt */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup QEI_Private_Macros QEI Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/* Quadrature Encoder Interface Control Register Definition --------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Control register
|
||||
**********************************************************************/
|
||||
#define QEI_CON_RESP ((uint32_t)(1<<0)) /**< Reset position counter */
|
||||
#define QEI_CON_RESPI ((uint32_t)(1<<1)) /**< Reset Posistion Counter on Index */
|
||||
#define QEI_CON_RESV ((uint32_t)(1<<2)) /**< Reset Velocity */
|
||||
#define QEI_CON_RESI ((uint32_t)(1<<3)) /**< Reset Index Counter */
|
||||
#define QEI_CON_BITMASK ((uint32_t)(0x0F)) /**< QEI Control register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Configuration register
|
||||
**********************************************************************/
|
||||
#define QEI_CONF_DIRINV ((uint32_t)(1<<0)) /**< Direction Invert */
|
||||
#define QEI_CONF_SIGMODE ((uint32_t)(1<<1)) /**< Signal mode */
|
||||
#define QEI_CONF_CAPMODE ((uint32_t)(1<<2)) /**< Capture mode */
|
||||
#define QEI_CONF_INVINX ((uint32_t)(1<<3)) /**< Invert index */
|
||||
#define QEI_CONF_BITMASK ((uint32_t)(0x0F)) /**< QEI Configuration register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Status register
|
||||
**********************************************************************/
|
||||
#define QEI_STAT_DIR ((uint32_t)(1<<0)) /**< Direction bit */
|
||||
#define QEI_STAT_BITMASK ((uint32_t)(1<<0)) /**< QEI status register bit-mask */
|
||||
|
||||
/* Quadrature Encoder Interface Interrupt registers definitions --------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Status register
|
||||
**********************************************************************/
|
||||
#define QEI_INTSTAT_INX_Int ((uint32_t)(1<<0)) /**< Indicates that an index pulse was detected */
|
||||
#define QEI_INTSTAT_TIM_Int ((uint32_t)(1<<1)) /**< Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_INTSTAT_VELC_Int ((uint32_t)(1<<2)) /**< Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_INTSTAT_DIR_Int ((uint32_t)(1<<3)) /**< Indicates that a change of direction was detected */
|
||||
#define QEI_INTSTAT_ERR_Int ((uint32_t)(1<<4)) /**< Indicates that an encoder phase error was detected */
|
||||
#define QEI_INTSTAT_ENCLK_Int ((uint32_t)(1<<5)) /**< Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_INTSTAT_POS0_Int ((uint32_t)(1<<6)) /**< Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSTAT_POS1_Int ((uint32_t)(1<<7)) /**< Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSTAT_POS2_Int ((uint32_t)(1<<8)) /**< Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSTAT_REV_Int ((uint32_t)(1<<9)) /**< Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_INTSTAT_POS0REV_Int ((uint32_t)(1<<10)) /**< Combined position 0 and revolution count interrupt. Set when
|
||||
both the POS0_Int bit is set and the REV_Int is set */
|
||||
#define QEI_INTSTAT_POS1REV_Int ((uint32_t)(1<<11)) /**< Combined position 1 and revolution count interrupt. Set when
|
||||
both the POS1_Int bit is set and the REV_Int is set */
|
||||
#define QEI_INTSTAT_POS2REV_Int ((uint32_t)(1<<12)) /**< Combined position 2 and revolution count interrupt. Set when
|
||||
both the POS2_Int bit is set and the REV_Int is set */
|
||||
#define QEI_INTSTAT_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Status register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Set register
|
||||
**********************************************************************/
|
||||
#define QEI_INTSET_INX_Int ((uint32_t)(1<<0)) /**< Set Bit Indicates that an index pulse was detected */
|
||||
#define QEI_INTSET_TIM_Int ((uint32_t)(1<<1)) /**< Set Bit Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_INTSET_VELC_Int ((uint32_t)(1<<2)) /**< Set Bit Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_INTSET_DIR_Int ((uint32_t)(1<<3)) /**< Set Bit Indicates that a change of direction was detected */
|
||||
#define QEI_INTSET_ERR_Int ((uint32_t)(1<<4)) /**< Set Bit Indicates that an encoder phase error was detected */
|
||||
#define QEI_INTSET_ENCLK_Int ((uint32_t)(1<<5)) /**< Set Bit Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_INTSET_POS0_Int ((uint32_t)(1<<6)) /**< Set Bit Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSET_POS1_Int ((uint32_t)(1<<7)) /**< Set Bit Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSET_POS2_Int ((uint32_t)(1<<8)) /**< Set Bit Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTSET_REV_Int ((uint32_t)(1<<9)) /**< Set Bit Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_INTSET_POS0REV_Int ((uint32_t)(1<<10)) /**< Set Bit that combined position 0 and revolution count interrupt */
|
||||
#define QEI_INTSET_POS1REV_Int ((uint32_t)(1<<11)) /**< Set Bit that Combined position 1 and revolution count interrupt */
|
||||
#define QEI_INTSET_POS2REV_Int ((uint32_t)(1<<12)) /**< Set Bit that Combined position 2 and revolution count interrupt */
|
||||
#define QEI_INTSET_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Set register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Clear register
|
||||
**********************************************************************/
|
||||
#define QEI_INTCLR_INX_Int ((uint32_t)(1<<0)) /**< Clear Bit Indicates that an index pulse was detected */
|
||||
#define QEI_INTCLR_TIM_Int ((uint32_t)(1<<1)) /**< Clear Bit Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_INTCLR_VELC_Int ((uint32_t)(1<<2)) /**< Clear Bit Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_INTCLR_DIR_Int ((uint32_t)(1<<3)) /**< Clear Bit Indicates that a change of direction was detected */
|
||||
#define QEI_INTCLR_ERR_Int ((uint32_t)(1<<4)) /**< Clear Bit Indicates that an encoder phase error was detected */
|
||||
#define QEI_INTCLR_ENCLK_Int ((uint32_t)(1<<5)) /**< Clear Bit Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_INTCLR_POS0_Int ((uint32_t)(1<<6)) /**< Clear Bit Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTCLR_POS1_Int ((uint32_t)(1<<7)) /**< Clear Bit Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTCLR_POS2_Int ((uint32_t)(1<<8)) /**< Clear Bit Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTCLR_REV_Int ((uint32_t)(1<<9)) /**< Clear Bit Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_INTCLR_POS0REV_Int ((uint32_t)(1<<10)) /**< Clear Bit that combined position 0 and revolution count interrupt */
|
||||
#define QEI_INTCLR_POS1REV_Int ((uint32_t)(1<<11)) /**< Clear Bit that Combined position 1 and revolution count interrupt */
|
||||
#define QEI_INTCLR_POS2REV_Int ((uint32_t)(1<<12)) /**< Clear Bit that Combined position 2 and revolution count interrupt */
|
||||
#define QEI_INTCLR_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Clear register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Enable register
|
||||
**********************************************************************/
|
||||
#define QEI_INTEN_INX_Int ((uint32_t)(1<<0)) /**< Enabled Interrupt Bit Indicates that an index pulse was detected */
|
||||
#define QEI_INTEN_TIM_Int ((uint32_t)(1<<1)) /**< Enabled Interrupt Bit Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_INTEN_VELC_Int ((uint32_t)(1<<2)) /**< Enabled Interrupt Bit Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_INTEN_DIR_Int ((uint32_t)(1<<3)) /**< Enabled Interrupt Bit Indicates that a change of direction was detected */
|
||||
#define QEI_INTEN_ERR_Int ((uint32_t)(1<<4)) /**< Enabled Interrupt Bit Indicates that an encoder phase error was detected */
|
||||
#define QEI_INTEN_ENCLK_Int ((uint32_t)(1<<5)) /**< Enabled Interrupt Bit Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_INTEN_POS0_Int ((uint32_t)(1<<6)) /**< Enabled Interrupt Bit Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTEN_POS1_Int ((uint32_t)(1<<7)) /**< Enabled Interrupt Bit Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTEN_POS2_Int ((uint32_t)(1<<8)) /**< Enabled Interrupt Bit Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_INTEN_REV_Int ((uint32_t)(1<<9)) /**< Enabled Interrupt Bit Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_INTEN_POS0REV_Int ((uint32_t)(1<<10)) /**< Enabled Interrupt Bit that combined position 0 and revolution count interrupt */
|
||||
#define QEI_INTEN_POS1REV_Int ((uint32_t)(1<<11)) /**< Enabled Interrupt Bit that Combined position 1 and revolution count interrupt */
|
||||
#define QEI_INTEN_POS2REV_Int ((uint32_t)(1<<12)) /**< Enabled Interrupt Bit that Combined position 2 and revolution count interrupt */
|
||||
#define QEI_INTEN_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Enable register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Enable Set register
|
||||
**********************************************************************/
|
||||
#define QEI_IESET_INX_Int ((uint32_t)(1<<0)) /**< Set Enable Interrupt Bit Indicates that an index pulse was detected */
|
||||
#define QEI_IESET_TIM_Int ((uint32_t)(1<<1)) /**< Set Enable Interrupt Bit Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_IESET_VELC_Int ((uint32_t)(1<<2)) /**< Set Enable Interrupt Bit Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_IESET_DIR_Int ((uint32_t)(1<<3)) /**< Set Enable Interrupt Bit Indicates that a change of direction was detected */
|
||||
#define QEI_IESET_ERR_Int ((uint32_t)(1<<4)) /**< Set Enable Interrupt Bit Indicates that an encoder phase error was detected */
|
||||
#define QEI_IESET_ENCLK_Int ((uint32_t)(1<<5)) /**< Set Enable Interrupt Bit Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_IESET_POS0_Int ((uint32_t)(1<<6)) /**< Set Enable Interrupt Bit Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IESET_POS1_Int ((uint32_t)(1<<7)) /**< Set Enable Interrupt Bit Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IESET_POS2_Int ((uint32_t)(1<<8)) /**< Set Enable Interrupt Bit Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IESET_REV_Int ((uint32_t)(1<<9)) /**< Set Enable Interrupt Bit Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_IESET_POS0REV_Int ((uint32_t)(1<<10)) /**< Set Enable Interrupt Bit that combined position 0 and revolution count interrupt */
|
||||
#define QEI_IESET_POS1REV_Int ((uint32_t)(1<<11)) /**< Set Enable Interrupt Bit that Combined position 1 and revolution count interrupt */
|
||||
#define QEI_IESET_POS2REV_Int ((uint32_t)(1<<12)) /**< Set Enable Interrupt Bit that Combined position 2 and revolution count interrupt */
|
||||
#define QEI_IESET_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Enable Set register bit-mask */
|
||||
|
||||
/*********************************************************************//**
|
||||
* Macro defines for QEI Interrupt Enable Clear register
|
||||
**********************************************************************/
|
||||
#define QEI_IECLR_INX_Int ((uint32_t)(1<<0)) /**< Clear Enabled Interrupt Bit Indicates that an index pulse was detected */
|
||||
#define QEI_IECLR_TIM_Int ((uint32_t)(1<<1)) /**< Clear Enabled Interrupt Bit Indicates that a velocity timer overflow occurred */
|
||||
#define QEI_IECLR_VELC_Int ((uint32_t)(1<<2)) /**< Clear Enabled Interrupt Bit Indicates that capture velocity is less than compare velocity */
|
||||
#define QEI_IECLR_DIR_Int ((uint32_t)(1<<3)) /**< Clear Enabled Interrupt Bit Indicates that a change of direction was detected */
|
||||
#define QEI_IECLR_ERR_Int ((uint32_t)(1<<4)) /**< Clear Enabled Interrupt Bit Indicates that an encoder phase error was detected */
|
||||
#define QEI_IECLR_ENCLK_Int ((uint32_t)(1<<5)) /**< Clear Enabled Interrupt Bit Indicates that and encoder clock pulse was detected */
|
||||
#define QEI_IECLR_POS0_Int ((uint32_t)(1<<6)) /**< Clear Enabled Interrupt Bit Indicates that the position 0 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IECLR_POS1_Int ((uint32_t)(1<<7)) /**< Clear Enabled Interrupt Bit Indicates that the position 1compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IECLR_POS2_Int ((uint32_t)(1<<8)) /**< Clear Enabled Interrupt Bit Indicates that the position 2 compare value is equal to the
|
||||
current position */
|
||||
#define QEI_IECLR_REV_Int ((uint32_t)(1<<9)) /**< Clear Enabled Interrupt Bit Indicates that the index compare value is equal to the current
|
||||
index count */
|
||||
#define QEI_IECLR_POS0REV_Int ((uint32_t)(1<<10)) /**< Clear Enabled Interrupt Bit that combined position 0 and revolution count interrupt */
|
||||
#define QEI_IECLR_POS1REV_Int ((uint32_t)(1<<11)) /**< Clear Enabled Interrupt Bit that Combined position 1 and revolution count interrupt */
|
||||
#define QEI_IECLR_POS2REV_Int ((uint32_t)(1<<12)) /**< Clear Enabled Interrupt Bit that Combined position 2 and revolution count interrupt */
|
||||
#define QEI_IECLR_BITMASK ((uint32_t)(0x1FFF)) /**< QEI Interrupt Enable Clear register bit-mask */
|
||||
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/* Macro check QEI peripheral */
|
||||
#define PARAM_QEIx(n) ((n==LPC_QEI))
|
||||
|
||||
/* Macro check QEI reset type */
|
||||
#define PARAM_QEI_RESET(n) ((n==QEI_CON_RESP) \
|
||||
|| (n==QEI_RESET_POSOnIDX) \
|
||||
|| (n==QEI_RESET_VEL) \
|
||||
|| (n==QEI_RESET_IDX))
|
||||
|
||||
/* Macro check QEI Direction invert mode */
|
||||
#define PARAM_QEI_DIRINV(n) ((n==QEI_DIRINV_NONE) || (n==QEI_DIRINV_CMPL))
|
||||
|
||||
/* Macro check QEI signal mode */
|
||||
#define PARAM_QEI_SIGNALMODE(n) ((n==QEI_SIGNALMODE_QUAD) || (n==QEI_SIGNALMODE_CLKDIR))
|
||||
|
||||
/* Macro check QEI Capture mode */
|
||||
#define PARAM_QEI_CAPMODE(n) ((n==QEI_CAPMODE_2X) || (n==QEI_CAPMODE_4X))
|
||||
|
||||
/* Macro check QEI Invert index mode */
|
||||
#define PARAM_QEI_INVINX(n) ((n==QEI_INVINX_NONE) || (n==QEI_INVINX_EN))
|
||||
|
||||
/* Macro check QEI Direction invert mode */
|
||||
#define PARAM_QEI_TIMERRELOAD(n) ((n==QEI_TIMERRELOAD_TICKVAL) || (n==QEI_TIMERRELOAD_USVAL))
|
||||
|
||||
/* Macro check QEI status type */
|
||||
#define PARAM_QEI_STATUS(n) ((n==QEI_STATUS_DIR))
|
||||
|
||||
/* Macro check QEI combine position type */
|
||||
#define PARAM_QEI_COMPPOS_CH(n) ((n==QEI_COMPPOS_CH_0) || (n==QEI_COMPPOS_CH_1) || (n==QEI_COMPPOS_CH_2))
|
||||
|
||||
/* Macro check QEI interrupt flag type */
|
||||
#define PARAM_QEI_INTFLAG(n) ((n==QEI_INTFLAG_INX_Int) \
|
||||
|| (n==QEI_INTFLAG_TIM_Int) \
|
||||
|| (n==QEI_INTFLAG_VELC_Int) \
|
||||
|| (n==QEI_INTFLAG_DIR_Int) \
|
||||
|| (n==QEI_INTFLAG_ERR_Int) \
|
||||
|| (n==QEI_INTFLAG_ENCLK_Int) \
|
||||
|| (n==QEI_INTFLAG_POS0_Int) \
|
||||
|| (n==QEI_INTFLAG_POS1_Int) \
|
||||
|| (n==QEI_INTFLAG_POS2_Int) \
|
||||
|| (n==QEI_INTFLAG_REV_Int) \
|
||||
|| (n==QEI_INTFLAG_POS0REV_Int) \
|
||||
|| (n==QEI_INTFLAG_POS1REV_Int) \
|
||||
|| (n==QEI_INTFLAG_POS2REV_Int))
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup QEI_Public_Types QEI Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief QEI Configuration structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t DirectionInvert :1; /**< Direction invert option:
|
||||
- QEI_DIRINV_NONE: QEI Direction is normal
|
||||
- QEI_DIRINV_CMPL: QEI Direction is complemented
|
||||
*/
|
||||
uint32_t SignalMode :1; /**< Signal mode Option:
|
||||
- QEI_SIGNALMODE_QUAD: Signal is in Quadrature phase mode
|
||||
- QEI_SIGNALMODE_CLKDIR: Signal is in Clock/Direction mode
|
||||
*/
|
||||
uint32_t CaptureMode :1; /**< Capture Mode Option:
|
||||
- QEI_CAPMODE_2X: Only Phase-A edges are counted (2X)
|
||||
- QEI_CAPMODE_4X: BOTH Phase-A and Phase-B edges are counted (4X)
|
||||
*/
|
||||
uint32_t InvertIndex :1; /**< Invert Index Option:
|
||||
- QEI_INVINX_NONE: the sense of the index input is normal
|
||||
- QEI_INVINX_EN: inverts the sense of the index input
|
||||
*/
|
||||
} QEI_CFG_Type;
|
||||
|
||||
/**
|
||||
* @brief Timer Reload Configuration structure type definition
|
||||
*/
|
||||
typedef struct {
|
||||
|
||||
uint8_t ReloadOption; /**< Velocity Timer Reload Option, should be:
|
||||
- QEI_TIMERRELOAD_TICKVAL: Reload value in absolute value
|
||||
- QEI_TIMERRELOAD_USVAL: Reload value in microsecond value
|
||||
*/
|
||||
uint8_t Reserved[3];
|
||||
uint32_t ReloadValue; /**< Velocity Timer Reload Value, 32-bit long, should be matched
|
||||
with Velocity Timer Reload Option
|
||||
*/
|
||||
} QEI_RELOADCFG_Type;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup QEI_Public_Functions QEI Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void QEI_Reset(LPC_QEI_TypeDef *QEIx, uint32_t ulResetType);
|
||||
void QEI_Init(LPC_QEI_TypeDef *QEIx, QEI_CFG_Type *QEI_ConfigStruct);
|
||||
void QEI_ConfigStructInit(QEI_CFG_Type *QIE_InitStruct);
|
||||
void QEI_DeInit(LPC_QEI_TypeDef *QEIx);
|
||||
FlagStatus QEI_GetStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulFlagType);
|
||||
uint32_t QEI_GetPosition(LPC_QEI_TypeDef *QEIx);
|
||||
void QEI_SetMaxPosition(LPC_QEI_TypeDef *QEIx, uint32_t ulMaxPos);
|
||||
void QEI_SetPositionComp(LPC_QEI_TypeDef *QEIx, uint8_t bPosCompCh, uint32_t ulPosComp);
|
||||
uint32_t QEI_GetIndex(LPC_QEI_TypeDef *QEIx);
|
||||
void QEI_SetIndexComp(LPC_QEI_TypeDef *QEIx, uint32_t ulIndexComp);
|
||||
void QEI_SetTimerReload(LPC_QEI_TypeDef *QEIx, QEI_RELOADCFG_Type *QEIReloadStruct);
|
||||
uint32_t QEI_GetTimer(LPC_QEI_TypeDef *QEIx);
|
||||
uint32_t QEI_GetVelocity(LPC_QEI_TypeDef *QEIx);
|
||||
uint32_t QEI_GetVelocityCap(LPC_QEI_TypeDef *QEIx);
|
||||
void QEI_SetVelocityComp(LPC_QEI_TypeDef *QEIx, uint32_t ulVelComp);
|
||||
void QEI_SetDigiFilter(LPC_QEI_TypeDef *QEIx, uint32_t ulSamplingPulse);
|
||||
FlagStatus QEI_GetIntStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
|
||||
void QEI_IntCmd(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType, FunctionalState NewState);
|
||||
void QEI_IntSet(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
|
||||
void QEI_IntClear(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
|
||||
uint32_t QEI_CalculateRPM(LPC_QEI_TypeDef *QEIx, uint32_t ulVelCapValue, uint32_t ulPPR);
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_QEI_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,112 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_rit.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_rit.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for RIT firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup RIT RIT (Repetitive Interrupt Timer)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_RIT_H_
|
||||
#define LPC17XX_RIT_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup RIT_Private_Macros RIT Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* --------------------- BIT DEFINITIONS -------------------------------------- */
|
||||
/*********************************************************************//**
|
||||
* Macro defines for RIT control register
|
||||
**********************************************************************/
|
||||
/** Set interrupt flag when the counter value equals the masked compare value */
|
||||
#define RIT_CTRL_INTEN ((uint32_t) (1))
|
||||
/** Set timer enable clear to 0 when the counter value equals the masked compare value */
|
||||
#define RIT_CTRL_ENCLR ((uint32_t) _BIT(1))
|
||||
/** Set timer enable on debug */
|
||||
#define RIT_CTRL_ENBR ((uint32_t) _BIT(2))
|
||||
/** Set timer enable */
|
||||
#define RIT_CTRL_TEN ((uint32_t) _BIT(3))
|
||||
|
||||
/** Macro to determine if it is valid RIT peripheral */
|
||||
#define PARAM_RITx(n) (((uint32_t *)n)==((uint32_t *)LPC_RIT))
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup RIT_Public_Functions RIT Public Functions
|
||||
* @{
|
||||
*/
|
||||
/* RIT Init/DeInit functions */
|
||||
void RIT_Init(LPC_RIT_TypeDef *RITx);
|
||||
void RIT_DeInit(LPC_RIT_TypeDef *RITx);
|
||||
|
||||
/* RIT config timer functions */
|
||||
void RIT_TimerConfig(LPC_RIT_TypeDef *RITx, uint32_t time_interval);
|
||||
|
||||
/* Enable/Disable RIT functions */
|
||||
void RIT_TimerClearCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
|
||||
void RIT_Cmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
|
||||
void RIT_TimerDebugCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
|
||||
|
||||
/* RIT Interrupt functions */
|
||||
IntStatus RIT_GetIntStatus(LPC_RIT_TypeDef *RITx);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_RIT_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
|
@ -1,314 +0,0 @@
|
|||
/**********************************************************************
|
||||
* $Id$ lpc17xx_rtc.h 2010-05-21
|
||||
*//**
|
||||
* @file lpc17xx_rtc.h
|
||||
* @brief Contains all macro definitions and function prototypes
|
||||
* support for RTC firmware library on LPC17xx
|
||||
* @version 2.0
|
||||
* @date 21. May. 2010
|
||||
* @author NXP MCU SW Application Team
|
||||
*
|
||||
* Copyright(C) 2010, NXP Semiconductor
|
||||
* All rights reserved.
|
||||
*
|
||||
***********************************************************************
|
||||
* Software that is described herein is for illustrative purposes only
|
||||
* which provides customers with programming information regarding the
|
||||
* products. This software is supplied "AS IS" without any warranties.
|
||||
* NXP Semiconductors assumes no responsibility or liability for the
|
||||
* use of the software, conveys no license or title under any patent,
|
||||
* copyright, or mask work right to the product. NXP Semiconductors
|
||||
* reserves the right to make changes in the software without
|
||||
* notification. NXP Semiconductors also make no representation or
|
||||
* warranty that such application will be suitable for the specified
|
||||
* use without further testing or modification.
|
||||
* Permission to use, copy, modify, and distribute this software and its
|
||||
* documentation is hereby granted, under NXP Semiconductors'
|
||||
* relevant copyright in the software, without fee, provided that it
|
||||
* is used in conjunction with NXP Semiconductors microcontrollers. This
|
||||
* copyright, permission, and disclaimer notice must appear in all copies of
|
||||
* this code.
|
||||
**********************************************************************/
|
||||
|
||||
/* Peripheral group ----------------------------------------------------------- */
|
||||
/** @defgroup RTC RTC (Real Time Clock)
|
||||
* @ingroup LPC1700CMSIS_FwLib_Drivers
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef LPC17XX_RTC_H_
|
||||
#define LPC17XX_RTC_H_
|
||||
|
||||
/* Includes ------------------------------------------------------------------- */
|
||||
#include "LPC17xx.h"
|
||||
#include "lpc_types.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/* Private Macros ------------------------------------------------------------- */
|
||||
/** @defgroup RTC_Private_Macros RTC Private Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* ----------------------- BIT DEFINITIONS ----------------------------------- */
|
||||
/* Miscellaneous register group --------------------------------------------- */
|
||||
/**********************************************************************
|
||||
* ILR register definitions
|
||||
**********************************************************************/
|
||||
/** ILR register mask */
|
||||
#define RTC_ILR_BITMASK ((0x00000003))
|
||||
/** Bit inform the source interrupt is counter increment*/
|
||||
#define RTC_IRL_RTCCIF ((1<<0))
|
||||
/** Bit inform the source interrupt is alarm match*/
|
||||
#define RTC_IRL_RTCALF ((1<<1))
|
||||
|
||||
/**********************************************************************
|
||||
* CCR register definitions
|
||||
**********************************************************************/
|
||||
/** CCR register mask */
|
||||
#define RTC_CCR_BITMASK ((0x00000013))
|
||||
/** Clock enable */
|
||||
#define RTC_CCR_CLKEN ((1<<0))
|
||||
/** Clock reset */
|
||||
#define RTC_CCR_CTCRST ((1<<1))
|
||||
/** Calibration counter enable */
|
||||
#define RTC_CCR_CCALEN ((1<<4))
|
||||
|
||||
/**********************************************************************
|
||||
* CIIR register definitions
|
||||
**********************************************************************/
|
||||
/** Counter Increment Interrupt bit for second */
|
||||
#define RTC_CIIR_IMSEC ((1<<0))
|
||||
/** Counter Increment Interrupt bit for minute */
|
||||
#define RTC_CIIR_IMMIN ((1<<1))
|
||||
/** Counter Increment Interrupt bit for hour */
|
||||
#define RTC_CIIR_IMHOUR ((1<<2))
|
||||
/** Counter Increment Interrupt bit for day of month */
|
||||
#define RTC_CIIR_IMDOM ((1<<3))
|
||||
/** Counter Increment Interrupt bit for day of week */
|
||||
#define RTC_CIIR_IMDOW ((1<<4))
|
||||
/** Counter Increment Interrupt bit for day of year */
|
||||
#define RTC_CIIR_IMDOY ((1<<5))
|
||||
/** Counter Increment Interrupt bit for month */
|
||||
#define RTC_CIIR_IMMON ((1<<6))
|
||||
/** Counter Increment Interrupt bit for year */
|
||||
#define RTC_CIIR_IMYEAR ((1<<7))
|
||||
/** CIIR bit mask */
|
||||
#define RTC_CIIR_BITMASK ((0xFF))
|
||||
|
||||
/**********************************************************************
|
||||
* AMR register definitions
|
||||
**********************************************************************/
|
||||
/** Counter Increment Select Mask bit for second */
|
||||
#define RTC_AMR_AMRSEC ((1<<0))
|
||||
/** Counter Increment Select Mask bit for minute */
|
||||
#define RTC_AMR_AMRMIN ((1<<1))
|
||||
/** Counter Increment Select Mask bit for hour */
|
||||
#define RTC_AMR_AMRHOUR ((1<<2))
|
||||
/** Counter Increment Select Mask bit for day of month */
|
||||
#define RTC_AMR_AMRDOM ((1<<3))
|
||||
/** Counter Increment Select Mask bit for day of week */
|
||||
#define RTC_AMR_AMRDOW ((1<<4))
|
||||
/** Counter Increment Select Mask bit for day of year */
|
||||
#define RTC_AMR_AMRDOY ((1<<5))
|
||||
/** Counter Increment Select Mask bit for month */
|
||||
#define RTC_AMR_AMRMON ((1<<6))
|
||||
/** Counter Increment Select Mask bit for year */
|
||||
#define RTC_AMR_AMRYEAR ((1<<7))
|
||||
/** AMR bit mask */
|
||||
#define RTC_AMR_BITMASK ((0xFF))
|
||||
|
||||
/**********************************************************************
|
||||
* RTC_AUX register definitions
|
||||
**********************************************************************/
|
||||
/** RTC Oscillator Fail detect flag */
|
||||
#define RTC_AUX_RTC_OSCF ((1<<4))
|
||||
|
||||
/**********************************************************************
|
||||
* RTC_AUXEN register definitions
|
||||
**********************************************************************/
|
||||
/** Oscillator Fail Detect interrupt enable*/
|
||||
#define RTC_AUXEN_RTC_OSCFEN ((1<<4))
|
||||
|
||||
/* Consolidated time register group ----------------------------------- */
|
||||
/**********************************************************************
|
||||
* Consolidated Time Register 0 definitions
|
||||
**********************************************************************/
|
||||
#define RTC_CTIME0_SECONDS_MASK ((0x3F))
|
||||
#define RTC_CTIME0_MINUTES_MASK ((0x3F00))
|
||||
#define RTC_CTIME0_HOURS_MASK ((0x1F0000))
|
||||
#define RTC_CTIME0_DOW_MASK ((0x7000000))
|
||||
|
||||
/**********************************************************************
|
||||
* Consolidated Time Register 1 definitions
|
||||
**********************************************************************/
|
||||
#define RTC_CTIME1_DOM_MASK ((0x1F))
|
||||
#define RTC_CTIME1_MONTH_MASK ((0xF00))
|
||||
#define RTC_CTIME1_YEAR_MASK ((0xFFF0000))
|
||||
|
||||
/**********************************************************************
|
||||
* Consolidated Time Register 2 definitions
|
||||
**********************************************************************/
|
||||
#define RTC_CTIME2_DOY_MASK ((0xFFF))
|
||||
|
||||
/**********************************************************************
|
||||
* Time Counter Group and Alarm register group
|
||||
**********************************************************************/
|
||||
/** SEC register mask */
|
||||
#define RTC_SEC_MASK (0x0000003F)
|
||||
/** MIN register mask */
|
||||
#define RTC_MIN_MASK (0x0000003F)
|
||||
/** HOUR register mask */
|
||||
#define RTC_HOUR_MASK (0x0000001F)
|
||||
/** DOM register mask */
|
||||
#define RTC_DOM_MASK (0x0000001F)
|
||||
/** DOW register mask */
|
||||
#define RTC_DOW_MASK (0x00000007)
|
||||
/** DOY register mask */
|
||||
#define RTC_DOY_MASK (0x000001FF)
|
||||
/** MONTH register mask */
|
||||
#define RTC_MONTH_MASK (0x0000000F)
|
||||
/** YEAR register mask */
|
||||
#define RTC_YEAR_MASK (0x00000FFF)
|
||||
|
||||
#define RTC_SECOND_MAX 59 /*!< Maximum value of second */
|
||||
#define RTC_MINUTE_MAX 59 /*!< Maximum value of minute*/
|
||||
#define RTC_HOUR_MAX 23 /*!< Maximum value of hour*/
|
||||
#define RTC_MONTH_MIN 1 /*!< Minimum value of month*/
|
||||
#define RTC_MONTH_MAX 12 /*!< Maximum value of month*/
|
||||
#define RTC_DAYOFMONTH_MIN 1 /*!< Minimum value of day of month*/
|
||||
#define RTC_DAYOFMONTH_MAX 31 /*!< Maximum value of day of month*/
|
||||
#define RTC_DAYOFWEEK_MAX 6 /*!< Maximum value of day of week*/
|
||||
#define RTC_DAYOFYEAR_MIN 1 /*!< Minimum value of day of year*/
|
||||
#define RTC_DAYOFYEAR_MAX 366 /*!< Maximum value of day of year*/
|
||||
#define RTC_YEAR_MAX 4095 /*!< Maximum value of year*/
|
||||
|
||||
/**********************************************************************
|
||||
* Calibration register
|
||||
**********************************************************************/
|
||||
/* Calibration register */
|
||||
/** Calibration value */
|
||||
#define RTC_CALIBRATION_CALVAL_MASK ((0x1FFFF))
|
||||
/** Calibration direction */
|
||||
#define RTC_CALIBRATION_LIBDIR ((1<<17))
|
||||
/** Calibration max value */
|
||||
#define RTC_CALIBRATION_MAX ((0x20000))
|
||||
/** Calibration definitions */
|
||||
#define RTC_CALIB_DIR_FORWARD ((uint8_t)(0))
|
||||
#define RTC_CALIB_DIR_BACKWARD ((uint8_t)(1))
|
||||
|
||||
|
||||
/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
|
||||
/** Macro to determine if it is valid RTC peripheral */
|
||||
#define PARAM_RTCx(x) (((uint32_t *)x)==((uint32_t *)LPC_RTC))
|
||||
|
||||
/* Macro check RTC interrupt type */
|
||||
#define PARAM_RTC_INT(n) ((n==RTC_INT_COUNTER_INCREASE) || (n==RTC_INT_ALARM))
|
||||
|
||||
/* Macro check RTC time type */
|
||||
#define PARAM_RTC_TIMETYPE(n) ((n==RTC_TIMETYPE_SECOND) || (n==RTC_TIMETYPE_MINUTE) \
|
||||
|| (n==RTC_TIMETYPE_HOUR) || (n==RTC_TIMETYPE_DAYOFWEEK) \
|
||||
|| (n==RTC_TIMETYPE_DAYOFMONTH) || (n==RTC_TIMETYPE_DAYOFYEAR) \
|
||||
|| (n==RTC_TIMETYPE_MONTH) || (n==RTC_TIMETYPE_YEAR))
|
||||
|
||||
/* Macro check RTC calibration type */
|
||||
#define PARAM_RTC_CALIB_DIR(n) ((n==RTC_CALIB_DIR_FORWARD) || (n==RTC_CALIB_DIR_BACKWARD))
|
||||
|
||||
/* Macro check RTC GPREG type */
|
||||
#define PARAM_RTC_GPREG_CH(n) (n<=4)
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/* Public Types --------------------------------------------------------------- */
|
||||
/** @defgroup RTC_Public_Types RTC Public Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Time structure definitions for easy manipulate the data */
|
||||
typedef struct {
|
||||
uint32_t SEC; /*!< Seconds Register */
|
||||
uint32_t MIN; /*!< Minutes Register */
|
||||
uint32_t HOUR; /*!< Hours Register */
|
||||
uint32_t DOM; /*!< Day of Month Register */
|
||||
uint32_t DOW; /*!< Day of Week Register */
|
||||
uint32_t DOY; /*!< Day of Year Register */
|
||||
uint32_t MONTH; /*!< Months Register */
|
||||
uint32_t YEAR; /*!< Years Register */
|
||||
} RTC_TIME_Type;
|
||||
|
||||
/** @brief RTC interrupt source */
|
||||
typedef enum {
|
||||
RTC_INT_COUNTER_INCREASE = RTC_IRL_RTCCIF, /*!< Counter Increment Interrupt */
|
||||
RTC_INT_ALARM = RTC_IRL_RTCALF /*!< The alarm interrupt */
|
||||
} RTC_INT_OPT;
|
||||
|
||||
|
||||
/** @brief RTC time type option */
|
||||
typedef enum {
|
||||
RTC_TIMETYPE_SECOND = 0, /*!< Second */
|
||||
RTC_TIMETYPE_MINUTE = 1, /*!< Month */
|
||||
RTC_TIMETYPE_HOUR = 2, /*!< Hour */
|
||||
RTC_TIMETYPE_DAYOFWEEK = 3, /*!< Day of week */
|
||||
RTC_TIMETYPE_DAYOFMONTH = 4, /*!< Day of month */
|
||||
RTC_TIMETYPE_DAYOFYEAR = 5, /*!< Day of year */
|
||||
RTC_TIMETYPE_MONTH = 6, /*!< Month */
|
||||
RTC_TIMETYPE_YEAR = 7 /*!< Year */
|
||||
} RTC_TIMETYPE_Num;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Public Functions ----------------------------------------------------------- */
|
||||
/** @defgroup RTC_Public_Functions RTC Public Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
void RTC_Init (LPC_RTC_TypeDef *RTCx);
|
||||
void RTC_DeInit(LPC_RTC_TypeDef *RTCx);
|
||||
void RTC_ResetClockTickCounter(LPC_RTC_TypeDef *RTCx);
|
||||
void RTC_Cmd (LPC_RTC_TypeDef *RTCx, FunctionalState NewState);
|
||||
void RTC_CntIncrIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t CntIncrIntType, \
|
||||
FunctionalState NewState);
|
||||
void RTC_AlarmIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t AlarmTimeType, \
|
||||
FunctionalState NewState);
|
||||
void RTC_SetTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t TimeValue);
|
||||
uint32_t RTC_GetTime(LPC_RTC_TypeDef *RTCx, uint32_t Timetype);
|
||||
void RTC_SetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
|
||||
void RTC_GetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
|
||||
void RTC_SetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t ALValue);
|
||||
uint32_t RTC_GetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype);
|
||||
void RTC_SetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
|
||||
void RTC_GetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
|
||||
IntStatus RTC_GetIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType);
|
||||
void RTC_ClearIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType);
|
||||
void RTC_CalibCounterCmd(LPC_RTC_TypeDef *RTCx, FunctionalState NewState);
|
||||
void RTC_CalibConfig(LPC_RTC_TypeDef *RTCx, uint32_t CalibValue, uint8_t CalibDir);
|
||||
void RTC_WriteGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel, uint32_t Value);
|
||||
uint32_t RTC_ReadGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* LPC17XX_RTC_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* --------------------------------- End Of File ------------------------------ */
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Reference in a new issue