Shorter paths to HAL, ExtUI (#17156)
This commit is contained in:
343
Marlin/src/HAL/DUE/DebugMonitor.cpp
Normal file
343
Marlin/src/HAL/DUE/DebugMonitor.cpp
Normal file
@ -0,0 +1,343 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../core/macros.h"
|
||||
#include "../../core/serial.h"
|
||||
|
||||
#include "../shared/backtrace/unwinder.h"
|
||||
#include "../shared/backtrace/unwmemaccess.h"
|
||||
|
||||
#include <stdarg.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() {
|
||||
|
||||
// Disable UART interrupt in NVIC
|
||||
NVIC_DisableIRQ( UART_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();
|
||||
|
||||
// Disable clock
|
||||
pmc_disable_periph_clk( ID_UART );
|
||||
|
||||
// Configure PMC
|
||||
pmc_enable_periph_clk( ID_UART );
|
||||
|
||||
// Disable PDC channel
|
||||
UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
|
||||
|
||||
// Reset and disable receiver and transmitter
|
||||
UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
|
||||
|
||||
// Configure mode: 8bit, No parity, 1 bit stop
|
||||
UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
|
||||
|
||||
// Configure baudrate (asynchronous, no oversampling) to BAUDRATE bauds
|
||||
UART->UART_BRGR = (SystemCoreClock / (BAUDRATE << 4));
|
||||
|
||||
// Enable receiver and transmitter
|
||||
UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
|
||||
}
|
||||
|
||||
// Send character through UART with no interrupts
|
||||
static void TX(char c) {
|
||||
while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); };
|
||||
UART->UART_THR = 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
|
||||
#ifdef 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;
|
||||
|
||||
// Disable USB
|
||||
otg_disable();
|
||||
|
||||
// Restart watchdog
|
||||
WDT_Restart(WDT);
|
||||
|
||||
// Reset controller
|
||||
NVIC_SystemReset();
|
||||
for (;;) WDT_Restart(WDT);
|
||||
}
|
||||
|
||||
__attribute__((naked)) void NMI_Handler() {
|
||||
__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() {
|
||||
__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() {
|
||||
__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() {
|
||||
__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() {
|
||||
__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() {
|
||||
__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_Handler() {
|
||||
__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() {
|
||||
__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 // ARDUINO_ARCH_SAM
|
1020
Marlin/src/HAL/DUE/EepromEmulation.cpp
Normal file
1020
Marlin/src/HAL/DUE/EepromEmulation.cpp
Normal file
File diff suppressed because it is too large
Load Diff
106
Marlin/src/HAL/DUE/HAL.cpp
Normal file
106
Marlin/src/HAL/DUE/HAL.cpp
Normal file
@ -0,0 +1,106 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
|
||||
#include <Wire.h>
|
||||
#include "usb/usb_task.h"
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
// HAL initialization task
|
||||
void HAL_init() {
|
||||
// Initialize the USB stack
|
||||
#if ENABLED(SDSUPPORT)
|
||||
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
|
||||
#endif
|
||||
usb_task_init();
|
||||
}
|
||||
|
||||
// HAL idle task
|
||||
void HAL_idletask() {
|
||||
// Perform USB stack housekeeping
|
||||
usb_task_idle();
|
||||
}
|
||||
|
||||
// Disable interrupts
|
||||
void cli() { noInterrupts(); }
|
||||
|
||||
// Enable interrupts
|
||||
void sei() { interrupts(); }
|
||||
|
||||
void HAL_clear_reset_source() { }
|
||||
|
||||
uint8_t HAL_get_reset_source() {
|
||||
switch ((RSTC->RSTC_SR >> 8) & 0x07) {
|
||||
case 0: return RST_POWER_ON;
|
||||
case 1: return RST_BACKUP;
|
||||
case 2: return RST_WATCHDOG;
|
||||
case 3: return RST_SOFTWARE;
|
||||
case 4: return RST_EXTERNAL;
|
||||
default: return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void _delay_ms(const int delay_ms) {
|
||||
// Todo: port for Due?
|
||||
delay(delay_ms);
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
extern unsigned int _ebss; // end of bss section
|
||||
}
|
||||
|
||||
// Return free memory between end of heap (or end bss) and whatever is current
|
||||
int freeMemory() {
|
||||
int free_memory, heap_end = (int)_sbrk(0);
|
||||
return (int)&free_memory - (heap_end ?: (int)&_ebss);
|
||||
}
|
||||
|
||||
// ------------------------
|
||||
// ADC
|
||||
// ------------------------
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t ch) {
|
||||
HAL_adc_result = analogRead(ch);
|
||||
}
|
||||
|
||||
uint16_t HAL_adc_get_result() {
|
||||
// nop
|
||||
return HAL_adc_result;
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
198
Marlin/src/HAL/DUE/HAL.h
Normal file
198
Marlin/src/HAL/DUE/HAL.h
Normal file
@ -0,0 +1,198 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Description: HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
*/
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "fastio.h"
|
||||
#include "watchdog.h"
|
||||
#include "timers.h"
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// Define MYSERIAL0/1 before MarlinSerial includes!
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL0 customizedSerial1
|
||||
#elif SERIAL_PORT == 0
|
||||
#define MYSERIAL0 Serial
|
||||
#elif SERIAL_PORT == 1
|
||||
#define MYSERIAL0 Serial1
|
||||
#elif SERIAL_PORT == 2
|
||||
#define MYSERIAL0 Serial2
|
||||
#elif SERIAL_PORT == 3
|
||||
#define MYSERIAL0 Serial3
|
||||
#else
|
||||
#error "The required SERIAL_PORT must be from -1 to 3. Please update your configuration."
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
#if SERIAL_PORT_2 == SERIAL_PORT
|
||||
#error "SERIAL_PORT_2 must be different from SERIAL_PORT. Please update your configuration."
|
||||
#elif SERIAL_PORT_2 == -1
|
||||
#define MYSERIAL1 customizedSerial2
|
||||
#elif SERIAL_PORT_2 == 0
|
||||
#define MYSERIAL1 Serial
|
||||
#elif SERIAL_PORT_2 == 1
|
||||
#define MYSERIAL1 Serial1
|
||||
#elif SERIAL_PORT_2 == 2
|
||||
#define MYSERIAL1 Serial2
|
||||
#elif SERIAL_PORT_2 == 3
|
||||
#define MYSERIAL1 Serial3
|
||||
#else
|
||||
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
|
||||
#endif
|
||||
#define NUM_SERIAL 2
|
||||
#else
|
||||
#define NUM_SERIAL 1
|
||||
#endif
|
||||
|
||||
#ifdef DGUS_SERIAL_PORT
|
||||
#if DGUS_SERIAL_PORT == SERIAL_PORT
|
||||
#error "DGUS_SERIAL_PORT must be different from SERIAL_PORT. Please update your configuration."
|
||||
#elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
|
||||
#error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
|
||||
#elif DGUS_SERIAL_PORT == -1
|
||||
#define DGUS_SERIAL internalDgusSerial
|
||||
#elif DGUS_SERIAL_PORT == 0
|
||||
#define DGUS_SERIAL Serial
|
||||
#elif DGUS_SERIAL_PORT == 1
|
||||
#define DGUS_SERIAL Serial1
|
||||
#elif DGUS_SERIAL_PORT == 2
|
||||
#define DGUS_SERIAL Serial2
|
||||
#elif DGUS_SERIAL_PORT == 3
|
||||
#define DGUS_SERIAL Serial3
|
||||
#else
|
||||
#error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
#include "MarlinSerialUSB.h"
|
||||
|
||||
// On AVR this is in math.h?
|
||||
#define square(x) ((x)*(x))
|
||||
|
||||
#ifndef strncpy_P
|
||||
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
|
||||
#endif
|
||||
|
||||
// Fix bug in pgm_read_ptr
|
||||
#undef pgm_read_ptr
|
||||
#define pgm_read_ptr(addr) (*((void**)(addr)))
|
||||
#undef pgm_read_word
|
||||
#define pgm_read_word(addr) (*((uint16_t*)(addr)))
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
#define SHARED_SERVOS HAS_SERVOS
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
//
|
||||
// Interrupts
|
||||
//
|
||||
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
|
||||
#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
|
||||
#define ISRS_ENABLED() (!__get_PRIMASK())
|
||||
#define ENABLE_ISRS() __enable_irq()
|
||||
#define DISABLE_ISRS() __disable_irq()
|
||||
|
||||
void cli(); // Disable interrupts
|
||||
void sei(); // Enable interrupts
|
||||
|
||||
void HAL_clear_reset_source(); // clear reset reason
|
||||
uint8_t HAL_get_reset_source(); // get reset reason
|
||||
|
||||
//
|
||||
// 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);
|
||||
|
||||
//
|
||||
// ADC
|
||||
//
|
||||
extern uint16_t HAL_adc_result; // result of last ADC conversion
|
||||
|
||||
#ifndef analogInputToDigitalPin
|
||||
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
|
||||
#endif
|
||||
|
||||
#define HAL_ANALOG_SELECT(ch)
|
||||
|
||||
inline void HAL_adc_init() {}//todo
|
||||
|
||||
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
|
||||
#define HAL_ADC_RESOLUTION 10
|
||||
#define HAL_READ_ADC() HAL_adc_result
|
||||
#define HAL_ADC_READY() true
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t ch);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
//
|
||||
// Pin Map
|
||||
//
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
//
|
||||
// Tone
|
||||
//
|
||||
void toneInit();
|
||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
|
||||
void noTone(const pin_t _pin);
|
||||
|
||||
// Enable hooks into idle and setup for HAL
|
||||
#define HAL_IDLETASK 1
|
||||
void HAL_idletask();
|
||||
void HAL_init();
|
||||
|
||||
//
|
||||
// Utility functions
|
||||
//
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
int freeMemory();
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
826
Marlin/src/HAL/DUE/HAL_SPI.cpp
Normal file
826
Marlin/src/HAL/DUE/HAL_SPI.cpp
Normal file
@ -0,0 +1,826 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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
|
||||
*
|
||||
* Completely rewritten and tuned by Eduardo José Tagle in 2017/2018
|
||||
* in ARM thumb2 inline assembler and tuned for maximum speed and performance
|
||||
* allowing SPI clocks of up to 12 Mhz to increase SD card read/write performance
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
#if EITHER(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI)
|
||||
|
||||
// ------------------------
|
||||
// Software SPI
|
||||
// ------------------------
|
||||
|
||||
// Make sure GCC optimizes this file.
|
||||
// Note that this line triggers a bug in GCC which is fixed by casting.
|
||||
// See the note below.
|
||||
#pragma GCC optimize (3)
|
||||
|
||||
typedef uint8_t (*pfnSpiTransfer)(uint8_t b);
|
||||
typedef void (*pfnSpiRxBlock)(uint8_t* buf, uint32_t nbyte);
|
||||
typedef void (*pfnSpiTxBlock)(const uint8_t* buf, uint32_t nbyte);
|
||||
|
||||
/* ---------------- Macros to be able to access definitions from asm */
|
||||
#define _PORT(IO) DIO ## IO ## _WPORT
|
||||
#define _PIN_MASK(IO) MASK(DIO ## IO ## _PIN)
|
||||
#define _PIN_SHIFT(IO) DIO ## IO ## _PIN
|
||||
#define PORT(IO) _PORT(IO)
|
||||
#define PIN_MASK(IO) _PIN_MASK(IO)
|
||||
#define PIN_SHIFT(IO) _PIN_SHIFT(IO)
|
||||
|
||||
// run at ~8 .. ~10Mhz - Tx version (Rx data discarded)
|
||||
static uint8_t spiTransferTx0(uint8_t bout) { // using Mode 0
|
||||
uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(MOSI_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t MOSI_MASK = PIN_MASK(MOSI_PIN);
|
||||
uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t SCK_MASK = PIN_MASK(SCK_PIN);
|
||||
uint32_t idx = 0;
|
||||
|
||||
/* Negate bout, as the assembler requires a negated value */
|
||||
bout = ~bout;
|
||||
|
||||
/* The software SPI routine */
|
||||
__asm__ __volatile__(
|
||||
A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
|
||||
|
||||
/* Bit 7 */
|
||||
A("ubfx %[idx],%[txval],#7,#1") /* Place bit 7 in bit 0 of idx*/
|
||||
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#6,#1") /* Place bit 6 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 6 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#5,#1") /* Place bit 5 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 5 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#4,#1") /* Place bit 4 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 4 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#3,#1") /* Place bit 3 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 3 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#2,#1") /* Place bit 2 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 2 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#1,#1") /* Place bit 1 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 1 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[idx],%[txval],#0,#1") /* Place bit 0 in bit 0 of idx*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 0 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[idx],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("nop") /* Result will be 0 */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
: [idx]"+r"( idx )
|
||||
: [txval]"r"( bout ) ,
|
||||
[mosi_mask]"r"( MOSI_MASK ),
|
||||
[mosi_port]"r"( MOSI_PORT_PLUS30 ),
|
||||
[sck_mask]"r"( SCK_MASK ),
|
||||
[sck_port]"r"( SCK_PORT_PLUS30 )
|
||||
: "cc"
|
||||
);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Calculates the bit band alias address and returns a pointer address to word.
|
||||
// addr: The byte address of bitbanding bit.
|
||||
// bit: The bit position of bitbanding bit.
|
||||
#define BITBAND_ADDRESS(addr, bit) \
|
||||
(((uint32_t)(addr) & 0xF0000000) + 0x02000000 + ((uint32_t)(addr)&0xFFFFF)*32 + (bit)*4)
|
||||
|
||||
// run at ~8 .. ~10Mhz - Rx version (Tx line not altered)
|
||||
static uint8_t spiTransferRx0(uint8_t) { // using Mode 0
|
||||
uint32_t bin = 0;
|
||||
uint32_t work = 0;
|
||||
uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(MISO_PIN))+0x3C, PIN_SHIFT(MISO_PIN)); /* PDSR of port in bitband area */
|
||||
uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t SCK_MASK = PIN_MASK(SCK_PIN);
|
||||
|
||||
/* The software SPI routine */
|
||||
__asm__ __volatile__(
|
||||
A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
|
||||
|
||||
/* bit 7 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#7,#1") /* Store read bit as the bit 7 */
|
||||
|
||||
/* bit 6 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#6,#1") /* Store read bit as the bit 6 */
|
||||
|
||||
/* bit 5 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#5,#1") /* Store read bit as the bit 5 */
|
||||
|
||||
/* bit 4 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#4,#1") /* Store read bit as the bit 4 */
|
||||
|
||||
/* bit 3 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#3,#1") /* Store read bit as the bit 3 */
|
||||
|
||||
/* bit 2 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#2,#1") /* Store read bit as the bit 2 */
|
||||
|
||||
/* bit 1 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#1,#1") /* Store read bit as the bit 1 */
|
||||
|
||||
/* bit 0 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#0,#1") /* Store read bit as the bit 0 */
|
||||
|
||||
: [bin]"+r"(bin),
|
||||
[work]"+r"(work)
|
||||
: [bitband_miso_port]"r"( BITBAND_MISO_PORT ),
|
||||
[sck_mask]"r"( SCK_MASK ),
|
||||
[sck_port]"r"( SCK_PORT_PLUS30 )
|
||||
: "cc"
|
||||
);
|
||||
|
||||
return bin;
|
||||
}
|
||||
|
||||
// run at ~4Mhz
|
||||
static uint8_t spiTransfer1(uint8_t b) { // using Mode 0
|
||||
int bits = 8;
|
||||
do {
|
||||
WRITE(MOSI_PIN, b & 0x80);
|
||||
b <<= 1; // little setup time
|
||||
|
||||
WRITE(SCK_PIN, HIGH);
|
||||
DELAY_NS(125); // 10 cycles @ 84mhz
|
||||
|
||||
b |= (READ(MISO_PIN) != 0);
|
||||
|
||||
WRITE(SCK_PIN, LOW);
|
||||
DELAY_NS(125); // 10 cycles @ 84mhz
|
||||
} while (--bits);
|
||||
return b;
|
||||
}
|
||||
|
||||
// all the others
|
||||
static uint32_t spiDelayCyclesX4 = (F_CPU) / 1000000; // 4µs => 125khz
|
||||
|
||||
static uint8_t spiTransferX(uint8_t b) { // using Mode 0
|
||||
int bits = 8;
|
||||
do {
|
||||
WRITE(MOSI_PIN, b & 0x80);
|
||||
b <<= 1; // little setup time
|
||||
|
||||
WRITE(SCK_PIN, HIGH);
|
||||
__delay_4cycles(spiDelayCyclesX4);
|
||||
|
||||
b |= (READ(MISO_PIN) != 0);
|
||||
|
||||
WRITE(SCK_PIN, LOW);
|
||||
__delay_4cycles(spiDelayCyclesX4);
|
||||
} while (--bits);
|
||||
return b;
|
||||
}
|
||||
|
||||
// Pointers to generic functions for byte transfers
|
||||
|
||||
/**
|
||||
* Note: The cast is unnecessary, but without it, this file triggers a GCC 4.8.3-2014 bug.
|
||||
* Later GCC versions do not have this problem, but at this time (May 2018) Arduino still
|
||||
* uses that buggy and obsolete GCC version!!
|
||||
*/
|
||||
static pfnSpiTransfer spiTransferRx = (pfnSpiTransfer)spiTransferX;
|
||||
static pfnSpiTransfer spiTransferTx = (pfnSpiTransfer)spiTransferX;
|
||||
|
||||
// Block transfers run at ~8 .. ~10Mhz - Tx version (Rx data discarded)
|
||||
static void spiTxBlock0(const uint8_t* ptr, uint32_t todo) {
|
||||
uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(MOSI_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t MOSI_MASK = PIN_MASK(MOSI_PIN);
|
||||
uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t SCK_MASK = PIN_MASK(SCK_PIN);
|
||||
uint32_t work = 0;
|
||||
uint32_t txval = 0;
|
||||
|
||||
/* The software SPI routine */
|
||||
__asm__ __volatile__(
|
||||
A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
|
||||
|
||||
L("loop%=")
|
||||
A("ldrb.w %[txval], [%[ptr]], #1") /* Load value to send, increment buffer */
|
||||
A("mvn %[txval],%[txval]") /* Negate value */
|
||||
|
||||
/* Bit 7 */
|
||||
A("ubfx %[work],%[txval],#7,#1") /* Place bit 7 in bit 0 of work*/
|
||||
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#6,#1") /* Place bit 6 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 6 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#5,#1") /* Place bit 5 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 5 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#4,#1") /* Place bit 4 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 4 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#3,#1") /* Place bit 3 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 3 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#2,#1") /* Place bit 2 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 2 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#1,#1") /* Place bit 1 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 1 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ubfx %[work],%[txval],#0,#1") /* Place bit 0 in bit 0 of work*/
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
|
||||
/* Bit 0 */
|
||||
A("str %[mosi_mask],[%[mosi_port], %[work],LSL #2]") /* Access the proper SODR or CODR registers based on that bit */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("subs %[todo],#1") /* Decrement count of pending words to send, update status */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bne.n loop%=") /* Repeat until done */
|
||||
|
||||
: [ptr]"+r" ( ptr ) ,
|
||||
[todo]"+r" ( todo ) ,
|
||||
[work]"+r"( work ) ,
|
||||
[txval]"+r"( txval )
|
||||
: [mosi_mask]"r"( MOSI_MASK ),
|
||||
[mosi_port]"r"( MOSI_PORT_PLUS30 ),
|
||||
[sck_mask]"r"( SCK_MASK ),
|
||||
[sck_port]"r"( SCK_PORT_PLUS30 )
|
||||
: "cc"
|
||||
);
|
||||
}
|
||||
|
||||
static void spiRxBlock0(uint8_t* ptr, uint32_t todo) {
|
||||
uint32_t bin = 0;
|
||||
uint32_t work = 0;
|
||||
uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(MISO_PIN))+0x3C, PIN_SHIFT(MISO_PIN)); /* PDSR of port in bitband area */
|
||||
uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */
|
||||
uint32_t SCK_MASK = PIN_MASK(SCK_PIN);
|
||||
|
||||
/* The software SPI routine */
|
||||
__asm__ __volatile__(
|
||||
A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
|
||||
|
||||
L("loop%=")
|
||||
|
||||
/* bit 7 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#7,#1") /* Store read bit as the bit 7 */
|
||||
|
||||
/* bit 6 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#6,#1") /* Store read bit as the bit 6 */
|
||||
|
||||
/* bit 5 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#5,#1") /* Store read bit as the bit 5 */
|
||||
|
||||
/* bit 4 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#4,#1") /* Store read bit as the bit 4 */
|
||||
|
||||
/* bit 3 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#3,#1") /* Store read bit as the bit 3 */
|
||||
|
||||
/* bit 2 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#2,#1") /* Store read bit as the bit 2 */
|
||||
|
||||
/* bit 1 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#1,#1") /* Store read bit as the bit 1 */
|
||||
|
||||
/* bit 0 */
|
||||
A("str %[sck_mask],[%[sck_port]]") /* SODR */
|
||||
A("ldr %[work],[%[bitband_miso_port]]") /* PDSR on bitband area for required bit: work will be 1 or 0 based on port */
|
||||
A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */
|
||||
A("bfi %[bin],%[work],#0,#1") /* Store read bit as the bit 0 */
|
||||
|
||||
A("subs %[todo],#1") /* Decrement count of pending words to send, update status */
|
||||
A("strb.w %[bin], [%[ptr]], #1") /* Store read value into buffer, increment buffer pointer */
|
||||
A("bne.n loop%=") /* Repeat until done */
|
||||
|
||||
: [ptr]"+r"(ptr),
|
||||
[todo]"+r"(todo),
|
||||
[bin]"+r"(bin),
|
||||
[work]"+r"(work)
|
||||
: [bitband_miso_port]"r"( BITBAND_MISO_PORT ),
|
||||
[sck_mask]"r"( SCK_MASK ),
|
||||
[sck_port]"r"( SCK_PORT_PLUS30 )
|
||||
: "cc"
|
||||
);
|
||||
}
|
||||
|
||||
static void spiTxBlockX(const uint8_t* buf, uint32_t todo) {
|
||||
do {
|
||||
(void)spiTransferTx(*buf++);
|
||||
} while (--todo);
|
||||
}
|
||||
|
||||
static void spiRxBlockX(uint8_t* buf, uint32_t todo) {
|
||||
do {
|
||||
*buf++ = spiTransferRx(0xFF);
|
||||
} while (--todo);
|
||||
}
|
||||
|
||||
// Pointers to generic functions for block tranfers
|
||||
static pfnSpiTxBlock spiTxBlock = (pfnSpiTxBlock)spiTxBlockX;
|
||||
static pfnSpiRxBlock spiRxBlock = (pfnSpiRxBlock)spiRxBlockX;
|
||||
|
||||
#if MB(ALLIGATOR)
|
||||
#define _SS_WRITE(S) WRITE(SS_PIN, S)
|
||||
#else
|
||||
#define _SS_WRITE(S) NOOP
|
||||
#endif
|
||||
|
||||
void spiBegin() {
|
||||
SET_OUTPUT(SS_PIN);
|
||||
_SS_WRITE(HIGH);
|
||||
SET_OUTPUT(SCK_PIN);
|
||||
SET_INPUT(MISO_PIN);
|
||||
SET_OUTPUT(MOSI_PIN);
|
||||
}
|
||||
|
||||
uint8_t spiRec() {
|
||||
_SS_WRITE(LOW);
|
||||
WRITE(MOSI_PIN, HIGH); // Output 1s 1
|
||||
uint8_t b = spiTransferRx(0xFF);
|
||||
_SS_WRITE(HIGH);
|
||||
return b;
|
||||
}
|
||||
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
if (nbyte) {
|
||||
_SS_WRITE(LOW);
|
||||
WRITE(MOSI_PIN, HIGH); // Output 1s 1
|
||||
spiRxBlock(buf, nbyte);
|
||||
_SS_WRITE(HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
void spiSend(uint8_t b) {
|
||||
_SS_WRITE(LOW);
|
||||
(void)spiTransferTx(b);
|
||||
_SS_WRITE(HIGH);
|
||||
}
|
||||
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
_SS_WRITE(LOW);
|
||||
(void)spiTransferTx(token);
|
||||
spiTxBlock(buf, 512);
|
||||
_SS_WRITE(HIGH);
|
||||
}
|
||||
|
||||
/**
|
||||
* spiRate should be
|
||||
* 0 : 8 - 10 MHz
|
||||
* 1 : 4 - 5 MHz
|
||||
* 2 : 2 - 2.5 MHz
|
||||
* 3 : 1 - 1.25 MHz
|
||||
* 4 : 500 - 625 kHz
|
||||
* 5 : 250 - 312 kHz
|
||||
* 6 : 125 - 156 kHz
|
||||
*/
|
||||
void spiInit(uint8_t spiRate) {
|
||||
switch (spiRate) {
|
||||
case 0:
|
||||
spiTransferTx = (pfnSpiTransfer)spiTransferTx0;
|
||||
spiTransferRx = (pfnSpiTransfer)spiTransferRx0;
|
||||
spiTxBlock = (pfnSpiTxBlock)spiTxBlock0;
|
||||
spiRxBlock = (pfnSpiRxBlock)spiRxBlock0;
|
||||
break;
|
||||
case 1:
|
||||
spiTransferTx = (pfnSpiTransfer)spiTransfer1;
|
||||
spiTransferRx = (pfnSpiTransfer)spiTransfer1;
|
||||
spiTxBlock = (pfnSpiTxBlock)spiTxBlockX;
|
||||
spiRxBlock = (pfnSpiRxBlock)spiRxBlockX;
|
||||
break;
|
||||
default:
|
||||
spiDelayCyclesX4 = ((F_CPU) / 1000000) >> (6 - spiRate);
|
||||
spiTransferTx = (pfnSpiTransfer)spiTransferX;
|
||||
spiTransferRx = (pfnSpiTransfer)spiTransferX;
|
||||
spiTxBlock = (pfnSpiTxBlock)spiTxBlockX;
|
||||
spiRxBlock = (pfnSpiRxBlock)spiRxBlockX;
|
||||
break;
|
||||
}
|
||||
|
||||
_SS_WRITE(HIGH);
|
||||
WRITE(MOSI_PIN, HIGH);
|
||||
WRITE(SCK_PIN, LOW);
|
||||
}
|
||||
|
||||
/** Begin SPI transaction, set clock, bit order, data mode */
|
||||
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
|
||||
// TODO: to be implemented
|
||||
}
|
||||
|
||||
#pragma GCC reset_options
|
||||
|
||||
#else // !SOFTWARE_SPI
|
||||
|
||||
#define WHILE_TX(N) while ((SPI0->SPI_SR & SPI_SR_TDRE) == (N))
|
||||
#define WHILE_RX(N) while ((SPI0->SPI_SR & SPI_SR_RDRF) == (N))
|
||||
#define FLUSH_TX() do{ WHILE_RX(1) SPI0->SPI_RDR; }while(0)
|
||||
|
||||
#if MB(ALLIGATOR)
|
||||
|
||||
// slave selects controlled by SPI controller
|
||||
// doesn't support changing SPI speeds for SD card
|
||||
|
||||
// ------------------------
|
||||
// hardware SPI
|
||||
// ------------------------
|
||||
static bool spiInitialized = false;
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
if (spiInitialized) return;
|
||||
|
||||
// 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz
|
||||
constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 };
|
||||
if (spiRate > 6) spiRate = 1;
|
||||
|
||||
// Set SPI mode 1, clock, select not active after transfer, with delay between transfers
|
||||
SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC,
|
||||
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDivider[spiRate]) |
|
||||
SPI_CSR_DLYBCT(1));
|
||||
// Set SPI mode 0, clock, select not active after transfer, with delay between transfers
|
||||
SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA |
|
||||
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDivider[spiRate]) |
|
||||
SPI_CSR_DLYBCT(1));
|
||||
|
||||
// Set SPI mode 0, clock, select not active after transfer, with delay between transfers
|
||||
SPI_ConfigureNPCS(SPI0, SPI_CHAN, SPI_CSR_NCPHA |
|
||||
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDivider[spiRate]) |
|
||||
SPI_CSR_DLYBCT(1));
|
||||
SPI_Enable(SPI0);
|
||||
spiInitialized = true;
|
||||
}
|
||||
|
||||
void spiBegin() {
|
||||
if (spiInitialized) return;
|
||||
|
||||
// Configure SPI pins
|
||||
PIO_Configure(
|
||||
g_APinDescription[SCK_PIN].pPort,
|
||||
g_APinDescription[SCK_PIN].ulPinType,
|
||||
g_APinDescription[SCK_PIN].ulPin,
|
||||
g_APinDescription[SCK_PIN].ulPinConfiguration);
|
||||
PIO_Configure(
|
||||
g_APinDescription[MOSI_PIN].pPort,
|
||||
g_APinDescription[MOSI_PIN].ulPinType,
|
||||
g_APinDescription[MOSI_PIN].ulPin,
|
||||
g_APinDescription[MOSI_PIN].ulPinConfiguration);
|
||||
PIO_Configure(
|
||||
g_APinDescription[MISO_PIN].pPort,
|
||||
g_APinDescription[MISO_PIN].ulPinType,
|
||||
g_APinDescription[MISO_PIN].ulPin,
|
||||
g_APinDescription[MISO_PIN].ulPinConfiguration);
|
||||
|
||||
// set master mode, peripheral select, fault detection
|
||||
SPI_Configure(SPI0, ID_SPI0, SPI_MR_MSTR | SPI_MR_MODFDIS | SPI_MR_PS);
|
||||
SPI_Enable(SPI0);
|
||||
|
||||
SET_OUTPUT(DAC0_SYNC);
|
||||
#if EXTRUDERS > 1
|
||||
SET_OUTPUT(DAC1_SYNC);
|
||||
WRITE(DAC1_SYNC, HIGH);
|
||||
#endif
|
||||
SET_OUTPUT(SPI_EEPROM1_CS);
|
||||
SET_OUTPUT(SPI_EEPROM2_CS);
|
||||
SET_OUTPUT(SPI_FLASH_CS);
|
||||
WRITE(DAC0_SYNC, HIGH);
|
||||
WRITE(SPI_EEPROM1_CS, HIGH);
|
||||
WRITE(SPI_EEPROM2_CS, HIGH);
|
||||
WRITE(SPI_FLASH_CS, HIGH);
|
||||
WRITE(SS_PIN, HIGH);
|
||||
|
||||
OUT_WRITE(SDSS, LOW);
|
||||
|
||||
PIO_Configure(
|
||||
g_APinDescription[SPI_PIN].pPort,
|
||||
g_APinDescription[SPI_PIN].ulPinType,
|
||||
g_APinDescription[SPI_PIN].ulPin,
|
||||
g_APinDescription[SPI_PIN].ulPinConfiguration
|
||||
);
|
||||
|
||||
spiInit(1);
|
||||
}
|
||||
|
||||
// Read single byte from SPI
|
||||
uint8_t spiRec() {
|
||||
// write dummy byte with address and end transmission flag
|
||||
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER;
|
||||
|
||||
WHILE_TX(0);
|
||||
WHILE_RX(0);
|
||||
|
||||
//DELAY_US(1U);
|
||||
return SPI0->SPI_RDR;
|
||||
}
|
||||
|
||||
uint8_t spiRec(uint32_t chan) {
|
||||
|
||||
WHILE_TX(0);
|
||||
FLUSH_RX();
|
||||
|
||||
// write dummy byte with address and end transmission flag
|
||||
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(chan) | SPI_TDR_LASTXFER;
|
||||
WHILE_RX(0);
|
||||
|
||||
return SPI0->SPI_RDR;
|
||||
}
|
||||
|
||||
// Read from SPI into buffer
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
if (!nbyte) return;
|
||||
--nbyte;
|
||||
for (int i = 0; i < nbyte; i++) {
|
||||
//WHILE_TX(0);
|
||||
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN);
|
||||
WHILE_RX(0);
|
||||
buf[i] = SPI0->SPI_RDR;
|
||||
//DELAY_US(1U);
|
||||
}
|
||||
buf[nbyte] = spiRec();
|
||||
}
|
||||
|
||||
// Write single byte to SPI
|
||||
void spiSend(const byte b) {
|
||||
// write byte with address and end transmission flag
|
||||
SPI0->SPI_TDR = (uint32_t)b | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER;
|
||||
WHILE_TX(0);
|
||||
WHILE_RX(0);
|
||||
SPI0->SPI_RDR;
|
||||
//DELAY_US(1U);
|
||||
}
|
||||
|
||||
void spiSend(const uint8_t* buf, size_t nbyte) {
|
||||
if (!nbyte) return;
|
||||
--nbyte;
|
||||
for (size_t i = 0; i < nbyte; i++) {
|
||||
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(SPI_CHAN);
|
||||
WHILE_TX(0);
|
||||
WHILE_RX(0);
|
||||
SPI0->SPI_RDR;
|
||||
//DELAY_US(1U);
|
||||
}
|
||||
spiSend(buf[nbyte]);
|
||||
}
|
||||
|
||||
void spiSend(uint32_t chan, byte b) {
|
||||
WHILE_TX(0);
|
||||
// write byte with address and end transmission flag
|
||||
SPI0->SPI_TDR = (uint32_t)b | SPI_PCS(chan) | SPI_TDR_LASTXFER;
|
||||
WHILE_RX(0);
|
||||
FLUSH_RX();
|
||||
}
|
||||
|
||||
void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) {
|
||||
if (!nbyte) return;
|
||||
--nbyte;
|
||||
for (size_t i = 0; i < nbyte; i++) {
|
||||
WHILE_TX(0);
|
||||
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(chan);
|
||||
WHILE_RX(0);
|
||||
FLUSH_RX();
|
||||
}
|
||||
spiSend(chan, buf[nbyte]);
|
||||
}
|
||||
|
||||
// Write from buffer to SPI
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
SPI0->SPI_TDR = (uint32_t)token | SPI_PCS(SPI_CHAN);
|
||||
WHILE_TX(0);
|
||||
//WHILE_RX(0);
|
||||
//SPI0->SPI_RDR;
|
||||
for (int i = 0; i < 511; i++) {
|
||||
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(SPI_CHAN);
|
||||
WHILE_TX(0);
|
||||
WHILE_RX(0);
|
||||
SPI0->SPI_RDR;
|
||||
//DELAY_US(1U);
|
||||
}
|
||||
spiSend(buf[511]);
|
||||
}
|
||||
|
||||
/** Begin SPI transaction, set clock, bit order, data mode */
|
||||
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
|
||||
// TODO: to be implemented
|
||||
}
|
||||
|
||||
#else // U8G compatible hardware SPI
|
||||
|
||||
#define SPI_MODE_0_DUE_HW 2 // DUE CPHA control bit is inverted
|
||||
#define SPI_MODE_1_DUE_HW 3
|
||||
#define SPI_MODE_2_DUE_HW 0
|
||||
#define SPI_MODE_3_DUE_HW 1
|
||||
|
||||
/**
|
||||
* The DUE SPI controller is set up so the upper word of the longword
|
||||
* written to the transmit data register selects which SPI Chip Select
|
||||
* Register is used. This allows different streams to have different SPI
|
||||
* settings.
|
||||
*
|
||||
* In practice it's spooky. Some combinations hang the system, while others
|
||||
* upset the peripheral device.
|
||||
*
|
||||
* SPI mode should be the same for all streams. The FYSETC_MINI_12864 gets
|
||||
* upset if the clock phase changes after chip select goes active.
|
||||
*
|
||||
* SPI_CSR_CSAAT should be set for all streams. If not the WHILE_TX(0)
|
||||
* macro returns immediately which can result in the SPI chip select going
|
||||
* inactive before all the data has been sent.
|
||||
*
|
||||
* The TMC2130 library uses SPI0->SPI_CSR[3].
|
||||
*
|
||||
* The U8G hardware SPI uses SPI0->SPI_CSR[0]. The system hangs and/or the
|
||||
* FYSETC_MINI_12864 gets upset if lower baud rates are used and the SD card
|
||||
* is inserted or removed.
|
||||
*
|
||||
* The SD card uses SPI0->SPI_CSR[3]. Efforts were made to use [1] and [2]
|
||||
* but they all resulted in hangs or garbage on the LCD.
|
||||
*
|
||||
* The SPI controlled chip selects are NOT enabled in the GPIO controller.
|
||||
* The application must control the chip select.
|
||||
*
|
||||
* All of the above can be avoided by defining FORCE_SOFT_SPI to force the
|
||||
* display to use software SPI.
|
||||
*
|
||||
*/
|
||||
|
||||
void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified)
|
||||
// Also sets U8G SPI rate to 4MHz and the SPI mode to 3
|
||||
|
||||
// 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz
|
||||
constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 };
|
||||
if (spiRate > 6) spiRate = 1;
|
||||
|
||||
// Enable PIOA and SPI0
|
||||
REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0);
|
||||
|
||||
// Disable PIO on A26 and A27
|
||||
REG_PIOA_PDR = 0x0C000000;
|
||||
OUT_WRITE(SDSS, HIGH);
|
||||
|
||||
// Reset SPI0 (from sam lib)
|
||||
SPI0->SPI_CR = SPI_CR_SPIDIS;
|
||||
SPI0->SPI_CR = SPI_CR_SWRST;
|
||||
SPI0->SPI_CR = SPI_CR_SWRST;
|
||||
SPI0->SPI_CR = SPI_CR_SPIEN;
|
||||
|
||||
// TMC2103 compatible setup
|
||||
// Master mode, no fault detection, PCS bits in data written to TDR select CSR register
|
||||
SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PS | SPI_MR_MODFDIS;
|
||||
// SPI mode 3, 8 Bit data transfer, baud rate
|
||||
SPI0->SPI_CSR[3] = SPI_CSR_SCBR(spiDivider[spiRate]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW; // use same CSR as TMC2130
|
||||
SPI0->SPI_CSR[0] = SPI_CSR_SCBR(spiDivider[1]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW; // U8G default to 4MHz
|
||||
}
|
||||
|
||||
void spiBegin() { spiInit(); }
|
||||
|
||||
static uint8_t spiTransfer(uint8_t data) {
|
||||
WHILE_TX(0);
|
||||
SPI0->SPI_TDR = (uint32_t)data | 0x00070000UL; // Add TMC2130 PCS bits to every byte (use SPI0->SPI_CSR[3])
|
||||
WHILE_TX(0);
|
||||
WHILE_RX(0);
|
||||
return SPI0->SPI_RDR;
|
||||
}
|
||||
|
||||
uint8_t spiRec() { return (uint8_t)spiTransfer(0xFF); }
|
||||
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
for (int i = 0; i < nbyte; i++)
|
||||
buf[i] = spiTransfer(0xFF);
|
||||
}
|
||||
|
||||
void spiSend(uint8_t data) { spiTransfer(data); }
|
||||
|
||||
void spiSend(const uint8_t* buf, size_t nbyte) {
|
||||
for (uint16_t i = 0; i < nbyte; i++)
|
||||
spiTransfer(buf[i]);
|
||||
}
|
||||
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
spiTransfer(token);
|
||||
for (uint16_t i = 0; i < 512; i++)
|
||||
spiTransfer(buf[i]);
|
||||
}
|
||||
|
||||
#endif // !ALLIGATOR
|
||||
#endif // !SOFTWARE_SPI
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
98
Marlin/src/HAL/DUE/InterruptVectors.cpp
Normal file
98
Marlin/src/HAL/DUE/InterruptVectors.cpp
Normal file
@ -0,0 +1,98 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* InterruptVectors_Due.cpp - This module relocates the Interrupt vector table to SRAM,
|
||||
* allowing to register new interrupt handlers at runtime. Specially valuable and needed
|
||||
* because Arduino runtime allocates some interrupt handlers that we NEED to override to
|
||||
* properly support extended functionality, as for example, USB host or USB device (MSD, MTP)
|
||||
* and custom serial port handlers, and we don't actually want to modify and/or recompile the
|
||||
* Arduino runtime. We just want to run as much as possible on Stock Arduino
|
||||
*
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
#include "InterruptVectors.h"
|
||||
|
||||
/* The relocated Exception/Interrupt Table - According to the ARM
|
||||
reference manual, alignment to 128 bytes should suffice, but in
|
||||
practice, we need alignment to 256 bytes to make this work in all
|
||||
cases */
|
||||
__attribute__ ((aligned(256)))
|
||||
static DeviceVectors ram_tab = { nullptr };
|
||||
|
||||
/**
|
||||
* This function checks if the exception/interrupt table is already in SRAM or not.
|
||||
* If it is not, then it copies the ROM table to the SRAM and relocates the table
|
||||
* by reprogramming the NVIC registers
|
||||
*/
|
||||
static pfnISR_Handler* get_relocated_table_addr() {
|
||||
// Get the address of the interrupt/exception table
|
||||
uint32_t isrtab = SCB->VTOR;
|
||||
|
||||
// If already relocated, we are done!
|
||||
if (isrtab >= IRAM0_ADDR)
|
||||
return (pfnISR_Handler*)isrtab;
|
||||
|
||||
// Get the address of the table stored in FLASH
|
||||
const pfnISR_Handler* romtab = (const pfnISR_Handler*)isrtab;
|
||||
|
||||
// Copy it to SRAM
|
||||
memcpy(&ram_tab, romtab, sizeof(ram_tab));
|
||||
|
||||
// Disable global interrupts
|
||||
CRITICAL_SECTION_START();
|
||||
|
||||
// Set the vector table base address to the SRAM copy
|
||||
SCB->VTOR = (uint32_t)(&ram_tab);
|
||||
|
||||
// Reenable interrupts
|
||||
CRITICAL_SECTION_END();
|
||||
|
||||
// Return the address of the table
|
||||
return (pfnISR_Handler*)(&ram_tab);
|
||||
}
|
||||
|
||||
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler) {
|
||||
// Get the address of the relocated table
|
||||
pfnISR_Handler *isrtab = get_relocated_table_addr();
|
||||
|
||||
// Disable global interrupts
|
||||
CRITICAL_SECTION_START();
|
||||
|
||||
// Get the original handler
|
||||
pfnISR_Handler oldHandler = isrtab[irq + 16];
|
||||
|
||||
// Install the new one
|
||||
isrtab[irq + 16] = newHandler;
|
||||
|
||||
// Reenable interrupts
|
||||
CRITICAL_SECTION_END();
|
||||
|
||||
// Return the original one
|
||||
return oldHandler;
|
||||
}
|
||||
|
||||
#endif
|
45
Marlin/src/HAL/DUE/InterruptVectors.h
Normal file
45
Marlin/src/HAL/DUE/InterruptVectors.h
Normal file
@ -0,0 +1,45 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* InterruptVectors_Due.h
|
||||
*
|
||||
* This module relocates the Interrupt vector table to SRAM, allowing new
|
||||
* interrupt handlers to be added at runtime. This is required because the
|
||||
* Arduino runtime steals interrupt handlers that Marlin MUST use to support
|
||||
* extended functionality such as USB hosts and USB devices (MSD, MTP) and
|
||||
* custom serial port handlers. Rather than modifying and/or recompiling the
|
||||
* Arduino runtime, We just want to run as much as possible on Stock Arduino.
|
||||
*
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
// ISR handler type
|
||||
typedef void (*pfnISR_Handler)();
|
||||
|
||||
// Install a new interrupt vector handler for the given irq, returning the old one
|
||||
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler);
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
651
Marlin/src/HAL/DUE/MarlinSerial.cpp
Normal file
651
Marlin/src/HAL/DUE/MarlinSerial.cpp
Normal file
@ -0,0 +1,651 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
#include "InterruptVectors.h"
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_r MarlinSerial<Cfg>::rx_buffer = { 0, 0, { 0 } };
|
||||
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_t MarlinSerial<Cfg>::tx_buffer = { 0 };
|
||||
template<typename Cfg> bool MarlinSerial<Cfg>::_written = false;
|
||||
template<typename Cfg> uint8_t MarlinSerial<Cfg>::xon_xoff_state = MarlinSerial<Cfg>::XON_XOFF_CHAR_SENT | MarlinSerial<Cfg>::XON_CHAR;
|
||||
template<typename Cfg> uint8_t MarlinSerial<Cfg>::rx_dropped_bytes = 0;
|
||||
template<typename Cfg> uint8_t MarlinSerial<Cfg>::rx_buffer_overruns = 0;
|
||||
template<typename Cfg> uint8_t MarlinSerial<Cfg>::rx_framing_errors = 0;
|
||||
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::rx_max_enqueued = 0;
|
||||
|
||||
// A SW memory barrier, to ensure GCC does not overoptimize loops
|
||||
#define sw_barrier() asm volatile("": : :"memory");
|
||||
|
||||
#include "../../feature/e_parser.h"
|
||||
|
||||
// (called with RX interrupts disabled)
|
||||
template<typename Cfg>
|
||||
FORCE_INLINE void MarlinSerial<Cfg>::store_rxd_char() {
|
||||
|
||||
static EmergencyParser::State emergency_state; // = EP_RESET
|
||||
|
||||
// Get the tail - Nothing can alter its value while we are at this ISR
|
||||
const ring_buffer_pos_t t = rx_buffer.tail;
|
||||
|
||||
// Get the head pointer
|
||||
ring_buffer_pos_t h = rx_buffer.head;
|
||||
|
||||
// Get the next element
|
||||
ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
|
||||
// Read the character from the USART
|
||||
uint8_t c = HWUART->UART_RHR;
|
||||
|
||||
if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
|
||||
|
||||
// If the character is to be stored at the index just before the tail
|
||||
// (such that the head would advance to the current tail), the RX FIFO is
|
||||
// full, so don't write the character or advance the head.
|
||||
if (i != t) {
|
||||
rx_buffer.buffer[h] = c;
|
||||
h = i;
|
||||
}
|
||||
else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
|
||||
--rx_dropped_bytes;
|
||||
|
||||
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
// Calculate count of bytes stored into the RX buffer
|
||||
|
||||
// Keep track of the maximum count of enqueued bytes
|
||||
if (Cfg::MAX_RX_QUEUED) NOLESS(rx_max_enqueued, rx_count);
|
||||
|
||||
if (Cfg::XONOFF) {
|
||||
// If the last char that was sent was an XON
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
|
||||
|
||||
// Bytes stored into the RX buffer
|
||||
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
|
||||
// If over 12.5% of RX buffer capacity, send XOFF before running out of
|
||||
// RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react
|
||||
// and stop sending bytes. This translates to 13mS propagation time.
|
||||
if (rx_count >= (Cfg::RX_SIZE) / 8) {
|
||||
|
||||
// At this point, definitely no TX interrupt was executing, since the TX isr can't be preempted.
|
||||
// Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens
|
||||
// to be in the middle of trying to disable the RX interrupt in the main program, eventually the
|
||||
// enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure
|
||||
// the sending of the XOFF char is to send it HERE AND NOW.
|
||||
|
||||
// About to send the XOFF char
|
||||
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
|
||||
|
||||
// Wait until the TX register becomes empty and send it - Here there could be a problem
|
||||
// - While waiting for the TX register to empty, the RX register could receive a new
|
||||
// character. This must also handle that situation!
|
||||
uint32_t status;
|
||||
while (!((status = HWUART->UART_SR) & UART_SR_TXRDY)) {
|
||||
|
||||
if (status & UART_SR_RXRDY) {
|
||||
// We received a char while waiting for the TX buffer to be empty - Receive and process it!
|
||||
|
||||
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
|
||||
// Read the character from the USART
|
||||
c = HWUART->UART_RHR;
|
||||
|
||||
if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
|
||||
|
||||
// If the character is to be stored at the index just before the tail
|
||||
// (such that the head would advance to the current tail), the FIFO is
|
||||
// full, so don't write the character or advance the head.
|
||||
if (i != t) {
|
||||
rx_buffer.buffer[h] = c;
|
||||
h = i;
|
||||
}
|
||||
else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
|
||||
--rx_dropped_bytes;
|
||||
}
|
||||
sw_barrier();
|
||||
}
|
||||
|
||||
HWUART->UART_THR = XOFF_CHAR;
|
||||
|
||||
// At this point there could be a race condition between the write() function
|
||||
// and this sending of the XOFF char. This interrupt could happen between the
|
||||
// wait to be empty TX buffer loop and the actual write of the character. Since
|
||||
// the TX buffer is full because it's sending the XOFF char, the only way to be
|
||||
// sure the write() function will succeed is to wait for the XOFF char to be
|
||||
// completely sent. Since an extra character could be received during the wait
|
||||
// it must also be handled!
|
||||
while (!((status = HWUART->UART_SR) & UART_SR_TXRDY)) {
|
||||
|
||||
if (status & UART_SR_RXRDY) {
|
||||
// A char arrived while waiting for the TX buffer to be empty - Receive and process it!
|
||||
|
||||
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
|
||||
// Read the character from the USART
|
||||
c = HWUART->UART_RHR;
|
||||
|
||||
if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
|
||||
|
||||
// If the character is to be stored at the index just before the tail
|
||||
// (such that the head would advance to the current tail), the FIFO is
|
||||
// full, so don't write the character or advance the head.
|
||||
if (i != t) {
|
||||
rx_buffer.buffer[h] = c;
|
||||
h = i;
|
||||
}
|
||||
else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
|
||||
--rx_dropped_bytes;
|
||||
}
|
||||
sw_barrier();
|
||||
}
|
||||
|
||||
// At this point everything is ready. The write() function won't
|
||||
// have any issues writing to the UART TX register if it needs to!
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Store the new head value
|
||||
rx_buffer.head = h;
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
FORCE_INLINE void MarlinSerial<Cfg>::_tx_thr_empty_irq() {
|
||||
if (Cfg::TX_SIZE > 0) {
|
||||
// Read positions
|
||||
uint8_t t = tx_buffer.tail;
|
||||
const uint8_t h = tx_buffer.head;
|
||||
|
||||
if (Cfg::XONOFF) {
|
||||
// If an XON char is pending to be sent, do it now
|
||||
if (xon_xoff_state == XON_CHAR) {
|
||||
|
||||
// Send the character
|
||||
HWUART->UART_THR = XON_CHAR;
|
||||
|
||||
// Remember we sent it.
|
||||
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
|
||||
|
||||
// If nothing else to transmit, just disable TX interrupts.
|
||||
if (h == t) HWUART->UART_IDR = UART_IDR_TXRDY;
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// If nothing to transmit, just disable TX interrupts. This could
|
||||
// happen as the result of the non atomicity of the disabling of RX
|
||||
// interrupts that could end reenabling TX interrupts as a side effect.
|
||||
if (h == t) {
|
||||
HWUART->UART_IDR = UART_IDR_TXRDY;
|
||||
return;
|
||||
}
|
||||
|
||||
// There is something to TX, Send the next byte
|
||||
const uint8_t c = tx_buffer.buffer[t];
|
||||
t = (t + 1) & (Cfg::TX_SIZE - 1);
|
||||
HWUART->UART_THR = c;
|
||||
tx_buffer.tail = t;
|
||||
|
||||
// Disable interrupts if there is nothing to transmit following this byte
|
||||
if (h == t) HWUART->UART_IDR = UART_IDR_TXRDY;
|
||||
}
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::UART_ISR() {
|
||||
const uint32_t status = HWUART->UART_SR;
|
||||
|
||||
// Data received?
|
||||
if (status & UART_SR_RXRDY) store_rxd_char();
|
||||
|
||||
if (Cfg::TX_SIZE > 0) {
|
||||
// Something to send, and TX interrupts are enabled (meaning something to send)?
|
||||
if ((status & UART_SR_TXRDY) && (HWUART->UART_IMR & UART_IMR_TXRDY)) _tx_thr_empty_irq();
|
||||
}
|
||||
|
||||
// Acknowledge errors
|
||||
if ((status & UART_SR_OVRE) || (status & UART_SR_FRAME)) {
|
||||
if (Cfg::DROPPED_RX && (status & UART_SR_OVRE) && !++rx_dropped_bytes) --rx_dropped_bytes;
|
||||
if (Cfg::RX_OVERRUNS && (status & UART_SR_OVRE) && !++rx_buffer_overruns) --rx_buffer_overruns;
|
||||
if (Cfg::RX_FRAMING_ERRORS && (status & UART_SR_FRAME) && !++rx_framing_errors) --rx_framing_errors;
|
||||
|
||||
// TODO: error reporting outside ISR
|
||||
HWUART->UART_CR = UART_CR_RSTSTA;
|
||||
}
|
||||
}
|
||||
|
||||
// Public Methods
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::begin(const long baud_setting) {
|
||||
|
||||
// Disable UART interrupt in NVIC
|
||||
NVIC_DisableIRQ( HWUART_IRQ );
|
||||
|
||||
// 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();
|
||||
|
||||
// Disable clock
|
||||
pmc_disable_periph_clk( HWUART_IRQ_ID );
|
||||
|
||||
// Configure PMC
|
||||
pmc_enable_periph_clk( HWUART_IRQ_ID );
|
||||
|
||||
// Disable PDC channel
|
||||
HWUART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
|
||||
|
||||
// Reset and disable receiver and transmitter
|
||||
HWUART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
|
||||
|
||||
// Configure mode: 8bit, No parity, 1 bit stop
|
||||
HWUART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
|
||||
|
||||
// Configure baudrate (asynchronous, no oversampling)
|
||||
HWUART->UART_BRGR = (SystemCoreClock / (baud_setting << 4));
|
||||
|
||||
// Configure interrupts
|
||||
HWUART->UART_IDR = 0xFFFFFFFF;
|
||||
HWUART->UART_IER = UART_IER_RXRDY | UART_IER_OVRE | UART_IER_FRAME;
|
||||
|
||||
// Install interrupt handler
|
||||
install_isr(HWUART_IRQ, UART_ISR);
|
||||
|
||||
// Configure priority. We need a very high priority to avoid losing characters
|
||||
// and we need to be able to preempt the Stepper ISR and everything else!
|
||||
// (this could probably be fixed by using DMA with the Serial port)
|
||||
NVIC_SetPriority(HWUART_IRQ, 1);
|
||||
|
||||
// Enable UART interrupt in NVIC
|
||||
NVIC_EnableIRQ(HWUART_IRQ);
|
||||
|
||||
// Enable receiver and transmitter
|
||||
HWUART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
|
||||
|
||||
if (Cfg::TX_SIZE > 0) _written = false;
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::end() {
|
||||
// Disable UART interrupt in NVIC
|
||||
NVIC_DisableIRQ( HWUART_IRQ );
|
||||
|
||||
// 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();
|
||||
|
||||
pmc_disable_periph_clk( HWUART_IRQ_ID );
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
int MarlinSerial<Cfg>::peek() {
|
||||
const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
|
||||
return v;
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
int MarlinSerial<Cfg>::read() {
|
||||
|
||||
const ring_buffer_pos_t h = rx_buffer.head;
|
||||
ring_buffer_pos_t t = rx_buffer.tail;
|
||||
|
||||
if (h == t) return -1;
|
||||
|
||||
int v = rx_buffer.buffer[t];
|
||||
t = (ring_buffer_pos_t)(t + 1) & (Cfg::RX_SIZE - 1);
|
||||
|
||||
// Advance tail
|
||||
rx_buffer.tail = t;
|
||||
|
||||
if (Cfg::XONOFF) {
|
||||
// If the XOFF char was sent, or about to be sent...
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
|
||||
// Get count of bytes in the RX buffer
|
||||
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
|
||||
// When below 10% of RX buffer capacity, send XON before running out of RX buffer bytes
|
||||
if (rx_count < (Cfg::RX_SIZE) / 10) {
|
||||
if (Cfg::TX_SIZE > 0) {
|
||||
// Signal we want an XON character to be sent.
|
||||
xon_xoff_state = XON_CHAR;
|
||||
// Enable TX isr.
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
}
|
||||
else {
|
||||
// If not using TX interrupts, we must send the XON char now
|
||||
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
|
||||
while (!(HWUART->UART_SR & UART_SR_TXRDY)) sw_barrier();
|
||||
HWUART->UART_THR = XON_CHAR;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return v;
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::available() {
|
||||
const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail;
|
||||
return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::flush() {
|
||||
rx_buffer.tail = rx_buffer.head;
|
||||
|
||||
if (Cfg::XONOFF) {
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
|
||||
if (Cfg::TX_SIZE > 0) {
|
||||
// Signal we want an XON character to be sent.
|
||||
xon_xoff_state = XON_CHAR;
|
||||
// Enable TX isr.
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
}
|
||||
else {
|
||||
// If not using TX interrupts, we must send the XON char now
|
||||
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
|
||||
while (!(HWUART->UART_SR & UART_SR_TXRDY)) sw_barrier();
|
||||
HWUART->UART_THR = XON_CHAR;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::write(const uint8_t c) {
|
||||
_written = true;
|
||||
|
||||
if (Cfg::TX_SIZE == 0) {
|
||||
while (!(HWUART->UART_SR & UART_SR_TXRDY)) sw_barrier();
|
||||
HWUART->UART_THR = c;
|
||||
}
|
||||
else {
|
||||
|
||||
// If the TX interrupts are disabled and the data register
|
||||
// is empty, just write the byte to the data register and
|
||||
// be done. This shortcut helps significantly improve the
|
||||
// effective datarate at high (>500kbit/s) bitrates, where
|
||||
// interrupt overhead becomes a slowdown.
|
||||
// Yes, there is a race condition between the sending of the
|
||||
// XOFF char at the RX isr, but it is properly handled there
|
||||
if (!(HWUART->UART_IMR & UART_IMR_TXRDY) && (HWUART->UART_SR & UART_SR_TXRDY)) {
|
||||
HWUART->UART_THR = c;
|
||||
return;
|
||||
}
|
||||
|
||||
const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
|
||||
|
||||
// If global interrupts are disabled (as the result of being called from an ISR)...
|
||||
if (!ISRS_ENABLED()) {
|
||||
|
||||
// Make room by polling if it is possible to transmit, and do so!
|
||||
while (i == tx_buffer.tail) {
|
||||
// If we can transmit another byte, do it.
|
||||
if (HWUART->UART_SR & UART_SR_TXRDY) _tx_thr_empty_irq();
|
||||
// Make sure compiler rereads tx_buffer.tail
|
||||
sw_barrier();
|
||||
}
|
||||
}
|
||||
else {
|
||||
// Interrupts are enabled, just wait until there is space
|
||||
while (i == tx_buffer.tail) sw_barrier();
|
||||
}
|
||||
|
||||
// Store new char. head is always safe to move
|
||||
tx_buffer.buffer[tx_buffer.head] = c;
|
||||
tx_buffer.head = i;
|
||||
|
||||
// Enable TX isr - Non atomic, but it will eventually enable TX isr
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
}
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::flushTX() {
|
||||
// TX
|
||||
|
||||
if (Cfg::TX_SIZE == 0) {
|
||||
// No bytes written, no need to flush. This special case is needed since there's
|
||||
// no way to force the TXC (transmit complete) bit to 1 during initialization.
|
||||
if (!_written) return;
|
||||
|
||||
// Wait until everything was transmitted
|
||||
while (!(HWUART->UART_SR & UART_SR_TXEMPTY)) sw_barrier();
|
||||
|
||||
// At this point nothing is queued anymore (DRIE is disabled) and
|
||||
// the hardware finished transmission (TXC is set).
|
||||
|
||||
}
|
||||
else {
|
||||
// If we have never written a byte, no need to flush. This special
|
||||
// case is needed since there is no way to force the TXC (transmit
|
||||
// complete) bit to 1 during initialization
|
||||
if (!_written) return;
|
||||
|
||||
// If global interrupts are disabled (as the result of being called from an ISR)...
|
||||
if (!ISRS_ENABLED()) {
|
||||
|
||||
// Wait until everything was transmitted - We must do polling, as interrupts are disabled
|
||||
while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {
|
||||
// If there is more space, send an extra character
|
||||
if (HWUART->UART_SR & UART_SR_TXRDY) _tx_thr_empty_irq();
|
||||
sw_barrier();
|
||||
}
|
||||
|
||||
}
|
||||
else {
|
||||
// Wait until everything was transmitted
|
||||
while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) sw_barrier();
|
||||
}
|
||||
|
||||
// At this point nothing is queued anymore (DRIE is disabled) and
|
||||
// the hardware finished transmission (TXC is set).
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Imports from print.h
|
||||
*/
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(char c, int base) {
|
||||
print((long)c, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(unsigned char b, int base) {
|
||||
print((unsigned long)b, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(int n, int base) {
|
||||
print((long)n, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(unsigned int n, int base) {
|
||||
print((unsigned long)n, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(long n, int base) {
|
||||
if (base == 0) write(n);
|
||||
else if (base == 10) {
|
||||
if (n < 0) { print('-'); n = -n; }
|
||||
printNumber(n, 10);
|
||||
}
|
||||
else
|
||||
printNumber(n, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(unsigned long n, int base) {
|
||||
if (base == 0) write(n);
|
||||
else printNumber(n, base);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::print(double n, int digits) {
|
||||
printFloat(n, digits);
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println() {
|
||||
print('\r');
|
||||
print('\n');
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(const String& s) {
|
||||
print(s);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(const char c[]) {
|
||||
print(c);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(char c, int base) {
|
||||
print(c, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(unsigned char b, int base) {
|
||||
print(b, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(unsigned int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(unsigned long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::println(double n, int digits) {
|
||||
print(n, digits);
|
||||
println();
|
||||
}
|
||||
|
||||
// Private Methods
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::printNumber(unsigned long n, uint8_t base) {
|
||||
if (n) {
|
||||
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
|
||||
int8_t i = 0;
|
||||
while (n) {
|
||||
buf[i++] = n % base;
|
||||
n /= base;
|
||||
}
|
||||
while (i--)
|
||||
print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
|
||||
}
|
||||
else
|
||||
print('0');
|
||||
}
|
||||
|
||||
template<typename Cfg>
|
||||
void MarlinSerial<Cfg>::printFloat(double number, uint8_t digits) {
|
||||
// Handle negative numbers
|
||||
if (number < 0.0) {
|
||||
print('-');
|
||||
number = -number;
|
||||
}
|
||||
|
||||
// Round correctly so that print(1.999, 2) prints as "2.00"
|
||||
double rounding = 0.5;
|
||||
for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1;
|
||||
number += rounding;
|
||||
|
||||
// Extract the integer part of the number and print it
|
||||
unsigned long int_part = (unsigned long)number;
|
||||
double remainder = number - (double)int_part;
|
||||
print(int_part);
|
||||
|
||||
// Print the decimal point, but only if there are digits beyond
|
||||
if (digits) {
|
||||
print('.');
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits--) {
|
||||
remainder *= 10.0;
|
||||
int toPrint = int(remainder);
|
||||
print(toPrint);
|
||||
remainder -= toPrint;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// If not using the USB port as serial port
|
||||
#if SERIAL_PORT >= 0
|
||||
|
||||
// Preinstantiate
|
||||
template class MarlinSerial<MarlinSerialCfg<SERIAL_PORT>>;
|
||||
|
||||
// Instantiate
|
||||
MarlinSerial<MarlinSerialCfg<SERIAL_PORT>> customizedSerial1;
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
|
||||
// Preinstantiate
|
||||
template class MarlinSerial<MarlinSerialCfg<SERIAL_PORT_2>>;
|
||||
|
||||
// Instantiate
|
||||
MarlinSerial<MarlinSerialCfg<SERIAL_PORT_2>> customizedSerial2;
|
||||
|
||||
#endif
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
184
Marlin/src/HAL/DUE/MarlinSerial.h
Normal file
184
Marlin/src/HAL/DUE/MarlinSerial.h
Normal file
@ -0,0 +1,184 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* MarlinSerial_Due.h - Hardware serial library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*/
|
||||
|
||||
#include <WString.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
|
||||
// Define constants and variables for buffering incoming serial data. We're
|
||||
// using a ring buffer (I think), in which rx_buffer_head is the index of the
|
||||
// location to which to write the next incoming character and rx_buffer_tail
|
||||
// is the index of the location from which to read.
|
||||
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#define TX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
//#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
|
||||
// #error "SERIAL_XON_XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
|
||||
//#elif RX_BUFFER_SIZE && (RX_BUFFER_SIZE < 2 || !IS_POWER_OF_2(RX_BUFFER_SIZE))
|
||||
// #error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
|
||||
//#elif TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
|
||||
// #error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256."
|
||||
//#endif
|
||||
|
||||
// Templated type selector
|
||||
template<bool b, typename T, typename F> struct TypeSelector { typedef T type;} ;
|
||||
template<typename T, typename F> struct TypeSelector<false, T, F> { typedef F type; };
|
||||
|
||||
// Templated structure wrapper
|
||||
template<typename S, unsigned int addr> struct StructWrapper {
|
||||
constexpr StructWrapper(int) {}
|
||||
FORCE_INLINE S* operator->() const { return (S*)addr; }
|
||||
};
|
||||
|
||||
template<typename Cfg>
|
||||
class MarlinSerial {
|
||||
protected:
|
||||
// Information for all supported UARTs
|
||||
static constexpr uint32_t BASES[] = {0x400E0800U, 0x40098000U, 0x4009C000U, 0x400A0000U, 0x400A4000U};
|
||||
static constexpr IRQn_Type IRQS[] = { UART_IRQn, USART0_IRQn, USART1_IRQn, USART2_IRQn, USART3_IRQn};
|
||||
static constexpr int IRQ_IDS[] = { ID_UART, ID_USART0, ID_USART1, ID_USART2, ID_USART3};
|
||||
|
||||
// Alias for shorter code
|
||||
static constexpr StructWrapper<Uart,BASES[Cfg::PORT]> HWUART = 0;
|
||||
static constexpr IRQn_Type HWUART_IRQ = IRQS[Cfg::PORT];
|
||||
static constexpr int HWUART_IRQ_ID = IRQ_IDS[Cfg::PORT];
|
||||
|
||||
// Base size of type on buffer size
|
||||
typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t;
|
||||
|
||||
struct ring_buffer_r {
|
||||
volatile ring_buffer_pos_t head, tail;
|
||||
unsigned char buffer[Cfg::RX_SIZE];
|
||||
};
|
||||
|
||||
struct ring_buffer_t {
|
||||
volatile uint8_t head, tail;
|
||||
unsigned char buffer[Cfg::TX_SIZE];
|
||||
};
|
||||
|
||||
static ring_buffer_r rx_buffer;
|
||||
static ring_buffer_t tx_buffer;
|
||||
static bool _written;
|
||||
|
||||
static constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80, // XON / XOFF Character was sent
|
||||
XON_XOFF_CHAR_MASK = 0x1F; // XON / XOFF character to send
|
||||
|
||||
// XON / XOFF character definitions
|
||||
static constexpr uint8_t XON_CHAR = 17, XOFF_CHAR = 19;
|
||||
static uint8_t xon_xoff_state,
|
||||
rx_dropped_bytes,
|
||||
rx_buffer_overruns,
|
||||
rx_framing_errors;
|
||||
static ring_buffer_pos_t rx_max_enqueued;
|
||||
|
||||
FORCE_INLINE static void store_rxd_char();
|
||||
FORCE_INLINE static void _tx_thr_empty_irq();
|
||||
static void UART_ISR();
|
||||
|
||||
public:
|
||||
MarlinSerial() {};
|
||||
static void begin(const long);
|
||||
static void end();
|
||||
static int peek();
|
||||
static int read();
|
||||
static void flush();
|
||||
static ring_buffer_pos_t available();
|
||||
static void write(const uint8_t c);
|
||||
static void flushTX();
|
||||
|
||||
FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; }
|
||||
FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
|
||||
FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
|
||||
FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; }
|
||||
|
||||
FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
|
||||
FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
||||
FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
|
||||
FORCE_INLINE static void print(const char* str) { write(str); }
|
||||
|
||||
static void print(char, int = 0);
|
||||
static void print(unsigned char, int = 0);
|
||||
static void print(int, int = DEC);
|
||||
static void print(unsigned int, int = DEC);
|
||||
static void print(long, int = DEC);
|
||||
static void print(unsigned long, int = DEC);
|
||||
static void print(double, int = 2);
|
||||
|
||||
static void println(const String& s);
|
||||
static void println(const char[]);
|
||||
static void println(char, int = 0);
|
||||
static void println(unsigned char, int = 0);
|
||||
static void println(int, int = DEC);
|
||||
static void println(unsigned int, int = DEC);
|
||||
static void println(long, int = DEC);
|
||||
static void println(unsigned long, int = DEC);
|
||||
static void println(double, int = 2);
|
||||
static void println();
|
||||
operator bool() { return true; }
|
||||
|
||||
private:
|
||||
static void printNumber(unsigned long, const uint8_t);
|
||||
static void printFloat(double, uint8_t);
|
||||
};
|
||||
|
||||
// Serial port configuration
|
||||
template <uint8_t serial>
|
||||
struct MarlinSerialCfg {
|
||||
static constexpr int PORT = serial;
|
||||
static constexpr unsigned int RX_SIZE = RX_BUFFER_SIZE;
|
||||
static constexpr unsigned int TX_SIZE = TX_BUFFER_SIZE;
|
||||
static constexpr bool XONOFF = ENABLED(SERIAL_XON_XOFF);
|
||||
static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER);
|
||||
static constexpr bool DROPPED_RX = ENABLED(SERIAL_STATS_DROPPED_RX);
|
||||
static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS);
|
||||
static constexpr bool RX_FRAMING_ERRORS = ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS);
|
||||
static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED);
|
||||
};
|
||||
|
||||
#if SERIAL_PORT >= 0
|
||||
|
||||
extern MarlinSerial<MarlinSerialCfg<SERIAL_PORT>> customizedSerial1;
|
||||
|
||||
#endif // SERIAL_PORT >= 0
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
|
||||
extern MarlinSerial<MarlinSerialCfg<SERIAL_PORT_2>> customizedSerial2;
|
||||
|
||||
#endif
|
290
Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
Normal file
290
Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
Normal file
@ -0,0 +1,290 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
|
||||
#include "MarlinSerialUSB.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/e_parser.h"
|
||||
#endif
|
||||
|
||||
// Imports from Atmel USB Stack/CDC implementation
|
||||
extern "C" {
|
||||
bool usb_task_cdc_isenabled();
|
||||
bool usb_task_cdc_dtr_active();
|
||||
bool udi_cdc_is_rx_ready();
|
||||
int udi_cdc_getc();
|
||||
bool udi_cdc_is_tx_ready();
|
||||
int udi_cdc_putc(int value);
|
||||
};
|
||||
|
||||
// Pending character
|
||||
static int pending_char = -1;
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
static EmergencyParser::State emergency_state; // = EP_RESET
|
||||
#endif
|
||||
|
||||
// Public Methods
|
||||
void MarlinSerialUSB::begin(const long) {}
|
||||
|
||||
void MarlinSerialUSB::end() {}
|
||||
|
||||
int MarlinSerialUSB::peek() {
|
||||
if (pending_char >= 0)
|
||||
return pending_char;
|
||||
|
||||
// If USB CDC not enumerated or not configured on the PC side
|
||||
if (!usb_task_cdc_isenabled())
|
||||
return -1;
|
||||
|
||||
// If no bytes sent from the PC
|
||||
if (!udi_cdc_is_rx_ready())
|
||||
return -1;
|
||||
|
||||
pending_char = udi_cdc_getc();
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
emergency_parser.update(emergency_state, (char)pending_char);
|
||||
#endif
|
||||
|
||||
return pending_char;
|
||||
}
|
||||
|
||||
int MarlinSerialUSB::read() {
|
||||
if (pending_char >= 0) {
|
||||
int ret = pending_char;
|
||||
pending_char = -1;
|
||||
return ret;
|
||||
}
|
||||
|
||||
// If USB CDC not enumerated or not configured on the PC side
|
||||
if (!usb_task_cdc_isenabled())
|
||||
return -1;
|
||||
|
||||
// If no bytes sent from the PC
|
||||
if (!udi_cdc_is_rx_ready())
|
||||
return -1;
|
||||
|
||||
int c = udi_cdc_getc();
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
emergency_parser.update(emergency_state, (char)c);
|
||||
#endif
|
||||
|
||||
return c;
|
||||
}
|
||||
|
||||
bool MarlinSerialUSB::available() {
|
||||
/* If Pending chars */
|
||||
return pending_char >= 0 ||
|
||||
/* or USB CDC enumerated and configured on the PC side and some
|
||||
bytes where sent to us */
|
||||
(usb_task_cdc_isenabled() && udi_cdc_is_rx_ready());
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::flush() { }
|
||||
void MarlinSerialUSB::flushTX() { }
|
||||
|
||||
void MarlinSerialUSB::write(const uint8_t c) {
|
||||
|
||||
/* Do not even bother sending anything if USB CDC is not enumerated
|
||||
or not configured on the PC side or there is no program on the PC
|
||||
listening to our messages */
|
||||
if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active())
|
||||
return;
|
||||
|
||||
/* Wait until the PC has read the pending to be sent data */
|
||||
while (usb_task_cdc_isenabled() &&
|
||||
usb_task_cdc_dtr_active() &&
|
||||
!udi_cdc_is_tx_ready()) {
|
||||
};
|
||||
|
||||
/* Do not even bother sending anything if USB CDC is not enumerated
|
||||
or not configured on the PC side or there is no program on the PC
|
||||
listening to our messages at this point */
|
||||
if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active())
|
||||
return;
|
||||
|
||||
// Fifo full
|
||||
// udi_cdc_signal_overrun();
|
||||
udi_cdc_putc(c);
|
||||
}
|
||||
|
||||
/**
|
||||
* Imports from print.h
|
||||
*/
|
||||
|
||||
void MarlinSerialUSB::print(char c, int base) {
|
||||
print((long)c, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(unsigned char b, int base) {
|
||||
print((unsigned long)b, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(int n, int base) {
|
||||
print((long)n, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(unsigned int n, int base) {
|
||||
print((unsigned long)n, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(long n, int base) {
|
||||
if (base == 0)
|
||||
write(n);
|
||||
else if (base == 10) {
|
||||
if (n < 0) {
|
||||
print('-');
|
||||
n = -n;
|
||||
}
|
||||
printNumber(n, 10);
|
||||
}
|
||||
else
|
||||
printNumber(n, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(unsigned long n, int base) {
|
||||
if (base == 0) write(n);
|
||||
else printNumber(n, base);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::print(double n, int digits) {
|
||||
printFloat(n, digits);
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println() {
|
||||
print('\r');
|
||||
print('\n');
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(const String& s) {
|
||||
print(s);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(const char c[]) {
|
||||
print(c);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(char c, int base) {
|
||||
print(c, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(unsigned char b, int base) {
|
||||
print(b, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(unsigned int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(unsigned long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::println(double n, int digits) {
|
||||
print(n, digits);
|
||||
println();
|
||||
}
|
||||
|
||||
// Private Methods
|
||||
|
||||
void MarlinSerialUSB::printNumber(unsigned long n, uint8_t base) {
|
||||
if (n) {
|
||||
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
|
||||
int8_t i = 0;
|
||||
while (n) {
|
||||
buf[i++] = n % base;
|
||||
n /= base;
|
||||
}
|
||||
while (i--)
|
||||
print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
|
||||
}
|
||||
else
|
||||
print('0');
|
||||
}
|
||||
|
||||
void MarlinSerialUSB::printFloat(double number, uint8_t digits) {
|
||||
// Handle negative numbers
|
||||
if (number < 0.0) {
|
||||
print('-');
|
||||
number = -number;
|
||||
}
|
||||
|
||||
// Round correctly so that print(1.999, 2) prints as "2.00"
|
||||
double rounding = 0.5;
|
||||
for (uint8_t i = 0; i < digits; ++i)
|
||||
rounding *= 0.1;
|
||||
|
||||
number += rounding;
|
||||
|
||||
// Extract the integer part of the number and print it
|
||||
unsigned long int_part = (unsigned long)number;
|
||||
double remainder = number - (double)int_part;
|
||||
print(int_part);
|
||||
|
||||
// Print the decimal point, but only if there are digits beyond
|
||||
if (digits) {
|
||||
print('.');
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits--) {
|
||||
remainder *= 10.0;
|
||||
int toPrint = int(remainder);
|
||||
print(toPrint);
|
||||
remainder -= toPrint;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Preinstantiate
|
||||
MarlinSerialUSB customizedSerial1;
|
||||
|
||||
#endif // SERIAL_PORT == -1
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
93
Marlin/src/HAL/DUE/MarlinSerialUSB.h
Normal file
93
Marlin/src/HAL/DUE/MarlinSerialUSB.h
Normal file
@ -0,0 +1,93 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* MarlinSerialUSB_Due.h - Hardware Serial over USB (CDC) library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
|
||||
#include <WString.h>
|
||||
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
|
||||
class MarlinSerialUSB {
|
||||
|
||||
public:
|
||||
MarlinSerialUSB() {};
|
||||
static void begin(const long);
|
||||
static void end();
|
||||
static int peek();
|
||||
static int read();
|
||||
static void flush();
|
||||
static void flushTX();
|
||||
static bool available();
|
||||
static void write(const uint8_t c);
|
||||
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
FORCE_INLINE static uint32_t dropped() { return 0; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
FORCE_INLINE static int rxMaxEnqueued() { return 0; }
|
||||
#endif
|
||||
|
||||
FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
|
||||
FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
||||
FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
|
||||
FORCE_INLINE static void print(const char* str) { write(str); }
|
||||
|
||||
static void print(char, int = 0);
|
||||
static void print(unsigned char, int = 0);
|
||||
static void print(int, int = DEC);
|
||||
static void print(unsigned int, int = DEC);
|
||||
static void print(long, int = DEC);
|
||||
static void print(unsigned long, int = DEC);
|
||||
static void print(double, int = 2);
|
||||
|
||||
static void println(const String& s);
|
||||
static void println(const char[]);
|
||||
static void println(char, int = 0);
|
||||
static void println(unsigned char, int = 0);
|
||||
static void println(int, int = DEC);
|
||||
static void println(unsigned int, int = DEC);
|
||||
static void println(long, int = DEC);
|
||||
static void println(unsigned long, int = DEC);
|
||||
static void println(double, int = 2);
|
||||
static void println();
|
||||
operator bool() { return true; }
|
||||
|
||||
private:
|
||||
static void printNumber(unsigned long, const uint8_t);
|
||||
static void printFloat(double, uint8_t);
|
||||
};
|
||||
|
||||
extern MarlinSerialUSB customizedSerial1;
|
||||
|
||||
#endif // SERIAL_PORT == -1
|
160
Marlin/src/HAL/DUE/Servo.cpp
Normal file
160
Marlin/src/HAL/DUE/Servo.cpp
Normal file
@ -0,0 +1,160 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
Copyright (c) 2013 Arduino LLC. 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 ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
#include "../shared/servo.h"
|
||||
#include "../shared/servo_private.h"
|
||||
|
||||
static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
|
||||
|
||||
// ------------------------
|
||||
/// Interrupt handler for the TC0 channel 1.
|
||||
// ------------------------
|
||||
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
|
||||
|
||||
#ifdef _useTimer1
|
||||
void HANDLER_FOR_TIMER1() { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); }
|
||||
#endif
|
||||
#ifdef _useTimer2
|
||||
void HANDLER_FOR_TIMER2() { Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); }
|
||||
#endif
|
||||
#ifdef _useTimer3
|
||||
void HANDLER_FOR_TIMER3() { Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); }
|
||||
#endif
|
||||
#ifdef _useTimer4
|
||||
void HANDLER_FOR_TIMER4() { Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); }
|
||||
#endif
|
||||
#ifdef _useTimer5
|
||||
void HANDLER_FOR_TIMER5() { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); }
|
||||
#endif
|
||||
|
||||
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {
|
||||
// clear interrupt
|
||||
tc->TC_CHANNEL[channel].TC_SR;
|
||||
if (Channel[timer] < 0)
|
||||
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
|
||||
else if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
|
||||
|
||||
Channel[timer]++; // increment to the next channel
|
||||
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
|
||||
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
|
||||
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
|
||||
}
|
||||
else {
|
||||
// finished all channels so wait for the refresh period to expire before starting over
|
||||
tc->TC_CHANNEL[channel].TC_RA =
|
||||
tc->TC_CHANNEL[channel].TC_CV < usToTicks(REFRESH_INTERVAL) - 4
|
||||
? (unsigned int)usToTicks(REFRESH_INTERVAL) // allow a few ticks to ensure the next OCR1A not missed
|
||||
: tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed
|
||||
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
|
||||
}
|
||||
}
|
||||
|
||||
static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn) {
|
||||
pmc_enable_periph_clk(id);
|
||||
TC_Configure(tc, channel,
|
||||
TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
|
||||
TC_CMR_WAVE | // Waveform mode
|
||||
TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC
|
||||
|
||||
/* 84MHz, MCK/32, for 1.5ms: 3937 */
|
||||
TC_SetRA(tc, channel, 2625); // 1ms
|
||||
|
||||
/* Configure and enable interrupt */
|
||||
NVIC_EnableIRQ(irqn);
|
||||
// TC_IER_CPAS: RA Compare
|
||||
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS;
|
||||
|
||||
// Enables the timer clock and performs a software reset to start the counting
|
||||
TC_Start(tc, channel);
|
||||
}
|
||||
|
||||
void initISR(timer16_Sequence_t timer) {
|
||||
#ifdef _useTimer1
|
||||
if (timer == _timer1)
|
||||
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
|
||||
#endif
|
||||
#ifdef _useTimer2
|
||||
if (timer == _timer2)
|
||||
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
|
||||
#endif
|
||||
#ifdef _useTimer3
|
||||
if (timer == _timer3)
|
||||
_initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
|
||||
#endif
|
||||
#ifdef _useTimer4
|
||||
if (timer == _timer4)
|
||||
_initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
|
||||
#endif
|
||||
#ifdef _useTimer5
|
||||
if (timer == _timer5)
|
||||
_initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
|
||||
#endif
|
||||
}
|
||||
|
||||
void finISR(timer16_Sequence_t) {
|
||||
#ifdef _useTimer1
|
||||
TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
|
||||
#endif
|
||||
#ifdef _useTimer2
|
||||
TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
|
||||
#endif
|
||||
#ifdef _useTimer3
|
||||
TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
|
||||
#endif
|
||||
#ifdef _useTimer4
|
||||
TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
|
||||
#endif
|
||||
#ifdef _useTimer5
|
||||
TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAS_SERVOS
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
107
Marlin/src/HAL/DUE/ServoTimers.h
Normal file
107
Marlin/src/HAL/DUE/ServoTimers.h
Normal file
@ -0,0 +1,107 @@
|
||||
/**
|
||||
* Copyright (c) 2013 Arduino LLC. 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
|
||||
*/
|
||||
|
||||
/**
|
||||
* Defines for 16 bit timers used with Servo library
|
||||
*
|
||||
* If _useTimerX is defined then TimerX is a 32 bit timer on the current board
|
||||
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
|
||||
* _Nbr_16timers indicates how many timers are available.
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAM Only definitions
|
||||
* --------------------
|
||||
*/
|
||||
|
||||
// For SAM3X:
|
||||
//!#define _useTimer1
|
||||
//!#define _useTimer2
|
||||
#define _useTimer3
|
||||
//!#define _useTimer4
|
||||
#define _useTimer5
|
||||
|
||||
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
|
||||
#define SERVO_TIMER_PRESCALER 32 // timer prescaler
|
||||
|
||||
/*
|
||||
TC0, chan 0 => TC0_Handler
|
||||
TC0, chan 1 => TC1_Handler
|
||||
TC0, chan 2 => TC2_Handler
|
||||
TC1, chan 0 => TC3_Handler
|
||||
TC1, chan 1 => TC4_Handler
|
||||
TC1, chan 2 => TC5_Handler
|
||||
TC2, chan 0 => TC6_Handler
|
||||
TC2, chan 1 => TC7_Handler
|
||||
TC2, chan 2 => TC8_Handler
|
||||
*/
|
||||
|
||||
#ifdef _useTimer1
|
||||
#define TC_FOR_TIMER1 TC1
|
||||
#define CHANNEL_FOR_TIMER1 0
|
||||
#define ID_TC_FOR_TIMER1 ID_TC3
|
||||
#define IRQn_FOR_TIMER1 TC3_IRQn
|
||||
#define HANDLER_FOR_TIMER1 TC3_Handler
|
||||
#endif
|
||||
#ifdef _useTimer2
|
||||
#define TC_FOR_TIMER2 TC1
|
||||
#define CHANNEL_FOR_TIMER2 1
|
||||
#define ID_TC_FOR_TIMER2 ID_TC4
|
||||
#define IRQn_FOR_TIMER2 TC4_IRQn
|
||||
#define HANDLER_FOR_TIMER2 TC4_Handler
|
||||
#endif
|
||||
#ifdef _useTimer3
|
||||
#define TC_FOR_TIMER3 TC1
|
||||
#define CHANNEL_FOR_TIMER3 2
|
||||
#define ID_TC_FOR_TIMER3 ID_TC5
|
||||
#define IRQn_FOR_TIMER3 TC5_IRQn
|
||||
#define HANDLER_FOR_TIMER3 TC5_Handler
|
||||
#endif
|
||||
#ifdef _useTimer4
|
||||
#define TC_FOR_TIMER4 TC0
|
||||
#define CHANNEL_FOR_TIMER4 2
|
||||
#define ID_TC_FOR_TIMER4 ID_TC2
|
||||
#define IRQn_FOR_TIMER4 TC2_IRQn
|
||||
#define HANDLER_FOR_TIMER4 TC2_Handler
|
||||
#endif
|
||||
#ifdef _useTimer5
|
||||
#define TC_FOR_TIMER5 TC0
|
||||
#define CHANNEL_FOR_TIMER5 0
|
||||
#define ID_TC_FOR_TIMER5 ID_TC0
|
||||
#define IRQn_FOR_TIMER5 TC0_IRQn
|
||||
#define HANDLER_FOR_TIMER5 TC0_Handler
|
||||
#endif
|
||||
|
||||
typedef enum : unsigned char {
|
||||
#ifdef _useTimer1
|
||||
_timer1,
|
||||
#endif
|
||||
#ifdef _useTimer2
|
||||
_timer2,
|
||||
#endif
|
||||
#ifdef _useTimer3
|
||||
_timer3,
|
||||
#endif
|
||||
#ifdef _useTimer4
|
||||
_timer4,
|
||||
#endif
|
||||
#ifdef _useTimer5
|
||||
_timer5,
|
||||
#endif
|
||||
_Nbr_16timers
|
||||
} timer16_Sequence_t;
|
61
Marlin/src/HAL/DUE/Tone.cpp
Normal file
61
Marlin/src/HAL/DUE/Tone.cpp
Normal file
@ -0,0 +1,61 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: Tone function for Arduino Due and compatible (SAM3X8E)
|
||||
* Derived from http://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
#include "timers.h"
|
||||
|
||||
static pin_t tone_pin;
|
||||
volatile static int32_t toggles;
|
||||
|
||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
|
||||
tone_pin = _pin;
|
||||
toggles = 2 * frequency * duration / 1000;
|
||||
HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
|
||||
}
|
||||
|
||||
void noTone(const pin_t _pin) {
|
||||
HAL_timer_disable_interrupt(TONE_TIMER_NUM);
|
||||
extDigitalWrite(_pin, LOW);
|
||||
}
|
||||
|
||||
HAL_TONE_TIMER_ISR() {
|
||||
static uint8_t pin_state = 0;
|
||||
HAL_timer_isr_prologue(TONE_TIMER_NUM);
|
||||
|
||||
if (toggles) {
|
||||
toggles--;
|
||||
extDigitalWrite(tone_pin, (pin_state ^= 1));
|
||||
}
|
||||
else noTone(tone_pin); // turn off interrupt
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
150
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
Normal file
150
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
Normal file
@ -0,0 +1,150 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 u8g_com_msp430_hw_spi.c
|
||||
*
|
||||
* Universal 8bit Graphics Library
|
||||
*
|
||||
* Copyright (c) 2012, olikraus@gmail.com
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* * Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or other
|
||||
* materials provided with the distribution.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
|
||||
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
|
||||
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef __SAM3X8E__
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
|
||||
#include <U8glib.h>
|
||||
|
||||
#include "../../../MarlinCore.h"
|
||||
|
||||
void spiBegin();
|
||||
void spiInit(uint8_t spiRate);
|
||||
void spiSend(uint8_t b);
|
||||
void spiSend(const uint8_t* buf, size_t n);
|
||||
|
||||
#include "../../shared/Marduino.h"
|
||||
#include "../fastio.h"
|
||||
|
||||
void u8g_SetPIOutput_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index) {
|
||||
PIO_Configure(g_APinDescription[u8g->pin_list[pin_index]].pPort, PIO_OUTPUT_1,
|
||||
g_APinDescription[u8g->pin_list[pin_index]].ulPin, g_APinDescription[u8g->pin_list[pin_index]].ulPinConfiguration); // OUTPUT
|
||||
}
|
||||
|
||||
void u8g_SetPILevel_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index, uint8_t level) {
|
||||
volatile Pio* port = g_APinDescription[u8g->pin_list[pin_index]].pPort;
|
||||
uint32_t mask = g_APinDescription[u8g->pin_list[pin_index]].ulPin;
|
||||
if (level) port->PIO_SODR = mask;
|
||||
else port->PIO_CODR = mask;
|
||||
}
|
||||
|
||||
uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_STOP:
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_INIT:
|
||||
u8g_SetPILevel_DUE_hw_spi(u8g, U8G_PI_CS, 1);
|
||||
u8g_SetPILevel_DUE_hw_spi(u8g, U8G_PI_A0, 1);
|
||||
|
||||
u8g_SetPIOutput_DUE_hw_spi(u8g, U8G_PI_CS);
|
||||
u8g_SetPIOutput_DUE_hw_spi(u8g, U8G_PI_A0);
|
||||
|
||||
u8g_Delay(5);
|
||||
|
||||
spiBegin();
|
||||
|
||||
#ifndef SPI_SPEED
|
||||
#define SPI_SPEED SPI_FULL_SPEED // use same SPI speed as SD card
|
||||
#endif
|
||||
spiInit(2);
|
||||
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
|
||||
u8g_SetPILevel_DUE_hw_spi(u8g, U8G_PI_A0, arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_CHIP_SELECT:
|
||||
u8g_SetPILevel_DUE_hw_spi(u8g, U8G_PI_CS, (arg_val ? 0 : 1));
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_RESET:
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
|
||||
spiSend((uint8_t)arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ: {
|
||||
uint8_t *ptr = (uint8_t*) arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
spiSend(*ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ_P: {
|
||||
uint8_t *ptr = (uint8_t*) arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
spiSend(*ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // HAS_GRAPHICAL_LCD
|
||||
|
||||
#endif //__SAM3X8E__
|
185
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
Normal file
185
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
Normal file
@ -0,0 +1,185 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 u8g_com_st7920_hw_spi.c
|
||||
*
|
||||
* Universal 8bit Graphics Library
|
||||
*
|
||||
* Copyright (c) 2011, olikraus@gmail.com
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* * Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or other
|
||||
* materials provided with the distribution.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
|
||||
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
|
||||
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(U8GLIB_ST7920)
|
||||
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#include <U8glib.h>
|
||||
|
||||
#include "u8g_com_HAL_DUE_sw_spi_shared.h"
|
||||
|
||||
#define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_0
|
||||
|
||||
static uint8_t rs_last_state = 255;
|
||||
|
||||
static void u8g_com_DUE_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) {
|
||||
if (rs != rs_last_state) { // time to send a command/data byte
|
||||
rs_last_state = rs;
|
||||
SPISEND_SW_DUE(rs ? 0x0FA : 0x0F8); // Command or Data
|
||||
DELAY_US(40); // give the controller some time to process the data: 20 is bad, 30 is OK, 40 is safe
|
||||
}
|
||||
SPISEND_SW_DUE(val & 0xF0);
|
||||
SPISEND_SW_DUE(val << 4);
|
||||
}
|
||||
|
||||
uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_INIT:
|
||||
SCK_pPio = g_APinDescription[u8g->pin_list[U8G_PI_SCK]].pPort;
|
||||
SCK_dwMask = g_APinDescription[u8g->pin_list[U8G_PI_SCK]].ulPin;
|
||||
MOSI_pPio = g_APinDescription[u8g->pin_list[U8G_PI_MOSI]].pPort;
|
||||
MOSI_dwMask = g_APinDescription[u8g->pin_list[U8G_PI_MOSI]].ulPin;
|
||||
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_CS, 0);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_CS);
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 0);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_SCK);
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_MOSI, 0);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_MOSI);
|
||||
|
||||
SCK_pPio->PIO_CODR = SCK_dwMask; //SCK low - needed at power up but not after reset
|
||||
MOSI_pPio->PIO_CODR = MOSI_dwMask; //MOSI low - needed at power up but not after reset
|
||||
|
||||
u8g_Delay(5);
|
||||
|
||||
u8g->pin_list[U8G_PI_A0_STATE] = 0; /* initial RS state: command mode */
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_STOP:
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_RESET:
|
||||
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel_DUE(u8g, U8G_PI_RESET, arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
|
||||
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_CHIP_SELECT:
|
||||
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS])
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
|
||||
u8g_com_DUE_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ: {
|
||||
uint8_t *ptr = (uint8_t*) arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
u8g_com_DUE_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ_P: {
|
||||
uint8_t *ptr = (uint8_t*) arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
u8g_com_DUE_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#if ENABLED(LIGHTWEIGHT_UI)
|
||||
#include "../../../lcd/ultralcd.h"
|
||||
#include "../../shared/HAL_ST7920.h"
|
||||
|
||||
#define ST7920_CS_PIN LCD_PINS_RS
|
||||
|
||||
#if DOGM_SPI_DELAY_US > 0
|
||||
#define U8G_DELAY() DELAY_US(DOGM_SPI_DELAY_US)
|
||||
#else
|
||||
#define U8G_DELAY() DELAY_US(10)
|
||||
#endif
|
||||
|
||||
void ST7920_cs() {
|
||||
WRITE(ST7920_CS_PIN, HIGH);
|
||||
U8G_DELAY();
|
||||
}
|
||||
|
||||
void ST7920_ncs() {
|
||||
WRITE(ST7920_CS_PIN, LOW);
|
||||
}
|
||||
|
||||
void ST7920_set_cmd() {
|
||||
SPISEND_SW_DUE(0xF8);
|
||||
DELAY_US(40);
|
||||
}
|
||||
|
||||
void ST7920_set_dat() {
|
||||
SPISEND_SW_DUE(0xFA);
|
||||
DELAY_US(40);
|
||||
}
|
||||
|
||||
void ST7920_write_byte(const uint8_t val) {
|
||||
SPISEND_SW_DUE(val & 0xF0);
|
||||
SPISEND_SW_DUE(val << 4);
|
||||
}
|
||||
#endif // LIGHTWEIGHT_UI
|
||||
|
||||
#endif // U8GLIB_ST7920
|
||||
#endif // ARDUINO_ARCH_SAM
|
148
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp
Normal file
148
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp
Normal file
@ -0,0 +1,148 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 u8g_com_std_sw_spi.c
|
||||
*
|
||||
* Universal 8bit Graphics Library
|
||||
*
|
||||
* Copyright (c) 2015, olikraus@gmail.com
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* * Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or other
|
||||
* materials provided with the distribution.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
|
||||
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
|
||||
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920)
|
||||
|
||||
#undef SPI_SPEED
|
||||
#define SPI_SPEED 2 // About 2 MHz
|
||||
|
||||
#include "u8g_com_HAL_DUE_sw_spi_shared.h"
|
||||
|
||||
#include "../../shared/Marduino.h"
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#include <U8glib.h>
|
||||
|
||||
#if ENABLED(FYSETC_MINI_12864)
|
||||
#define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_3
|
||||
#else
|
||||
#define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_0
|
||||
#endif
|
||||
|
||||
uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_INIT:
|
||||
SCK_pPio = g_APinDescription[u8g->pin_list[U8G_PI_SCK]].pPort;
|
||||
SCK_dwMask = g_APinDescription[u8g->pin_list[U8G_PI_SCK]].ulPin;
|
||||
MOSI_pPio = g_APinDescription[u8g->pin_list[U8G_PI_MOSI]].pPort;
|
||||
MOSI_dwMask = g_APinDescription[u8g->pin_list[U8G_PI_MOSI]].ulPin;
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_SCK);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_MOSI);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_CS);
|
||||
u8g_SetPIOutput_DUE(u8g, U8G_PI_A0);
|
||||
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput_DUE(u8g, U8G_PI_RESET);
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 0);
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_MOSI, 0);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_STOP:
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_RESET:
|
||||
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel_DUE(u8g, U8G_PI_RESET, arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_CHIP_SELECT:
|
||||
#if ENABLED(FYSETC_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0
|
||||
if (arg_val) { // SCK idle state needs to be set to the proper idle state before
|
||||
// the next chip select goes active
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 1); //set SCK to mode 3 idle state before CS goes active
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_CS, LOW);
|
||||
}
|
||||
else {
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_CS, HIGH);
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 0); //set SCK to mode 0 idle state after CS goes inactive
|
||||
}
|
||||
#else
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_CS, !arg_val);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
SPISEND_SW_DUE(arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ: {
|
||||
uint8_t *ptr = (uint8_t *)arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
SPISEND_SW_DUE(*ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ_P: {
|
||||
uint8_t *ptr = (uint8_t *)arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
SPISEND_SW_DUE(u8g_pgm_read(ptr));
|
||||
ptr++;
|
||||
arg_val--;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
|
||||
u8g_SetPILevel_DUE(u8g, U8G_PI_A0, arg_val);
|
||||
break;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920
|
||||
#endif // ARDUINO_ARCH_SAM
|
112
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
Normal file
112
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
Normal file
@ -0,0 +1,112 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 u8g_com_st7920_hw_spi.c
|
||||
*
|
||||
* Universal 8bit Graphics Library
|
||||
*
|
||||
* Copyright (c) 2011, olikraus@gmail.com
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* * Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or other
|
||||
* materials provided with the distribution.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
|
||||
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
|
||||
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
|
||||
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#include <U8glib.h>
|
||||
|
||||
#include "u8g_com_HAL_DUE_sw_spi_shared.h"
|
||||
|
||||
void u8g_SetPIOutput_DUE(u8g_t *u8g, uint8_t pin_index) {
|
||||
PIO_Configure(g_APinDescription[u8g->pin_list[pin_index]].pPort, PIO_OUTPUT_1,
|
||||
g_APinDescription[u8g->pin_list[pin_index]].ulPin, g_APinDescription[u8g->pin_list[pin_index]].ulPinConfiguration); // OUTPUT
|
||||
}
|
||||
|
||||
void u8g_SetPILevel_DUE(u8g_t *u8g, uint8_t pin_index, uint8_t level) {
|
||||
volatile Pio* port = g_APinDescription[u8g->pin_list[pin_index]].pPort;
|
||||
uint32_t mask = g_APinDescription[u8g->pin_list[pin_index]].ulPin;
|
||||
if (level) port->PIO_SODR = mask; else port->PIO_CODR = mask;
|
||||
}
|
||||
|
||||
Pio *SCK_pPio, *MOSI_pPio;
|
||||
uint32_t SCK_dwMask, MOSI_dwMask;
|
||||
|
||||
void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (val & 0x80)
|
||||
MOSI_pPio->PIO_SODR = MOSI_dwMask;
|
||||
else
|
||||
MOSI_pPio->PIO_CODR = MOSI_dwMask;
|
||||
DELAY_NS(48);
|
||||
SCK_pPio->PIO_SODR = SCK_dwMask;
|
||||
DELAY_NS(905);
|
||||
val <<= 1;
|
||||
SCK_pPio->PIO_CODR = SCK_dwMask;
|
||||
}
|
||||
}
|
||||
|
||||
void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
SCK_pPio->PIO_CODR = SCK_dwMask;
|
||||
DELAY_NS(50);
|
||||
if (val & 0x80)
|
||||
MOSI_pPio->PIO_SODR = MOSI_dwMask;
|
||||
else
|
||||
MOSI_pPio->PIO_CODR = MOSI_dwMask;
|
||||
val <<= 1;
|
||||
DELAY_NS(10);
|
||||
SCK_pPio->PIO_SODR = SCK_dwMask;
|
||||
DELAY_NS(70);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_GRAPHICAL_LCD
|
||||
#endif // ARDUINO_ARCH_SAM
|
35
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h
Normal file
35
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h
Normal file
@ -0,0 +1,35 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
#include "../../shared/Marduino.h"
|
||||
#include <U8glib.h>
|
||||
|
||||
void u8g_SetPIOutput_DUE(u8g_t *u8g, uint8_t pin_index);
|
||||
void u8g_SetPILevel_DUE(u8g_t *u8g, uint8_t pin_index, uint8_t level);
|
||||
|
||||
void u8g_spiSend_sw_DUE_mode_0(uint8_t val);
|
||||
void u8g_spiSend_sw_DUE_mode_3(uint8_t val);
|
||||
|
||||
extern Pio *SCK_pPio, *MOSI_pPio;
|
||||
extern uint32_t SCK_dwMask, MOSI_dwMask;
|
89
Marlin/src/HAL/DUE/endstop_interrupts.h
Normal file
89
Marlin/src/HAL/DUE/endstop_interrupts.h
Normal file
@ -0,0 +1,89 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Endstop Interrupts
|
||||
*
|
||||
* Without endstop interrupts the endstop pins must be polled continually in
|
||||
* the temperature-ISR via endstops.update(), most of the time finding no change.
|
||||
* With this feature endstops.update() is called only when we know that at
|
||||
* least one endstop has changed state, saving valuable CPU cycles.
|
||||
*
|
||||
* This feature only works when all used endstop pins can generate an 'external interrupt'.
|
||||
*
|
||||
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
|
||||
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
|
||||
*/
|
||||
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void endstop_ISR() { endstops.update(); }
|
||||
|
||||
/**
|
||||
* Endstop interrupts for Due based targets.
|
||||
* On Due, all pins support external interrupt capability.
|
||||
*/
|
||||
|
||||
void setup_endstop_interrupts() {
|
||||
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
|
||||
#if HAS_X_MAX
|
||||
_ATTACH(X_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
_ATTACH(X_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
_ATTACH(Y_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
_ATTACH(Y_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
_ATTACH(Z_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
_ATTACH(Z_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
_ATTACH(Z2_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
_ATTACH(Z2_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z3_MAX
|
||||
_ATTACH(Z3_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z3_MIN
|
||||
_ATTACH(Z3_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z4_MAX
|
||||
_ATTACH(Z4_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z4_MIN
|
||||
_ATTACH(Z4_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
_ATTACH(Z_MIN_PROBE_PIN);
|
||||
#endif
|
||||
}
|
562
Marlin/src/HAL/DUE/fastio.h
Normal file
562
Marlin/src/HAL/DUE/fastio.h
Normal file
@ -0,0 +1,562 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Fast I/O Routines for SAM3X8E
|
||||
* Use direct port manipulation to save scads of processor time.
|
||||
* Contributed by Triffid_Hunter and modified by Kliment, thinkyhead, Bob-the-Kuhn, et.al.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: Fast IO functions for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
* Note the code here was specifically crafted by disassembling what GCC produces
|
||||
* out of it, so GCC is able to optimize it out as much as possible to the least
|
||||
* amount of instructions. Be very carefull if you modify them, as "clean code"
|
||||
* leads to less efficient compiled code!!
|
||||
*/
|
||||
|
||||
#include <pins_arduino.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
/**
|
||||
* Utility functions
|
||||
*/
|
||||
|
||||
// Due has 12 PWMs assigned to logical pins 2-13.
|
||||
// 6, 7, 8 & 9 come from the PWM controller. The others come from the timers.
|
||||
#define PWM_PIN(P) WITHIN(P, 2, 13)
|
||||
|
||||
#ifndef MASK
|
||||
#define MASK(PIN) (1 << PIN)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Magic I/O routines
|
||||
*
|
||||
* Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW);
|
||||
*
|
||||
* Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
|
||||
*/
|
||||
|
||||
// Read a pin
|
||||
#define _READ(IO) bool(DIO ## IO ## _WPORT -> PIO_PDSR & MASK(DIO ## IO ## _PIN))
|
||||
|
||||
// Write to a pin
|
||||
#define _WRITE(IO,V) do { \
|
||||
volatile Pio* port = (DIO ## IO ## _WPORT); \
|
||||
const uint32_t mask = MASK(DIO ## IO ## _PIN); \
|
||||
if (V) port->PIO_SODR = mask; \
|
||||
else port->PIO_CODR = mask; \
|
||||
}while(0)
|
||||
|
||||
// Toggle a pin
|
||||
#define _TOGGLE(IO) _WRITE(IO, !READ(IO))
|
||||
|
||||
#if MB(PRINTRBOARD_G2)
|
||||
|
||||
#include "fastio/G2_pins.h"
|
||||
|
||||
// Set pin as input
|
||||
#define _SET_INPUT(IO) do{ \
|
||||
pmc_enable_periph_clk(G2_g_APinDescription[IO].ulPeripheralId); \
|
||||
PIO_Configure((DIO ## IO ## _WPORT), PIO_INPUT, MASK(DIO ## IO ## _PIN), 0); \
|
||||
}while(0)
|
||||
|
||||
// Set pin as output
|
||||
#define _SET_OUTPUT(IO) do{ \
|
||||
uint32_t mask = MASK(G2_g_APinDescription[IO].ulPeripheralId); \
|
||||
if ((PMC->PMC_PCSR0 & mask) != (mask)) PMC->PMC_PCER0 = mask; \
|
||||
volatile Pio* port = (DIO ## IO ## _WPORT); \
|
||||
mask = MASK(DIO ## IO ## _PIN); \
|
||||
if (_READ(IO)) port->PIO_SODR = mask; \
|
||||
else port->PIO_CODR = mask; \
|
||||
port->PIO_IDR = mask; \
|
||||
const uint32_t pin_config = G2_g_APinDescription[IO].ulPinConfiguration; \
|
||||
if (pin_config & PIO_PULLUP) port->PIO_PUER = mask; \
|
||||
else port->PIO_PUDR = mask; \
|
||||
if (pin_config & PIO_OPENDRAIN) port->PIO_MDER = mask; \
|
||||
else port->PIO_MDDR = mask; \
|
||||
port->PIO_PER = mask; \
|
||||
port->PIO_OER = mask; \
|
||||
g_pinStatus[IO] = (g_pinStatus[IO] & 0xF0) | PIN_STATUS_DIGITAL_OUTPUT; \
|
||||
}while(0)
|
||||
|
||||
/**
|
||||
* Set pin as output with comments
|
||||
* #define _SET_OUTPUT(IO) do{ \
|
||||
* uint32_t mask = MASK(G2_g_APinDescription[IO].ulPeripheralId); \
|
||||
* if ((PMC->PMC_PCSR0 & mask ) != (mask)) PMC->PMC_PCER0 = mask; \ // enable PIO clock if not already enabled
|
||||
*
|
||||
* volatile Pio* port = (DIO ## IO ## _WPORT); \
|
||||
* const uint32_t mask = MASK(DIO ## IO ## _PIN); \
|
||||
* if (_READ(IO)) port->PIO_SODR = mask; \ // set output to match input BEFORE setting direction or will glitch the output
|
||||
* else port->PIO_CODR = mask; \
|
||||
*
|
||||
* port->PIO_IDR = mask; \ // disable interrupt
|
||||
*
|
||||
* uint32_t pin_config = G2_g_APinDescription[IO].ulPinConfiguration; \
|
||||
* if (pin_config & PIO_PULLUP) pPio->PIO_PUER = mask; \ // enable pullup if necessary
|
||||
* else pPio->PIO_PUDR = mask; \
|
||||
*
|
||||
* if (pin_config & PIO_OPENDRAIN) port->PIO_MDER = mask; \ // Enable multi-drive if necessary
|
||||
* else port->PIO_MDDR = mask; \
|
||||
*
|
||||
* port->PIO_PER = mask; \
|
||||
* port->PIO_OER = mask; \ // set to output
|
||||
*
|
||||
* g_pinStatus[IO] = (g_pinStatus[IO] & 0xF0) | PIN_STATUS_DIGITAL_OUTPUT; \
|
||||
* }while(0)
|
||||
*/
|
||||
|
||||
#else
|
||||
|
||||
// Set pin as input
|
||||
#define _SET_INPUT(IO) do{ \
|
||||
pmc_enable_periph_clk(g_APinDescription[IO].ulPeripheralId); \
|
||||
PIO_Configure(digitalPinToPort(IO), PIO_INPUT, digitalPinToBitMask(IO), 0); \
|
||||
}while(0)
|
||||
|
||||
// Set pin as output
|
||||
#define _SET_OUTPUT(IO) do{ \
|
||||
pmc_enable_periph_clk(g_APinDescription[IO].ulPeripheralId); \
|
||||
PIO_Configure(digitalPinToPort(IO), _READ(IO) ? PIO_OUTPUT_1 : PIO_OUTPUT_0, digitalPinToBitMask(IO), g_APinDescription[IO].ulPinConfiguration); \
|
||||
g_pinStatus[IO] = (g_pinStatus[IO] & 0xF0) | PIN_STATUS_DIGITAL_OUTPUT; \
|
||||
}while(0)
|
||||
#endif
|
||||
|
||||
// Set pin as input with pullup mode
|
||||
#define _PULLUP(IO,V) pinMode(IO, (V) ? INPUT_PULLUP : INPUT)
|
||||
|
||||
// Read a pin (wrapper)
|
||||
#define READ(IO) _READ(IO)
|
||||
|
||||
// Write to a pin (wrapper)
|
||||
#define WRITE(IO,V) _WRITE(IO,V)
|
||||
|
||||
// Toggle a pin (wrapper)
|
||||
#define TOGGLE(IO) _TOGGLE(IO)
|
||||
|
||||
// Set pin as input (wrapper)
|
||||
#define SET_INPUT(IO) _SET_INPUT(IO)
|
||||
// Set pin as input with pullup (wrapper)
|
||||
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
|
||||
// Set pin as output (wrapper) - reads the pin and sets the output to that value
|
||||
#define SET_OUTPUT(IO) _SET_OUTPUT(IO)
|
||||
// Set pin as PWM
|
||||
#define SET_PWM(IO) SET_OUTPUT(IO)
|
||||
|
||||
// Check if pin is an input
|
||||
#define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0)
|
||||
// Check if pin is an output
|
||||
#define IS_OUTPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) != 0)
|
||||
|
||||
// Shorthand
|
||||
#define OUT_WRITE(IO,V) { SET_OUTPUT(IO); WRITE(IO,V); }
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
/**
|
||||
* Ports and functions
|
||||
* Added as necessary or if I feel like it- not a comprehensive list!
|
||||
*/
|
||||
|
||||
// UART
|
||||
#define RXD DIO0
|
||||
#define TXD DIO1
|
||||
|
||||
// TWI (I2C)
|
||||
#define SCL DIO21
|
||||
#define SDA DIO20
|
||||
|
||||
/**
|
||||
* pins
|
||||
*/
|
||||
|
||||
#define DIO0_PIN 8
|
||||
#define DIO0_WPORT PIOA
|
||||
|
||||
#define DIO1_PIN 9
|
||||
#define DIO1_WPORT PIOA
|
||||
|
||||
#define DIO2_PIN 25
|
||||
#define DIO2_WPORT PIOB
|
||||
|
||||
#define DIO3_PIN 28
|
||||
#define DIO3_WPORT PIOC
|
||||
|
||||
#define DIO4_PIN 26
|
||||
#define DIO4_WPORT PIOC
|
||||
|
||||
#define DIO5_PIN 25
|
||||
#define DIO5_WPORT PIOC
|
||||
|
||||
#define DIO6_PIN 24
|
||||
#define DIO6_WPORT PIOC
|
||||
|
||||
#define DIO7_PIN 23
|
||||
#define DIO7_WPORT PIOC
|
||||
|
||||
#define DIO8_PIN 22
|
||||
#define DIO8_WPORT PIOC
|
||||
|
||||
#define DIO9_PIN 21
|
||||
#define DIO9_WPORT PIOC
|
||||
|
||||
#define DIO10_PIN 29
|
||||
#define DIO10_WPORT PIOC
|
||||
|
||||
#define DIO11_PIN 7
|
||||
#define DIO11_WPORT PIOD
|
||||
|
||||
#define DIO12_PIN 8
|
||||
#define DIO12_WPORT PIOD
|
||||
|
||||
#define DIO13_PIN 27
|
||||
#define DIO13_WPORT PIOB
|
||||
|
||||
#define DIO14_PIN 4
|
||||
#define DIO14_WPORT PIOD
|
||||
|
||||
#define DIO15_PIN 5
|
||||
#define DIO15_WPORT PIOD
|
||||
|
||||
#define DIO16_PIN 13
|
||||
#define DIO16_WPORT PIOA
|
||||
|
||||
#define DIO17_PIN 12
|
||||
#define DIO17_WPORT PIOA
|
||||
|
||||
#define DIO18_PIN 11
|
||||
#define DIO18_WPORT PIOA
|
||||
|
||||
#define DIO19_PIN 10
|
||||
#define DIO19_WPORT PIOA
|
||||
|
||||
#define DIO20_PIN 12
|
||||
#define DIO20_WPORT PIOB
|
||||
|
||||
#define DIO21_PIN 13
|
||||
#define DIO21_WPORT PIOB
|
||||
|
||||
#define DIO22_PIN 26
|
||||
#define DIO22_WPORT PIOB
|
||||
|
||||
#define DIO23_PIN 14
|
||||
#define DIO23_WPORT PIOA
|
||||
|
||||
#define DIO24_PIN 15
|
||||
#define DIO24_WPORT PIOA
|
||||
|
||||
#define DIO25_PIN 0
|
||||
#define DIO25_WPORT PIOD
|
||||
|
||||
#define DIO26_PIN 1
|
||||
#define DIO26_WPORT PIOD
|
||||
|
||||
#define DIO27_PIN 2
|
||||
#define DIO27_WPORT PIOD
|
||||
|
||||
#define DIO28_PIN 3
|
||||
#define DIO28_WPORT PIOD
|
||||
|
||||
#define DIO29_PIN 6
|
||||
#define DIO29_WPORT PIOD
|
||||
|
||||
#define DIO30_PIN 9
|
||||
#define DIO30_WPORT PIOD
|
||||
|
||||
#define DIO31_PIN 7
|
||||
#define DIO31_WPORT PIOA
|
||||
|
||||
#define DIO32_PIN 10
|
||||
#define DIO32_WPORT PIOD
|
||||
|
||||
#define DIO33_PIN 1
|
||||
#define DIO33_WPORT PIOC
|
||||
|
||||
#if !MB(PRINTRBOARD_G2) // normal DUE pin mapping
|
||||
|
||||
#define DIO34_PIN 2
|
||||
#define DIO34_WPORT PIOC
|
||||
|
||||
#define DIO35_PIN 3
|
||||
#define DIO35_WPORT PIOC
|
||||
|
||||
#define DIO36_PIN 4
|
||||
#define DIO36_WPORT PIOC
|
||||
|
||||
#define DIO37_PIN 5
|
||||
#define DIO37_WPORT PIOC
|
||||
|
||||
#define DIO38_PIN 6
|
||||
#define DIO38_WPORT PIOC
|
||||
|
||||
#define DIO39_PIN 7
|
||||
#define DIO39_WPORT PIOC
|
||||
|
||||
#define DIO40_PIN 8
|
||||
#define DIO40_WPORT PIOC
|
||||
|
||||
#define DIO41_PIN 9
|
||||
#define DIO41_WPORT PIOC
|
||||
|
||||
#endif // !PRINTRBOARD_G2
|
||||
|
||||
#define DIO42_PIN 19
|
||||
#define DIO42_WPORT PIOA
|
||||
|
||||
#define DIO43_PIN 20
|
||||
#define DIO43_WPORT PIOA
|
||||
|
||||
#define DIO44_PIN 19
|
||||
#define DIO44_WPORT PIOC
|
||||
|
||||
#define DIO45_PIN 18
|
||||
#define DIO45_WPORT PIOC
|
||||
|
||||
#define DIO46_PIN 17
|
||||
#define DIO46_WPORT PIOC
|
||||
|
||||
#define DIO47_PIN 16
|
||||
#define DIO47_WPORT PIOC
|
||||
|
||||
#define DIO48_PIN 15
|
||||
#define DIO48_WPORT PIOC
|
||||
|
||||
#define DIO49_PIN 14
|
||||
#define DIO49_WPORT PIOC
|
||||
|
||||
#define DIO50_PIN 13
|
||||
#define DIO50_WPORT PIOC
|
||||
|
||||
#define DIO51_PIN 12
|
||||
#define DIO51_WPORT PIOC
|
||||
|
||||
#define DIO52_PIN 21
|
||||
#define DIO52_WPORT PIOB
|
||||
|
||||
#define DIO53_PIN 14
|
||||
#define DIO53_WPORT PIOB
|
||||
|
||||
#define DIO54_PIN 16
|
||||
#define DIO54_WPORT PIOA
|
||||
|
||||
#define DIO55_PIN 24
|
||||
#define DIO55_WPORT PIOA
|
||||
|
||||
#define DIO56_PIN 23
|
||||
#define DIO56_WPORT PIOA
|
||||
|
||||
#define DIO57_PIN 22
|
||||
#define DIO57_WPORT PIOA
|
||||
|
||||
#define DIO58_PIN 6
|
||||
#define DIO58_WPORT PIOA
|
||||
|
||||
#define DIO59_PIN 4
|
||||
#define DIO59_WPORT PIOA
|
||||
|
||||
#define DIO60_PIN 3
|
||||
#define DIO60_WPORT PIOA
|
||||
|
||||
#define DIO61_PIN 2
|
||||
#define DIO61_WPORT PIOA
|
||||
|
||||
#define DIO62_PIN 17
|
||||
#define DIO62_WPORT PIOB
|
||||
|
||||
#define DIO63_PIN 18
|
||||
#define DIO63_WPORT PIOB
|
||||
|
||||
#define DIO64_PIN 19
|
||||
#define DIO64_WPORT PIOB
|
||||
|
||||
#define DIO65_PIN 20
|
||||
#define DIO65_WPORT PIOB
|
||||
|
||||
#define DIO66_PIN 15
|
||||
#define DIO66_WPORT PIOB
|
||||
|
||||
#define DIO67_PIN 16
|
||||
#define DIO67_WPORT PIOB
|
||||
|
||||
#define DIO68_PIN 1
|
||||
#define DIO68_WPORT PIOA
|
||||
|
||||
#define DIO69_PIN 0
|
||||
#define DIO69_WPORT PIOA
|
||||
|
||||
#define DIO70_PIN 17
|
||||
#define DIO70_WPORT PIOA
|
||||
|
||||
#define DIO71_PIN 18
|
||||
#define DIO71_WPORT PIOA
|
||||
|
||||
#define DIO72_PIN 30
|
||||
#define DIO72_WPORT PIOC
|
||||
|
||||
#define DIO73_PIN 21
|
||||
#define DIO73_WPORT PIOA
|
||||
|
||||
#define DIO74_PIN 25
|
||||
#define DIO74_WPORT PIOA
|
||||
|
||||
#define DIO75_PIN 26
|
||||
#define DIO75_WPORT PIOA
|
||||
|
||||
#define DIO76_PIN 27
|
||||
#define DIO76_WPORT PIOA
|
||||
|
||||
#define DIO77_PIN 28
|
||||
#define DIO77_WPORT PIOA
|
||||
|
||||
#define DIO78_PIN 23
|
||||
#define DIO78_WPORT PIOB
|
||||
|
||||
#define DIO79_PIN 17
|
||||
#define DIO79_WPORT PIOA
|
||||
|
||||
#define DIO80_PIN 12
|
||||
#define DIO80_WPORT PIOB
|
||||
|
||||
#define DIO81_PIN 8
|
||||
#define DIO81_WPORT PIOA
|
||||
|
||||
#define DIO82_PIN 11
|
||||
#define DIO82_WPORT PIOA
|
||||
|
||||
#define DIO83_PIN 13
|
||||
#define DIO83_WPORT PIOA
|
||||
|
||||
#define DIO84_PIN 4
|
||||
#define DIO84_WPORT PIOD
|
||||
|
||||
#define DIO85_PIN 11
|
||||
#define DIO85_WPORT PIOB
|
||||
|
||||
#define DIO86_PIN 21
|
||||
#define DIO86_WPORT PIOB
|
||||
|
||||
#define DIO87_PIN 29
|
||||
#define DIO87_WPORT PIOA
|
||||
|
||||
#define DIO88_PIN 15
|
||||
#define DIO88_WPORT PIOB
|
||||
|
||||
#define DIO89_PIN 14
|
||||
#define DIO89_WPORT PIOB
|
||||
|
||||
#define DIO90_PIN 1
|
||||
#define DIO90_WPORT PIOA
|
||||
|
||||
#define DIO91_PIN 15
|
||||
#define DIO91_WPORT PIOB
|
||||
|
||||
#if ARDUINO_SAM_ARCHIM
|
||||
|
||||
#define DIO92_PIN 11
|
||||
#define DIO92_WPORT PIOC
|
||||
|
||||
#define DIO93_PIN 2
|
||||
#define DIO93_WPORT PIOB
|
||||
|
||||
#define DIO94_PIN 1
|
||||
#define DIO94_WPORT PIOB
|
||||
|
||||
#define DIO95_PIN 0
|
||||
#define DIO95_WPORT PIOB
|
||||
|
||||
#define DIO96_PIN 10
|
||||
#define DIO96_WPORT PIOC
|
||||
|
||||
#define DIO97_PIN 24
|
||||
#define DIO97_WPORT PIOB
|
||||
|
||||
#define DIO98_PIN 7
|
||||
#define DIO98_WPORT PIOB
|
||||
|
||||
#define DIO99_PIN 6
|
||||
#define DIO99_WPORT PIOB
|
||||
|
||||
#define DIO100_PIN 8
|
||||
#define DIO100_WPORT PIOB
|
||||
|
||||
#define DIO101_PIN 5
|
||||
#define DIO101_WPORT PIOB
|
||||
|
||||
#define DIO102_PIN 4
|
||||
#define DIO102_WPORT PIOB
|
||||
|
||||
#define DIO103_PIN 3
|
||||
#define DIO103_WPORT PIOB
|
||||
|
||||
#define DIO104_PIN 20
|
||||
#define DIO104_WPORT PIOC
|
||||
|
||||
#define DIO105_PIN 22
|
||||
#define DIO105_WPORT PIOB
|
||||
|
||||
#define DIO106_PIN 27
|
||||
#define DIO106_WPORT PIOC
|
||||
|
||||
#define DIO107_PIN 10
|
||||
#define DIO107_WPORT PIOB
|
||||
|
||||
#define DIO108_PIN 9
|
||||
#define DIO108_WPORT PIOB
|
||||
|
||||
#else // !ARDUINO_SAM_ARCHIM
|
||||
|
||||
#define DIO92_PIN 5
|
||||
#define DIO92_WPORT PIOA
|
||||
|
||||
#define DIO93_PIN 12
|
||||
#define DIO93_WPORT PIOB
|
||||
|
||||
#define DIO94_PIN 22
|
||||
#define DIO94_WPORT PIOB
|
||||
|
||||
#define DIO95_PIN 23
|
||||
#define DIO95_WPORT PIOB
|
||||
|
||||
#define DIO96_PIN 24
|
||||
#define DIO96_WPORT PIOB
|
||||
|
||||
#define DIO97_PIN 20
|
||||
#define DIO97_WPORT PIOC
|
||||
|
||||
#define DIO98_PIN 27
|
||||
#define DIO98_WPORT PIOC
|
||||
|
||||
#define DIO99_PIN 10
|
||||
#define DIO99_WPORT PIOC
|
||||
|
||||
#define DIO100_PIN 11
|
||||
#define DIO100_WPORT PIOC
|
||||
|
||||
#endif // !ARDUINO_SAM_ARCHIM
|
145
Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
Normal file
145
Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
Normal file
@ -0,0 +1,145 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 PWM module is only used to generate interrupts 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. The G2 needs about 10KHz min in order to
|
||||
* not have obvious ripple on the Vref signals.
|
||||
*
|
||||
* The data structures are setup to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 0.8 to 1.1 microseconds.
|
||||
*
|
||||
* FIve PWM interrupt sources are used. Channel 0 sets the base period. All Vref
|
||||
* signals are set active when this counter overflows and resets to zero. The compare
|
||||
* values in channels 1-4 are set to give the desired duty cycle for that Vref pin.
|
||||
* When counter 0 matches the compare value then that channel generates an interrupt.
|
||||
* The ISR checks the source of the interrupt and sets the corresponding pin inactive.
|
||||
*
|
||||
* Some jitter in the Vref signal is OK so the interrupt priority is left at its default value.
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if MB(PRINTRBOARD_G2)
|
||||
|
||||
#include "G2_PWM.h"
|
||||
|
||||
volatile uint32_t *SODR_A = &PIOA->PIO_SODR,
|
||||
*SODR_B = &PIOB->PIO_SODR,
|
||||
*CODR_A = &PIOA->PIO_CODR,
|
||||
*CODR_B = &PIOB->PIO_CODR;
|
||||
|
||||
PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT;
|
||||
|
||||
void Stepper::digipot_init() {
|
||||
|
||||
OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins
|
||||
OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0);
|
||||
OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0);
|
||||
OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0);
|
||||
|
||||
#define WPKEY (0x50574D << 8) // “PWM” in ASCII
|
||||
#define WPCMD_DIS_SW 0 // command to disable Write Protect SW
|
||||
#define WPRG_ALL (PWM_WPCR_WPRG0 | PWM_WPCR_WPRG1 | PWM_WPCR_WPRG2 | PWM_WPCR_WPRG3 | PWM_WPCR_WPRG4 | PWM_WPCR_WPRG5) // all Write Protect Groups
|
||||
|
||||
#define PWM_CLOCK_F F_CPU / 1000000UL // set clock to 1MHz
|
||||
|
||||
PMC->PMC_PCER1 = PMC_PCER1_PID36; // enable PWM controller clock (disabled on power up)
|
||||
|
||||
PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers
|
||||
PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled
|
||||
PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned
|
||||
PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned
|
||||
PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned
|
||||
PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned
|
||||
PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned
|
||||
|
||||
PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period
|
||||
|
||||
PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows
|
||||
PWM->PWM_IER2 = PWM_IER2_CMPM0 | PWM_IER2_CMPM1 | PWM_IER2_CMPM2 | PWM_IER2_CMPM3 | PWM_IER2_CMPM4; // generate interrupt on compare event
|
||||
|
||||
PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive
|
||||
PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive
|
||||
PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive
|
||||
PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive
|
||||
|
||||
PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event
|
||||
PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event
|
||||
PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event
|
||||
PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event
|
||||
|
||||
PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 | PWM_SCM_SYNC1 | PWM_SCM_SYNC2 | PWM_SCM_SYNC3 | PWM_SCM_SYNC4; // sync 1-4 with 0, use mode 0 for updates
|
||||
|
||||
PWM->PWM_ENA = PWM_ENA_CHID0 | PWM_ENA_CHID1 | PWM_ENA_CHID2 | PWM_ENA_CHID3 | PWM_ENA_CHID4; // enable the channels used by G2
|
||||
PWM->PWM_IER1 = PWM_IER1_CHID0 | PWM_IER1_CHID1 | PWM_IER1_CHID2 | PWM_IER1_CHID3 | PWM_IER1_CHID4; // enable interrupts for the channels used by G2
|
||||
|
||||
NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler
|
||||
NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals)
|
||||
}
|
||||
|
||||
void Stepper::digipot_current(const uint8_t driver, const int16_t current) {
|
||||
|
||||
if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed
|
||||
|
||||
switch (driver) {
|
||||
case 0: PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y
|
||||
PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current));
|
||||
PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event
|
||||
PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event
|
||||
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
|
||||
break;
|
||||
case 1: PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z
|
||||
PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event
|
||||
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
|
||||
break;
|
||||
default:PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E
|
||||
PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event
|
||||
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS;
|
||||
|
||||
void PWM_Handler() {
|
||||
PWM_ISR1_STATUS = PWM->PWM_ISR1;
|
||||
PWM_ISR2_STATUS = PWM->PWM_ISR2;
|
||||
if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt
|
||||
*ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active
|
||||
*ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active
|
||||
*ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active
|
||||
*ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active
|
||||
}
|
||||
else {
|
||||
if (PWM_ISR2_STATUS & PWM_IER2_CMPM1) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive
|
||||
if (PWM_ISR2_STATUS & PWM_IER2_CMPM2) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive
|
||||
if (PWM_ISR2_STATUS & PWM_IER2_CMPM3) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive
|
||||
if (PWM_ISR2_STATUS & PWM_IER2_CMPM4) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
#endif // PRINTRBOARD_G2
|
78
Marlin/src/HAL/DUE/fastio/G2_PWM.h
Normal file
78
Marlin/src/HAL/DUE/fastio/G2_PWM.h
Normal file
@ -0,0 +1,78 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* This module is stripped down version of the LPC1768_PWM.h file from
|
||||
* PR #7500. It is hardwired for the PRINTRBOARD_G2 Motor Current needs.
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
#include "../../../module/stepper.h"
|
||||
//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\module\stepper.h
|
||||
//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\HAL\HAL_DUE\G2_PWM.h
|
||||
|
||||
#define PWM_PERIOD_US 100 // base repetition rate in micro seconds
|
||||
|
||||
typedef struct { // holds the data needed by the ISR to control the Vref pin
|
||||
volatile uint32_t* set_register;
|
||||
volatile uint32_t* clr_register;
|
||||
uint32_t write_mask;
|
||||
} PWM_map;
|
||||
|
||||
#define G2_VREF(I) (uint32_t)(I * 5 * 0.15) // desired Vref * 1000 (scaled so don't loose accuracy in next step)
|
||||
|
||||
#define G2_VREF_COUNT(Q) (uint32_t)map(constrain(Q, 500, 3.3 * 1000), 0, 3.3 * 1000, 0, PWM_PERIOD_US) // under 500 the results are very non-linear
|
||||
|
||||
extern volatile uint32_t *SODR_A, *SODR_B, *CODR_A, *CODR_B;
|
||||
|
||||
#define _PIN(IO) (DIO ## IO ## _PIN)
|
||||
|
||||
#define PWM_MAP_INIT_ROW(IO,ZZ) { ZZ == 'A' ? SODR_A : SODR_B, ZZ == 'A' ? CODR_A : CODR_B, 1 << _PIN(IO) }
|
||||
|
||||
|
||||
#define PWM_MAP_INIT { PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_X_PIN, 'B'), \
|
||||
PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Y_PIN, 'B'), \
|
||||
PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Z_PIN, 'B'), \
|
||||
PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_E_PIN, 'A'), \
|
||||
};
|
||||
|
||||
#define NUM_PWMS 4
|
||||
|
||||
extern PWM_map ISR_table[NUM_PWMS];
|
||||
|
||||
extern uint32_t motor_current_setting[3];
|
||||
|
||||
#define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4)
|
||||
#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]; }while(0)
|
||||
|
||||
#define PWM_MR0 19999 // base repetition rate minus one count - 20mS
|
||||
#define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output
|
||||
#define PWM_PCLKSEL0 0x00 // select clock source for prescaler - defaults to 25MHz on power up
|
||||
// 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
extern bool PWM_table_swap; // flag to tell the ISR that the tables have been swapped
|
||||
|
||||
#define HAL_G2_PWM_ISR void PWM_Handler()
|
||||
|
||||
extern volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS;
|
278
Marlin/src/HAL/DUE/fastio/G2_pins.h
Normal file
278
Marlin/src/HAL/DUE/fastio/G2_pins.h
Normal file
@ -0,0 +1,278 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* This file contains the custom port/pin definitions for the PRINTRBOARD_G2
|
||||
* motherboard. This motherboard uses the SAM3X8C which is a subset of the
|
||||
* SAM3X8E used in the DUE board. It uses port/pin pairs that are not
|
||||
* available using the DUE definitions.
|
||||
*
|
||||
* The first part is a copy of the pin descriptions in the
|
||||
* "variants\arduino_due_x\variant.cpp" file but with pins 34-41 replaced by
|
||||
* the G2 pins.
|
||||
*
|
||||
* The second part is the FASTIO port/pin definitions.
|
||||
*
|
||||
* THESE PINS CAN ONLY BE ACCESSED VIA FASTIO COMMANDS.
|
||||
*/
|
||||
|
||||
/*
|
||||
Copyright (c) 2011 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
|
||||
*/
|
||||
|
||||
typedef struct _G2_PinDescription {
|
||||
Pio* pPort;
|
||||
uint32_t ulPin;
|
||||
uint32_t ulPeripheralId;
|
||||
EPioType ulPinType;
|
||||
uint32_t ulPinConfiguration;
|
||||
uint32_t ulPinAttribute;
|
||||
EAnalogChannel ulAnalogChannel; /* Analog pin in the Arduino context (label on the board) */
|
||||
EAnalogChannel ulADCChannelNumber; /* ADC Channel number in the SAM device */
|
||||
EPWMChannel ulPWMChannel;
|
||||
ETCChannel ulTCChannel;
|
||||
} G2_PinDescription;
|
||||
|
||||
/**
|
||||
* This section is a copy of the pin descriptions in the "variants\arduino_due_x\variant.cpp" file
|
||||
* with pins 34-41 replaced by the G2 pins.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Pins descriptions
|
||||
*/
|
||||
const G2_PinDescription G2_g_APinDescription[] = {
|
||||
// 0 .. 53 - Digital pins
|
||||
// ----------------------
|
||||
// 0/1 - UART (Serial)
|
||||
{ PIOA, PIO_PA8A_URXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // URXD
|
||||
{ PIOA, PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // UTXD
|
||||
|
||||
// 2
|
||||
{ PIOB, PIO_PB25B_TIOA0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHA0 }, // TIOA0
|
||||
{ PIOC, PIO_PC28B_TIOA7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA7 }, // TIOA7
|
||||
{ PIOC, PIO_PC26B_TIOB6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB6 }, // TIOB6
|
||||
|
||||
// 5
|
||||
{ PIOC, PIO_PC25B_TIOA6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA6 }, // TIOA6
|
||||
{ PIOC, PIO_PC24B_PWML7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH7, NOT_ON_TIMER }, // PWML7
|
||||
{ PIOC, PIO_PC23B_PWML6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH6, NOT_ON_TIMER }, // PWML6
|
||||
{ PIOC, PIO_PC22B_PWML5, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH5, NOT_ON_TIMER }, // PWML5
|
||||
{ PIOC, PIO_PC21B_PWML4, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH4, NOT_ON_TIMER }, // PWML4
|
||||
// 10
|
||||
{ PIOC, PIO_PC29B_TIOB7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB7 }, // TIOB7
|
||||
{ PIOD, PIO_PD7B_TIOA8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA8 }, // TIOA8
|
||||
{ PIOD, PIO_PD8B_TIOB8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB8 }, // TIOB8
|
||||
|
||||
// 13 - AMBER LED
|
||||
{ PIOB, PIO_PB27B_TIOB0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHB0 }, // TIOB0
|
||||
|
||||
// 14/15 - USART3 (Serial3)
|
||||
{ PIOD, PIO_PD4B_TXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD3
|
||||
{ PIOD, PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD3
|
||||
|
||||
// 16/17 - USART1 (Serial2)
|
||||
{ PIOA, PIO_PA13A_TXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD1
|
||||
{ PIOA, PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD1
|
||||
|
||||
// 18/19 - USART0 (Serial1)
|
||||
{ PIOA, PIO_PA11A_TXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD0
|
||||
{ PIOA, PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD0
|
||||
|
||||
// 20/21 - TWI1
|
||||
{ PIOB, PIO_PB12A_TWD1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD1 - SDA0
|
||||
{ PIOB, PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK1 - SCL0
|
||||
|
||||
// 22
|
||||
{ PIOB, PIO_PB26, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 22
|
||||
{ PIOA, PIO_PA14, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 23
|
||||
{ PIOA, PIO_PA15, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 24
|
||||
{ PIOD, PIO_PD0, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 25
|
||||
|
||||
// 26
|
||||
{ PIOD, PIO_PD1, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 26
|
||||
{ PIOD, PIO_PD2, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 27
|
||||
{ PIOD, PIO_PD3, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 28
|
||||
{ PIOD, PIO_PD6, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 29
|
||||
|
||||
// 30
|
||||
{ PIOD, PIO_PD9, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 30
|
||||
{ PIOA, PIO_PA7, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 31
|
||||
{ PIOD, PIO_PD10, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 32
|
||||
{ PIOC, PIO_PC1, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 33
|
||||
|
||||
// 34
|
||||
|
||||
// start of custom pins
|
||||
{ PIOA, PIO_PA29, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 34 Y_STEP_PIN
|
||||
{ PIOB, PIO_PB1, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 35 Y_DIR_PIN
|
||||
{ PIOB, PIO_PB0, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 36 Y_ENABLE_PIN
|
||||
{ PIOB, PIO_PB22, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 37 E0_ENABLE_PIN
|
||||
{ PIOB, PIO_PB11, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 38 E0_MS1_PIN
|
||||
{ PIOB, PIO_PB10, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 39 E0_MS3_PIN
|
||||
{ PIOA, PIO_PA5, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 40 HEATER_0_PIN
|
||||
{ PIOB, PIO_PB24, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 41 HEATER_BED_PIN
|
||||
// end of custom pins
|
||||
|
||||
// 42
|
||||
{ PIOA, PIO_PA19, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 42
|
||||
{ PIOA, PIO_PA20, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 43
|
||||
{ PIOC, PIO_PC19, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 44
|
||||
{ PIOC, PIO_PC18, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 45
|
||||
|
||||
// 46
|
||||
{ PIOC, PIO_PC17, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 46
|
||||
{ PIOC, PIO_PC16, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 47
|
||||
{ PIOC, PIO_PC15, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 48
|
||||
{ PIOC, PIO_PC14, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 49
|
||||
|
||||
// 50
|
||||
{ PIOC, PIO_PC13, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 50
|
||||
{ PIOC, PIO_PC12, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 51
|
||||
{ PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52
|
||||
{ PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53
|
||||
|
||||
|
||||
// 54 .. 65 - Analog pins
|
||||
// ----------------------
|
||||
{ PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0
|
||||
{ PIOA, PIO_PA24X1_AD6, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC1, ADC6, NOT_ON_PWM, NOT_ON_TIMER }, // AD1
|
||||
{ PIOA, PIO_PA23X1_AD5, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC2, ADC5, NOT_ON_PWM, NOT_ON_TIMER }, // AD2
|
||||
{ PIOA, PIO_PA22X1_AD4, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC3, ADC4, NOT_ON_PWM, NOT_ON_TIMER }, // AD3
|
||||
// 58
|
||||
{ PIOA, PIO_PA6X1_AD3, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC4, ADC3, NOT_ON_PWM, TC0_CHB2 }, // AD4
|
||||
{ PIOA, PIO_PA4X1_AD2, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC5, ADC2, NOT_ON_PWM, NOT_ON_TIMER }, // AD5
|
||||
{ PIOA, PIO_PA3X1_AD1, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC6, ADC1, NOT_ON_PWM, TC0_CHB1 }, // AD6
|
||||
{ PIOA, PIO_PA2X1_AD0, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC7, ADC0, NOT_ON_PWM, TC0_CHA1 }, // AD7
|
||||
// 62
|
||||
{ PIOB, PIO_PB17X1_AD10, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC8, ADC10, NOT_ON_PWM, NOT_ON_TIMER }, // AD8
|
||||
{ PIOB, PIO_PB18X1_AD11, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC9, ADC11, NOT_ON_PWM, NOT_ON_TIMER }, // AD9
|
||||
{ PIOB, PIO_PB19X1_AD12, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC10, ADC12, NOT_ON_PWM, NOT_ON_TIMER }, // AD10
|
||||
{ PIOB, PIO_PB20X1_AD13, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC11, ADC13, NOT_ON_PWM, NOT_ON_TIMER }, // AD11
|
||||
|
||||
// 66/67 - DAC0/DAC1
|
||||
{ PIOB, PIO_PB15X1_DAC0, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC12, DA0, NOT_ON_PWM, NOT_ON_TIMER }, // DAC0
|
||||
{ PIOB, PIO_PB16X1_DAC1, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC13, DA1, NOT_ON_PWM, NOT_ON_TIMER }, // DAC1
|
||||
|
||||
// 68/69 - CANRX0/CANTX0
|
||||
{ PIOA, PIO_PA1A_CANRX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC14, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX
|
||||
{ PIOA, PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC15, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX
|
||||
|
||||
// 70/71 - TWI0
|
||||
{ PIOA, PIO_PA17A_TWD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD0 - SDA1
|
||||
{ PIOA, PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK0 - SCL1
|
||||
|
||||
// 72/73 - LEDs
|
||||
{ PIOC, PIO_PC30, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER RXL
|
||||
{ PIOA, PIO_PA21, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER TXL
|
||||
|
||||
// 74/75/76 - SPI
|
||||
{ PIOA, PIO_PA25A_SPI0_MISO,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MISO
|
||||
{ PIOA, PIO_PA26A_SPI0_MOSI,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MOSI
|
||||
{ PIOA, PIO_PA27A_SPI0_SPCK,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // SPCK
|
||||
|
||||
// 77 - SPI CS0
|
||||
{ PIOA, PIO_PA28A_SPI0_NPCS0,ID_PIOA,PIO_PERIPH_A,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS0
|
||||
|
||||
// 78 - SPI CS3 (unconnected)
|
||||
{ PIOB, PIO_PB23B_SPI0_NPCS3,ID_PIOB,PIO_PERIPH_B,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS3
|
||||
|
||||
// 79 .. 84 - "All pins" masks
|
||||
|
||||
// 79 - TWI0 all pins
|
||||
{ PIOA, PIO_PA17A_TWD0|PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 80 - TWI1 all pins
|
||||
{ PIOB, PIO_PB12A_TWD1|PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 81 - UART (Serial) all pins
|
||||
{ PIOA, PIO_PA8A_URXD|PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 82 - USART0 (Serial1) all pins
|
||||
{ PIOA, PIO_PA11A_TXD0|PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 83 - USART1 (Serial2) all pins
|
||||
{ PIOA, PIO_PA13A_TXD1|PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 84 - USART3 (Serial3) all pins
|
||||
{ PIOD, PIO_PD4B_TXD3|PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
|
||||
// 85 - USB
|
||||
{ PIOB, PIO_PB11A_UOTGID|PIO_PB10A_UOTGVBOF, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL,NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ID - VBOF
|
||||
|
||||
// 86 - SPI CS2
|
||||
{ PIOB, PIO_PB21B_SPI0_NPCS2, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS2
|
||||
|
||||
// 87 - SPI CS1
|
||||
{ PIOA, PIO_PA29A_SPI0_NPCS1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS1
|
||||
|
||||
// 88/89 - CANRX1/CANTX1 (same physical pin for 66/53)
|
||||
{ PIOB, PIO_PB15A_CANRX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX1
|
||||
{ PIOB, PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX1
|
||||
|
||||
// 90 .. 91 - "All CAN pins" masks
|
||||
// 90 - CAN0 all pins
|
||||
{ PIOA, PIO_PA1A_CANRX0|PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
// 91 - CAN1 all pins
|
||||
{ PIOB, PIO_PB15A_CANRX1|PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
|
||||
|
||||
// END
|
||||
{ nullptr, 0, 0, PIO_NOT_A_PIN, PIO_DEFAULT, 0, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }
|
||||
};
|
||||
|
||||
// This section replaces the FASTIO definitions of pins 34-41
|
||||
|
||||
#define DIO34_PIN 29
|
||||
#define DIO34_WPORT PIOA // only available via FASTIO // 34 PA29 - Y_STEP_PIN
|
||||
|
||||
#define DIO35_PIN 1
|
||||
#define DIO35_WPORT PIOB // only available via FASTIO // 35 PAB1 - Y_DIR_PIN
|
||||
|
||||
#define DIO36_PIN 0
|
||||
#define DIO36_WPORT PIOB // only available via FASTIO // 36 PB0 - Y_ENABLE_PIN
|
||||
|
||||
#define DIO37_PIN 22
|
||||
#define DIO37_WPORT PIOB // only available via FASTIO // 37 PB22 - E0_ENABLE_PIN
|
||||
|
||||
#define DIO38_PIN 11
|
||||
#define DIO38_WPORT PIOB // only available via FASTIO // 38 PB11 - E0_MS1_PIN
|
||||
|
||||
#define DIO39_PIN 10
|
||||
#define DIO39_WPORT PIOB // only available via FASTIO // 39 PB10 - E0_MS3_PIN
|
||||
|
||||
#define DIO40_PIN 5
|
||||
#define DIO40_WPORT PIOA // only available via FASTIO // 40 PA5 - HEATER_0_PIN
|
||||
|
||||
#define DIO41_PIN 24
|
||||
#define DIO41_WPORT PIOB // only available via FASTIO // 41 PB24 - HEATER_BED_PIN
|
22
Marlin/src/HAL/DUE/inc/Conditionals_LCD.h
Normal file
22
Marlin/src/HAL/DUE/inc/Conditionals_LCD.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
22
Marlin/src/HAL/DUE/inc/Conditionals_adv.h
Normal file
22
Marlin/src/HAL/DUE/inc/Conditionals_adv.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
28
Marlin/src/HAL/DUE/inc/Conditionals_post.h
Normal file
28
Marlin/src/HAL/DUE/inc/Conditionals_post.h
Normal file
@ -0,0 +1,28 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#if USE_EMULATED_EEPROM
|
||||
#undef SRAM_EEPROM_EMULATION
|
||||
#undef SDCARD_EEPROM_EMULATION
|
||||
#define FLASH_EEPROM_EMULATION 1
|
||||
#endif
|
61
Marlin/src/HAL/DUE/inc/SanityCheck.h
Normal file
61
Marlin/src/HAL/DUE/inc/SanityCheck.h
Normal file
@ -0,0 +1,61 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Test Arduino Due specific configuration values for errors at compile-time.
|
||||
*/
|
||||
|
||||
/**
|
||||
* HARDWARE VS. SOFTWARE SPI COMPATIBILITY
|
||||
*
|
||||
* DUE selects hardware vs. software SPI depending on whether one of the hardware-controllable SDSS pins is in use.
|
||||
*
|
||||
* The hardware SPI controller doesn't allow software SPIs to control any shared pins.
|
||||
*
|
||||
* When DUE software SPI is used then Trinamic drivers must use the TMC softSPI.
|
||||
*
|
||||
* When DUE hardware SPI is used then a Trinamic driver can use either its hardware SPI or, if there are no shared
|
||||
* pins, its software SPI.
|
||||
*
|
||||
* Usually the hardware SPI pins are only available to the LCD. This makes the DUE hard SPI used at the same time
|
||||
* as the TMC2130 soft SPI the most common setup.
|
||||
*/
|
||||
#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SW_##P == MOSI_PIN || TMC_SW_##P == MISO_PIN || TMC_SW_##P == SCK_PIN))
|
||||
|
||||
#if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130)
|
||||
#if ENABLED(TMC_USE_SW_SPI)
|
||||
#if DISABLED(DUE_SOFTWARE_SPI) && (_IS_HW_SPI(MOSI) || _IS_HW_SPI(MISO) || _IS_HW_SPI(SCK))
|
||||
#error "DUE hardware SPI is required but is incompatible with TMC2130 software SPI. Either disable TMC_USE_SW_SPI or use separate pins for the two SPIs."
|
||||
#endif
|
||||
#elif ENABLED(DUE_SOFTWARE_SPI)
|
||||
#error "DUE software SPI is required but is incompatible with TMC2130 hardware SPI. Enable TMC_USE_SW_SPI to fix."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
#error "FAST_PWM_FAN is not yet implemented for this platform."
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_SW_SERIAL
|
||||
#error "TMC220x Software Serial is not supported on this platform."
|
||||
#endif
|
82
Marlin/src/HAL/DUE/persistent_store_eeprom.cpp
Normal file
82
Marlin/src/HAL/DUE/persistent_store_eeprom.cpp
Normal file
@ -0,0 +1,82 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
|
||||
*
|
||||
* 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 ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(EEPROM_SETTINGS)
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/persistent_store_api.h"
|
||||
|
||||
#if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION)
|
||||
#define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp)
|
||||
#endif
|
||||
|
||||
extern void eeprom_flush();
|
||||
|
||||
bool PersistentStore::access_start() { return true; }
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
#if ENABLED(FLASH_EEPROM_EMULATION)
|
||||
eeprom_flush();
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
while (size--) {
|
||||
uint8_t * const p = (uint8_t * const)pos;
|
||||
uint8_t v = *value;
|
||||
// EEPROM has only ~100,000 write cycles,
|
||||
// so only write bytes that have changed!
|
||||
if (v != eeprom_read_byte(p)) {
|
||||
eeprom_write_byte(p, v);
|
||||
delay(2);
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
crc16(crc, &v, 1);
|
||||
pos++;
|
||||
value++;
|
||||
};
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
do {
|
||||
uint8_t c = eeprom_read_byte((uint8_t*)pos);
|
||||
if (writing) *value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return E2END + 1; }
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_SAM
|
183
Marlin/src/HAL/DUE/pinsDebug.h
Normal file
183
Marlin/src/HAL/DUE/pinsDebug.h
Normal file
@ -0,0 +1,183 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Support routines for Due
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
*/
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
|
||||
/**
|
||||
* Due/Marlin quirks
|
||||
*
|
||||
* a) determining the state of a pin
|
||||
* The Due/Arduino status definitions for the g_pinStatus[pin] array are:
|
||||
* #define PIN_STATUS_DIGITAL_INPUT_PULLUP (0x01)
|
||||
* #define PIN_STATUS_DIGITAL_INPUT (0x02)
|
||||
* #define PIN_STATUS_DIGITAL_OUTPUT (0x03)
|
||||
* #define PIN_STATUS_ANALOG (0x04)
|
||||
* #define PIN_STATUS_PWM (0x05)
|
||||
* #define PIN_STATUS_TIMER (0x06)
|
||||
*
|
||||
* These are only valid if the following Due/Arduino provided functions are used:
|
||||
* analogRead
|
||||
* analogWrite
|
||||
* digitalWrite
|
||||
* pinMode
|
||||
*
|
||||
* The FASTIO routines do not touch the g_pinStatus[pin] array.
|
||||
*
|
||||
* The net result is that both the g_pinStatus[pin] array and the PIO_OSR register
|
||||
* needs to be looked at when determining if a pin is an input or an output.
|
||||
*
|
||||
* b) Due has only pins 6, 7, 8 & 9 enabled for PWMs. FYI - they run at 1KHz
|
||||
*
|
||||
* c) NUM_DIGITAL_PINS does not include the analog pins
|
||||
*
|
||||
* d) Pins 0-78 are defined for Due but 78 has a comment of "unconnected!". 78 is
|
||||
* included just in case.
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define PRINT_PORT(p)
|
||||
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
||||
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0)
|
||||
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
|
||||
#define IS_ANALOG(P) WITHIN(P, char(analogInputToDigitalPin(0)), char(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
|
||||
#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \
|
||||
((g_APinDescription[pin].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
|
||||
#define MULTI_NAME_PAD 14 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
|
||||
volatile Pio* port = g_APinDescription[pin].pPort;
|
||||
uint32_t mask = g_APinDescription[pin].ulPin;
|
||||
uint8_t pin_status = g_pinStatus[pin] & 0xF;
|
||||
return ( (pin_status == 0 && (port->PIO_OSR & mask))
|
||||
|| pin_status == PIN_STATUS_DIGITAL_OUTPUT
|
||||
|| pwm_status(pin));
|
||||
}
|
||||
|
||||
|
||||
void pwm_details(int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
uint32_t chan = g_APinDescription[pin].ulPWMChannel;
|
||||
SERIAL_ECHOPAIR("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* DUE Board pin | PORT | Label
|
||||
* ----------------+--------+-------
|
||||
* 0 | PA8 | "RX0"
|
||||
* 1 | PA9 | "TX0"
|
||||
* 2 TIOA0 | PB25 |
|
||||
* 3 TIOA7 | PC28 |
|
||||
* 4 NPCS1 | PA29 |
|
||||
* TIOB6 | PC26 |
|
||||
* 5 TIOA6 | PC25 |
|
||||
* 6 PWML7 | PC24 |
|
||||
* 7 PWML6 | PC23 |
|
||||
* 8 PWML5 | PC22 |
|
||||
* 9 PWML4 | PC21 |
|
||||
* 10 NPCS0 | PA28 |
|
||||
* TIOB7 | PC29 |
|
||||
* 11 TIOA8 | PD7 |
|
||||
* 12 TIOB8 | PD8 |
|
||||
* 13 TIOB0 | PB27 | LED AMBER "L"
|
||||
* 14 TXD3 | PD4 | "TX3"
|
||||
* 15 RXD3 | PD5 | "RX3"
|
||||
* 16 TXD1 | PA13 | "TX2"
|
||||
* 17 RXD1 | PA12 | "RX2"
|
||||
* 18 TXD0 | PA11 | "TX1"
|
||||
* 19 RXD0 | PA10 | "RX1"
|
||||
* 20 | PB12 | "SDA"
|
||||
* 21 | PB13 | "SCL"
|
||||
* 22 | PB26 |
|
||||
* 23 | PA14 |
|
||||
* 24 | PA15 |
|
||||
* 25 | PD0 |
|
||||
* 26 | PD1 |
|
||||
* 27 | PD2 |
|
||||
* 28 | PD3 |
|
||||
* 29 | PD6 |
|
||||
* 30 | PD9 |
|
||||
* 31 | PA7 |
|
||||
* 32 | PD10 |
|
||||
* 33 | PC1 |
|
||||
* 34 | PC2 |
|
||||
* 35 | PC3 |
|
||||
* 36 | PC4 |
|
||||
* 37 | PC5 |
|
||||
* 38 | PC6 |
|
||||
* 39 | PC7 |
|
||||
* 40 | PC8 |
|
||||
* 41 | PC9 |
|
||||
* 42 | PA19 |
|
||||
* 43 | PA20 |
|
||||
* 44 | PC19 |
|
||||
* 45 | PC18 |
|
||||
* 46 | PC17 |
|
||||
* 47 | PC16 |
|
||||
* 48 | PC15 |
|
||||
* 49 | PC14 |
|
||||
* 50 | PC13 |
|
||||
* 51 | PC12 |
|
||||
* 52 NPCS2 | PB21 |
|
||||
* 53 | PB14 |
|
||||
* 54 | PA16 | "A0"
|
||||
* 55 | PA24 | "A1"
|
||||
* 56 | PA23 | "A2"
|
||||
* 57 | PA22 | "A3"
|
||||
* 58 TIOB2 | PA6 | "A4"
|
||||
* 69 | PA4 | "A5"
|
||||
* 60 TIOB1 | PA3 | "A6"
|
||||
* 61 TIOA1 | PA2 | "A7"
|
||||
* 62 | PB17 | "A8"
|
||||
* 63 | PB18 | "A9"
|
||||
* 64 | PB19 | "A10"
|
||||
* 65 | PB20 | "A11"
|
||||
* 66 | PB15 | "DAC0"
|
||||
* 67 | PB16 | "DAC1"
|
||||
* 68 | PA1 | "CANRX"
|
||||
* 69 | PA0 | "CANTX"
|
||||
* 70 | PA17 | "SDA1"
|
||||
* 71 | PA18 | "SCL1"
|
||||
* 72 | PC30 | LED AMBER "RX"
|
||||
* 73 | PA21 | LED AMBER "TX"
|
||||
* 74 MISO | PA25 |
|
||||
* 75 MOSI | PA26 |
|
||||
* 76 SCLK | PA27 |
|
||||
* 77 NPCS0 | PA28 |
|
||||
* 78 NPCS3 | PB23 | unconnected!
|
||||
*
|
||||
* USB pin | PORT
|
||||
* ----------------+--------
|
||||
* ID | PB11
|
||||
* VBOF | PB10
|
||||
*
|
||||
*/
|
64
Marlin/src/HAL/DUE/spi_pins.h
Normal file
64
Marlin/src/HAL/DUE/spi_pins.h
Normal file
@ -0,0 +1,64 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Define SPI Pins: SCK, MISO, MOSI, SS
|
||||
*
|
||||
* Available chip select pins for HW SPI are 4 10 52 77
|
||||
*/
|
||||
#if SDSS == 4 || SDSS == 10 || SDSS == 52 || SDSS == 77 || SDSS == 87
|
||||
#if SDSS == 4
|
||||
#define SPI_PIN 87
|
||||
#define SPI_CHAN 1
|
||||
#elif SDSS == 10
|
||||
#define SPI_PIN 77
|
||||
#define SPI_CHAN 0
|
||||
#elif SDSS == 52
|
||||
#define SPI_PIN 86
|
||||
#define SPI_CHAN 2
|
||||
#elif SDSS == 77
|
||||
#define SPI_PIN 77
|
||||
#define SPI_CHAN 0
|
||||
#else
|
||||
#define SPI_PIN 87
|
||||
#define SPI_CHAN 1
|
||||
#endif
|
||||
#define SCK_PIN 76
|
||||
#define MISO_PIN 74
|
||||
#define MOSI_PIN 75
|
||||
#else
|
||||
// defaults
|
||||
#define DUE_SOFTWARE_SPI
|
||||
#ifndef SCK_PIN
|
||||
#define SCK_PIN 52
|
||||
#endif
|
||||
#ifndef MISO_PIN
|
||||
#define MISO_PIN 50
|
||||
#endif
|
||||
#ifndef MOSI_PIN
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* A.28, A.29, B.21, C.26, C.29 */
|
||||
#define SS_PIN SDSS
|
136
Marlin/src/HAL/DUE/timers.cpp
Normal file
136
Marlin/src/HAL/DUE/timers.cpp
Normal file
@ -0,0 +1,136 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
// ------------------------
|
||||
// Includes
|
||||
// ------------------------
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
|
||||
#include "timers.h"
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
// ------------------------
|
||||
|
||||
#define NUM_HARDWARE_TIMERS 9
|
||||
|
||||
// ------------------------
|
||||
// Private Variables
|
||||
// ------------------------
|
||||
|
||||
const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
|
||||
{ TC0, 0, TC0_IRQn, 3}, // 0 - [servo timer5]
|
||||
{ TC0, 1, TC1_IRQn, 0}, // 1
|
||||
{ TC0, 2, TC2_IRQn, 2}, // 2 - stepper
|
||||
{ TC1, 0, TC3_IRQn, 0}, // 3 - stepper for BOARD_ARCHIM1
|
||||
{ TC1, 1, TC4_IRQn, 15}, // 4 - temperature
|
||||
{ TC1, 2, TC5_IRQn, 3}, // 5 - [servo timer3]
|
||||
{ TC2, 0, TC6_IRQn, 14}, // 6 - tone
|
||||
{ TC2, 1, TC7_IRQn, 0}, // 7
|
||||
{ TC2, 2, TC8_IRQn, 0}, // 8
|
||||
};
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
/*
|
||||
Timer_clock1: Prescaler 2 -> 42MHz
|
||||
Timer_clock2: Prescaler 8 -> 10.5MHz
|
||||
Timer_clock3: Prescaler 32 -> 2.625MHz
|
||||
Timer_clock4: Prescaler 128 -> 656.25kHz
|
||||
*/
|
||||
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
Tc *tc = TimerConfig[timer_num].pTimerRegs;
|
||||
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
||||
uint32_t channel = TimerConfig[timer_num].channel;
|
||||
|
||||
// Disable interrupt, just in case it was already enabled
|
||||
NVIC_DisableIRQ(irq);
|
||||
|
||||
// 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();
|
||||
|
||||
// Disable timer interrupt
|
||||
tc->TC_CHANNEL[channel].TC_IDR = TC_IDR_CPCS;
|
||||
|
||||
// Stop timer, just in case, to be able to reconfigure it
|
||||
TC_Stop(tc, channel);
|
||||
|
||||
pmc_set_writeprotect(false);
|
||||
pmc_enable_periph_clk((uint32_t)irq);
|
||||
NVIC_SetPriority(irq, TimerConfig [timer_num].priority);
|
||||
|
||||
// wave mode, reset counter on match with RC,
|
||||
TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
|
||||
|
||||
// Set compare value
|
||||
TC_SetRC(tc, channel, VARIANT_MCK / 2 / frequency);
|
||||
|
||||
// And start timer
|
||||
TC_Start(tc, channel);
|
||||
|
||||
// enable interrupt on RC compare
|
||||
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPCS;
|
||||
|
||||
// Finally, enable IRQ
|
||||
NVIC_EnableIRQ(irq);
|
||||
}
|
||||
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
|
||||
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
||||
NVIC_EnableIRQ(irq);
|
||||
}
|
||||
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
|
||||
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
||||
NVIC_DisableIRQ(irq);
|
||||
|
||||
// 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();
|
||||
}
|
||||
|
||||
// missing from CMSIS: Check if interrupt is enabled or not
|
||||
static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) {
|
||||
return (NVIC->ISER[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) != 0;
|
||||
}
|
||||
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
|
||||
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
||||
return NVIC_GetEnabledIRQ(irq);
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
120
Marlin/src/HAL/DUE/timers.h
Normal file
120
Marlin/src/HAL/DUE/timers.h
Normal file
@ -0,0 +1,120 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
||||
|
||||
#define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals
|
||||
|
||||
#ifndef STEP_TIMER_NUM
|
||||
#define STEP_TIMER_NUM 2 // index of timer to use for stepper
|
||||
#endif
|
||||
#define TEMP_TIMER_NUM 4 // index of timer to use for temperature
|
||||
#define PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
#define TONE_TIMER_NUM 6 // index of timer to use for beeper tones
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
|
||||
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
#define HAL_STEP_TIMER_ISR() void TC2_Handler()
|
||||
#endif
|
||||
#define HAL_TEMP_TIMER_ISR() void TC4_Handler()
|
||||
#define HAL_TONE_TIMER_ISR() void TC6_Handler()
|
||||
|
||||
// ------------------------
|
||||
// Types
|
||||
// ------------------------
|
||||
|
||||
typedef struct {
|
||||
Tc *pTimerRegs;
|
||||
uint16_t channel;
|
||||
IRQn_Type IRQ_Id;
|
||||
uint8_t priority;
|
||||
} tTimerConfig;
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
extern const tTimerConfig TimerConfig[];
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
|
||||
|
||||
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
|
||||
const tTimerConfig * const pConfig = &TimerConfig[timer_num];
|
||||
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = compare;
|
||||
}
|
||||
|
||||
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
|
||||
const tTimerConfig * const pConfig = &TimerConfig[timer_num];
|
||||
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
|
||||
}
|
||||
|
||||
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
const tTimerConfig * const pConfig = &TimerConfig[timer_num];
|
||||
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
|
||||
}
|
||||
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer_num);
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num);
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
|
||||
|
||||
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
|
||||
const tTimerConfig * const pConfig = &TimerConfig[timer_num];
|
||||
// Reading the status register clears the interrupt flag
|
||||
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
|
||||
}
|
||||
|
||||
#define HAL_timer_isr_epilogue(TIMER_NUM)
|
97
Marlin/src/HAL/DUE/usb/arduino_due_x.h
Normal file
97
Marlin/src/HAL/DUE/usb/arduino_due_x.h
Normal file
@ -0,0 +1,97 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Arduino Due/X Board Definition.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page arduino_due_x_opfreq "Arduino Due/X - Operating frequencies"
|
||||
* This page lists several definition related to the board operating frequency
|
||||
*
|
||||
* \section Definitions
|
||||
* - \ref BOARD_FREQ_*
|
||||
* - \ref BOARD_MCK
|
||||
*/
|
||||
|
||||
/*! Board oscillator settings */
|
||||
#define BOARD_FREQ_SLCK_XTAL (32768U)
|
||||
#define BOARD_FREQ_SLCK_BYPASS (32768U)
|
||||
#define BOARD_FREQ_MAINCK_XTAL (12000000U)
|
||||
#define BOARD_FREQ_MAINCK_BYPASS (12000000U)
|
||||
|
||||
/*! Master clock frequency */
|
||||
#define BOARD_MCK CHIP_FREQ_CPU_MAX
|
||||
#define BOARD_NO_32K_XTAL
|
||||
|
||||
/** board main clock xtal startup time */
|
||||
#define BOARD_OSC_STARTUP_US 15625
|
||||
|
||||
/* ------------------------------------------------------------------------ */
|
||||
|
||||
/**
|
||||
* \page arduino_due_x_board_info "Arduino Due/X - Board informations"
|
||||
* This page lists several definition related to the board description.
|
||||
*
|
||||
*/
|
||||
|
||||
/* ------------------------------------------------------------------------ */
|
||||
/* USB */
|
||||
/* ------------------------------------------------------------------------ */
|
||||
/*! USB OTG VBus On/Off: Bus Power Control Port. */
|
||||
#define PIN_UOTGHS_VBOF { PIO_PB10, PIOB, ID_PIOB, PIO_PERIPH_A, PIO_PULLUP }
|
||||
/*! USB OTG Identification: Mini Connector Identification Port. */
|
||||
#define PIN_UOTGHS_ID { PIO_PB11, PIOB, ID_PIOB, PIO_PERIPH_A, PIO_PULLUP }
|
||||
|
||||
/*! Multiplexed pin used for USB_ID: */
|
||||
#define USB_ID PIO_PB11_IDX
|
||||
#define USB_ID_GPIO (PIO_PB11_IDX)
|
||||
#define USB_ID_FLAGS (PIO_PERIPH_A | PIO_DEFAULT)
|
||||
/*! Multiplexed pin used for USB_VBOF: */
|
||||
#define USB_VBOF PIO_PB10_IDX
|
||||
#define USB_VBOF_GPIO (PIO_PB10_IDX)
|
||||
#define USB_VBOF_FLAGS (PIO_PERIPH_A | PIO_DEFAULT)
|
||||
/*! Active level of the USB_VBOF output pin. */
|
||||
#define USB_VBOF_ACTIVE_LEVEL LOW
|
||||
/* ------------------------------------------------------------------------ */
|
1151
Marlin/src/HAL/DUE/usb/compiler.h
Normal file
1151
Marlin/src/HAL/DUE/usb/compiler.h
Normal file
File diff suppressed because it is too large
Load Diff
116
Marlin/src/HAL/DUE/usb/conf_access.h
Normal file
116
Marlin/src/HAL/DUE/usb/conf_access.h
Normal file
@ -0,0 +1,116 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Memory access control configuration file.
|
||||
*
|
||||
* Copyright (c) 2012-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _CONF_ACCESS_H_
|
||||
#define _CONF_ACCESS_H_
|
||||
|
||||
#include "compiler.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
/*! \name Activation of Logical Unit Numbers
|
||||
*/
|
||||
//! @{
|
||||
|
||||
#define LUN_0 ENABLE //!< SD/MMC Card over MCI Slot 0.
|
||||
#define LUN_1 DISABLE
|
||||
#define LUN_2 DISABLE
|
||||
#define LUN_3 DISABLE
|
||||
#define LUN_4 DISABLE
|
||||
#define LUN_5 DISABLE
|
||||
#define LUN_6 DISABLE
|
||||
#define LUN_7 DISABLE
|
||||
#define LUN_USB DISABLE
|
||||
//! @}
|
||||
|
||||
/*! \name LUN 0 Definitions
|
||||
*/
|
||||
//! @{
|
||||
#define SD_MMC_SPI_MEM LUN_0
|
||||
#define LUN_ID_SD_MMC_SPI_MEM LUN_ID_0
|
||||
#define LUN_0_INCLUDE "sd_mmc_spi_mem.h"
|
||||
#define Lun_0_test_unit_ready sd_mmc_spi_test_unit_ready
|
||||
#define Lun_0_read_capacity sd_mmc_spi_read_capacity
|
||||
#define Lun_0_unload sd_mmc_spi_unload
|
||||
#define Lun_0_wr_protect sd_mmc_spi_wr_protect
|
||||
#define Lun_0_removal sd_mmc_spi_removal
|
||||
#define Lun_0_usb_read_10 sd_mmc_spi_usb_read_10
|
||||
#define Lun_0_usb_write_10 sd_mmc_spi_usb_write_10
|
||||
#define LUN_0_NAME "\"SD/MMC Card\""
|
||||
//! @}
|
||||
|
||||
|
||||
/*! \name Actions Associated with Memory Accesses
|
||||
*
|
||||
* Write here the action to associate with each memory access.
|
||||
*
|
||||
* \warning Be careful not to waste time in order not to disturb the functions.
|
||||
*/
|
||||
//! @{
|
||||
#define memory_start_read_action(nb_sectors)
|
||||
#define memory_stop_read_action()
|
||||
#define memory_start_write_action(nb_sectors)
|
||||
#define memory_stop_write_action()
|
||||
//! @}
|
||||
|
||||
/*! \name Activation of Interface Features
|
||||
*/
|
||||
//! @{
|
||||
#define ACCESS_USB true //!< MEM <-> USB interface.
|
||||
#define ACCESS_MEM_TO_RAM false //!< MEM <-> RAM interface.
|
||||
#define ACCESS_STREAM false //!< Streaming MEM <-> MEM interface.
|
||||
#define ACCESS_STREAM_RECORD false //!< Streaming MEM <-> MEM interface in record mode.
|
||||
#define ACCESS_MEM_TO_MEM false //!< MEM <-> MEM interface.
|
||||
#define ACCESS_CODEC false //!< Codec interface.
|
||||
//! @}
|
||||
|
||||
/*! \name Specific Options for Access Control
|
||||
*/
|
||||
//! @{
|
||||
#define GLOBAL_WR_PROTECT false //!< Management of a global write protection.
|
||||
//! @}
|
||||
|
||||
|
||||
#endif // _CONF_ACCESS_H_
|
100
Marlin/src/HAL/DUE/usb/conf_clock.h
Normal file
100
Marlin/src/HAL/DUE/usb/conf_clock.h
Normal file
@ -0,0 +1,100 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief SAM3X clock configuration.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef CONF_CLOCK_H_INCLUDED
|
||||
#define CONF_CLOCK_H_INCLUDED
|
||||
|
||||
// ===== System Clock (MCK) Source Options
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_SLCK_RC
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_SLCK_XTAL
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_SLCK_BYPASS
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_8M_RC
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_12M_RC
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_XTAL
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_BYPASS
|
||||
#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK
|
||||
//#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_UPLLCK
|
||||
|
||||
// ===== System Clock (MCK) Prescaler Options (Fmck = Fsys / (SYSCLK_PRES))
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_1
|
||||
#define CONFIG_SYSCLK_PRES SYSCLK_PRES_2
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_4
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_8
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_16
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_32
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_64
|
||||
//#define CONFIG_SYSCLK_PRES SYSCLK_PRES_3
|
||||
|
||||
// ===== PLL0 (A) Options (Fpll = (Fclk * PLL_mul) / PLL_div)
|
||||
// Use mul and div effective values here.
|
||||
#define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL
|
||||
#define CONFIG_PLL0_MUL 14
|
||||
#define CONFIG_PLL0_DIV 1
|
||||
|
||||
// ===== UPLL (UTMI) Hardware fixed at 480MHz.
|
||||
|
||||
// ===== USB Clock Source Options (Fusb = FpllX / USB_div)
|
||||
// Use div effective value here.
|
||||
//#define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL0
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL
|
||||
#define CONFIG_USBCLK_DIV 1
|
||||
|
||||
// ===== Target frequency (System clock)
|
||||
// - XTAL frequency: 12MHz
|
||||
// - System clock source: PLLA
|
||||
// - System clock prescaler: 2 (divided by 2)
|
||||
// - PLLA source: XTAL
|
||||
// - PLLA output: XTAL * 14 / 1
|
||||
// - System clock is: 12 * 14 / 1 /2 = 84MHz
|
||||
// ===== Target frequency (USB Clock)
|
||||
// - USB clock source: UPLL
|
||||
// - USB clock divider: 1 (not divided)
|
||||
// - UPLL frequency: 480MHz
|
||||
// - USB clock: 480 / 1 = 480MHz
|
||||
|
||||
|
||||
#endif /* CONF_CLOCK_H_INCLUDED */
|
300
Marlin/src/HAL/DUE/usb/conf_usb.h
Normal file
300
Marlin/src/HAL/DUE/usb/conf_usb.h
Normal file
@ -0,0 +1,300 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB configuration file
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _CONF_USB_H_
|
||||
#define _CONF_USB_H_
|
||||
|
||||
#undef UNUSED /* To avoid a macro clash as macros.h already defines it */
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
#include "compiler.h"
|
||||
|
||||
/**
|
||||
* USB Device Configuration
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Device definition (mandatory)
|
||||
#define USB_DEVICE_MAJOR_VERSION 1
|
||||
#define USB_DEVICE_MINOR_VERSION 0
|
||||
#define USB_DEVICE_POWER 100 // Consumption on Vbus line (mA)
|
||||
#define USB_DEVICE_ATTR \
|
||||
(USB_CONFIG_ATTR_SELF_POWERED)
|
||||
// (USB_CONFIG_ATTR_BUS_POWERED)
|
||||
// (USB_CONFIG_ATTR_REMOTE_WAKEUP|USB_CONFIG_ATTR_SELF_POWERED)
|
||||
// (USB_CONFIG_ATTR_REMOTE_WAKEUP|USB_CONFIG_ATTR_BUS_POWERED)
|
||||
|
||||
/**
|
||||
* Device speeds support
|
||||
* Low speed not supported by CDC and MSC
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! To define a Low speed device
|
||||
//#define USB_DEVICE_LOW_SPEED
|
||||
|
||||
//! To define a Full speed device
|
||||
//#define USB_DEVICE_FULL_SPEED
|
||||
|
||||
#if MB(ARCHIM1)
|
||||
#define USB_DEVICE_FULL_SPEED
|
||||
#endif
|
||||
|
||||
//! To authorize the High speed
|
||||
#ifndef USB_DEVICE_FULL_SPEED
|
||||
#if (UC3A3||UC3A4)
|
||||
#define USB_DEVICE_HS_SUPPORT
|
||||
#elif (SAM3XA||SAM3U)
|
||||
#define USB_DEVICE_HS_SUPPORT
|
||||
#endif
|
||||
#endif
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* USB Device Callbacks definitions (Optional)
|
||||
* @{
|
||||
*/
|
||||
#define UDC_VBUS_EVENT(b_vbus_high)
|
||||
#define UDC_SOF_EVENT()
|
||||
#define UDC_SUSPEND_EVENT()
|
||||
#define UDC_RESUME_EVENT()
|
||||
#define UDC_GET_EXTRA_STRING() usb_task_extra_string()
|
||||
#define USB_DEVICE_SPECIFIC_REQUEST() usb_task_other_requests()
|
||||
//@}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
/**
|
||||
* USB Device low level configuration
|
||||
* When only one interface is used, these configurations are defined by the class module.
|
||||
* For composite device, these configuration must be defined here
|
||||
* @{
|
||||
*/
|
||||
//! Control endpoint size
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
|
||||
//! Two interfaces for this device (CDC COM + CDC DATA + MSC)
|
||||
#define USB_DEVICE_NB_INTERFACE 3
|
||||
|
||||
//! 5 endpoints used by CDC and MSC interfaces
|
||||
#if SAM3U
|
||||
// (3 | USB_EP_DIR_IN) // CDC Notify endpoint
|
||||
// (6 | USB_EP_DIR_IN) // CDC TX
|
||||
// (5 | USB_EP_DIR_OUT) // CDC RX
|
||||
// (1 | USB_EP_DIR_IN) // MSC IN
|
||||
// (2 | USB_EP_DIR_OUT) // MSC OUT
|
||||
# define USB_DEVICE_MAX_EP 6
|
||||
# if defined(USB_DEVICE_HS_SUPPORT)
|
||||
// In HS mode, size of bulk endpoints are 512
|
||||
// If CDC and MSC endpoints all uses 2 banks, DPRAM is not enough: 4 bulk
|
||||
// endpoints requires 4K bytes. So reduce the number of banks of CDC bulk
|
||||
// endpoints to use less DPRAM. Keep MSC setting to keep MSC performance.
|
||||
# define UDD_BULK_NB_BANK(ep) ((ep == 5 || ep== 6) ? 1 : 2)
|
||||
#endif
|
||||
#else
|
||||
// (3 | USB_EP_DIR_IN) // CDC Notify endpoint
|
||||
// (4 | USB_EP_DIR_IN) // CDC TX
|
||||
// (5 | USB_EP_DIR_OUT) // CDC RX
|
||||
// (1 | USB_EP_DIR_IN) // MSC IN
|
||||
// (2 | USB_EP_DIR_OUT) // MSC OUT
|
||||
# define USB_DEVICE_MAX_EP 5
|
||||
# if SAM3XA && defined(USB_DEVICE_HS_SUPPORT)
|
||||
// In HS mode, size of bulk endpoints are 512
|
||||
// If CDC and MSC endpoints all uses 2 banks, DPRAM is not enough: 4 bulk
|
||||
// endpoints requires 4K bytes. So reduce the number of banks of CDC bulk
|
||||
// endpoints to use less DPRAM. Keep MSC setting to keep MSC performance.
|
||||
# define UDD_BULK_NB_BANK(ep) ((ep == 4 || ep== 5) ? 1 : 2)
|
||||
# endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//@}
|
||||
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* USB Interface Configuration
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* Configuration of CDC interface
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Define one USB communication ports
|
||||
#define UDI_CDC_PORT_NB 1
|
||||
|
||||
//! Interface callback definition
|
||||
#define UDI_CDC_ENABLE_EXT(port) usb_task_cdc_enable(port)
|
||||
#define UDI_CDC_DISABLE_EXT(port) usb_task_cdc_disable(port)
|
||||
#define UDI_CDC_RX_NOTIFY(port) usb_task_cdc_rx_notify(port)
|
||||
#define UDI_CDC_TX_EMPTY_NOTIFY(port)
|
||||
#define UDI_CDC_SET_CODING_EXT(port,cfg) usb_task_cdc_config(port,cfg)
|
||||
#define UDI_CDC_SET_DTR_EXT(port,set) usb_task_cdc_set_dtr(port,set)
|
||||
#define UDI_CDC_SET_RTS_EXT(port,set)
|
||||
|
||||
//! Define it when the transfer CDC Device to Host is a low rate (<512000 bauds)
|
||||
//! to reduce CDC buffers size
|
||||
//#define UDI_CDC_LOW_RATE
|
||||
|
||||
//! Default configuration of communication port
|
||||
#define UDI_CDC_DEFAULT_RATE 115200
|
||||
#define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1
|
||||
#define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE
|
||||
#define UDI_CDC_DEFAULT_DATABITS 8
|
||||
|
||||
//! Enable id string of interface to add an extra USB string
|
||||
#define UDI_CDC_IAD_STRING_ID 4
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
/**
|
||||
* USB CDC low level configuration
|
||||
* In standalone these configurations are defined by the CDC module.
|
||||
* For composite device, these configuration must be defined here
|
||||
* @{
|
||||
*/
|
||||
//! Endpoint numbers definition
|
||||
#if SAM3U
|
||||
# define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint
|
||||
# define UDI_CDC_DATA_EP_IN_0 (6 | USB_EP_DIR_IN) // TX
|
||||
# define UDI_CDC_DATA_EP_OUT_0 (5 | USB_EP_DIR_OUT)// RX
|
||||
#else
|
||||
# define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint
|
||||
# define UDI_CDC_DATA_EP_IN_0 (4 | USB_EP_DIR_IN) // TX
|
||||
# define UDI_CDC_DATA_EP_OUT_0 (5 | USB_EP_DIR_OUT)// RX
|
||||
#endif
|
||||
|
||||
//! Interface numbers
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_0 0
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_0 1
|
||||
|
||||
//@}
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* Configuration of MSC interface
|
||||
* @{
|
||||
*/
|
||||
//! Vendor name and Product version of MSC interface
|
||||
#define UDI_MSC_GLOBAL_VENDOR_ID \
|
||||
'M', 'A', 'R', 'L', 'I', 'N', '3', 'D'
|
||||
#define UDI_MSC_GLOBAL_PRODUCT_VERSION \
|
||||
'1', '.', '0', '0'
|
||||
|
||||
//! Interface callback definition
|
||||
#define UDI_MSC_ENABLE_EXT() usb_task_msc_enable()
|
||||
#define UDI_MSC_DISABLE_EXT() usb_task_msc_disable()
|
||||
|
||||
//! Enable id string of interface to add an extra USB string
|
||||
#define UDI_MSC_STRING_ID 5
|
||||
|
||||
/**
|
||||
* USB MSC low level configuration
|
||||
* In standalone these configurations are defined by the MSC module.
|
||||
* For composite device, these configuration must be defined here
|
||||
* @{
|
||||
*/
|
||||
//! Endpoint numbers definition
|
||||
#define UDI_MSC_EP_IN (1 | USB_EP_DIR_IN)
|
||||
#define UDI_MSC_EP_OUT (2 | USB_EP_DIR_OUT)
|
||||
|
||||
//! Interface number
|
||||
#define UDI_MSC_IFACE_NUMBER 2
|
||||
//@}
|
||||
//@}
|
||||
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* Description of Composite Device
|
||||
* @{
|
||||
*/
|
||||
//! USB Interfaces descriptor structure
|
||||
#define UDI_COMPOSITE_DESC_T \
|
||||
usb_iad_desc_t udi_cdc_iad; \
|
||||
udi_cdc_comm_desc_t udi_cdc_comm; \
|
||||
udi_cdc_data_desc_t udi_cdc_data; \
|
||||
udi_msc_desc_t udi_msc
|
||||
|
||||
//! USB Interfaces descriptor value for Full Speed
|
||||
#define UDI_COMPOSITE_DESC_FS \
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \
|
||||
.udi_msc = UDI_MSC_DESC_FS
|
||||
|
||||
//! USB Interfaces descriptor value for High Speed
|
||||
#define UDI_COMPOSITE_DESC_HS \
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \
|
||||
.udi_msc = UDI_MSC_DESC_HS
|
||||
|
||||
//! USB Interface APIs
|
||||
#define UDI_COMPOSITE_API \
|
||||
&udi_api_cdc_comm, \
|
||||
&udi_api_cdc_data, \
|
||||
&udi_api_msc
|
||||
//@}
|
||||
|
||||
/**
|
||||
* USB Device Driver Configuration
|
||||
* @{
|
||||
*/
|
||||
//@}
|
||||
|
||||
//! The includes of classes and other headers must be done at the end of this file to avoid compile error
|
||||
#include "udi_cdc.h"
|
||||
#include "udi_msc.h"
|
||||
#else
|
||||
#include "udi_cdc_conf.h"
|
||||
#endif
|
||||
|
||||
#include "usb_task.h"
|
||||
|
||||
#endif // _CONF_USB_H_
|
647
Marlin/src/HAL/DUE/usb/ctrl_access.c
Normal file
647
Marlin/src/HAL/DUE/usb/ctrl_access.c
Normal file
@ -0,0 +1,647 @@
|
||||
/*****************************************************************************
|
||||
*
|
||||
* \file
|
||||
*
|
||||
* \brief Abstraction layer for memory interfaces.
|
||||
*
|
||||
* This module contains the interfaces:
|
||||
* - MEM <-> USB;
|
||||
* - MEM <-> RAM;
|
||||
* - MEM <-> MEM.
|
||||
*
|
||||
* This module may be configured and expanded to support the following features:
|
||||
* - write-protected globals;
|
||||
* - password-protected data;
|
||||
* - specific features;
|
||||
* - etc.
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
//_____ I N C L U D E S ____________________________________________________
|
||||
|
||||
#include "compiler.h"
|
||||
#include "preprocessor.h"
|
||||
#ifdef FREERTOS_USED
|
||||
#include "FreeRTOS.h"
|
||||
#include "semphr.h"
|
||||
#endif
|
||||
#include "ctrl_access.h"
|
||||
|
||||
|
||||
//_____ D E F I N I T I O N S ______________________________________________
|
||||
|
||||
#ifdef FREERTOS_USED
|
||||
|
||||
/*! \name LUN Access Protection Macros
|
||||
*/
|
||||
//! @{
|
||||
|
||||
/*! \brief Locks accesses to LUNs.
|
||||
*
|
||||
* \return \c true if the access was successfully locked, else \c false.
|
||||
*/
|
||||
#define Ctrl_access_lock() ctrl_access_lock()
|
||||
|
||||
/*! \brief Unlocks accesses to LUNs.
|
||||
*/
|
||||
#define Ctrl_access_unlock() xSemaphoreGive(ctrl_access_semphr)
|
||||
|
||||
//! @}
|
||||
|
||||
//! Handle to the semaphore protecting accesses to LUNs.
|
||||
static xSemaphoreHandle ctrl_access_semphr = NULL;
|
||||
|
||||
#else
|
||||
|
||||
/*! \name LUN Access Protection Macros
|
||||
*/
|
||||
//! @{
|
||||
|
||||
/*! \brief Locks accesses to LUNs.
|
||||
*
|
||||
* \return \c true if the access was successfully locked, else \c false.
|
||||
*/
|
||||
#define Ctrl_access_lock() true
|
||||
|
||||
/*! \brief Unlocks accesses to LUNs.
|
||||
*/
|
||||
#define Ctrl_access_unlock()
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // FREERTOS_USED
|
||||
|
||||
|
||||
#if MAX_LUN
|
||||
|
||||
/*! \brief Initializes an entry of the LUN descriptor table.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return LUN descriptor table entry initializer.
|
||||
*/
|
||||
#if ACCESS_USB == true && ACCESS_MEM_TO_RAM == true
|
||||
#define Lun_desc_entry(lun) \
|
||||
{\
|
||||
TPASTE3(Lun_, lun, _test_unit_ready),\
|
||||
TPASTE3(Lun_, lun, _read_capacity),\
|
||||
TPASTE3(Lun_, lun, _unload),\
|
||||
TPASTE3(Lun_, lun, _wr_protect),\
|
||||
TPASTE3(Lun_, lun, _removal),\
|
||||
TPASTE3(Lun_, lun, _usb_read_10),\
|
||||
TPASTE3(Lun_, lun, _usb_write_10),\
|
||||
TPASTE3(Lun_, lun, _mem_2_ram),\
|
||||
TPASTE3(Lun_, lun, _ram_2_mem),\
|
||||
TPASTE3(LUN_, lun, _NAME)\
|
||||
}
|
||||
#elif ACCESS_USB == true
|
||||
#define Lun_desc_entry(lun) \
|
||||
{\
|
||||
TPASTE3(Lun_, lun, _test_unit_ready),\
|
||||
TPASTE3(Lun_, lun, _read_capacity),\
|
||||
TPASTE3(Lun_, lun, _unload),\
|
||||
TPASTE3(Lun_, lun, _wr_protect),\
|
||||
TPASTE3(Lun_, lun, _removal),\
|
||||
TPASTE3(Lun_, lun, _usb_read_10),\
|
||||
TPASTE3(Lun_, lun, _usb_write_10),\
|
||||
TPASTE3(LUN_, lun, _NAME)\
|
||||
}
|
||||
#elif ACCESS_MEM_TO_RAM == true
|
||||
#define Lun_desc_entry(lun) \
|
||||
{\
|
||||
TPASTE3(Lun_, lun, _test_unit_ready),\
|
||||
TPASTE3(Lun_, lun, _read_capacity),\
|
||||
TPASTE3(Lun_, lun, _unload),\
|
||||
TPASTE3(Lun_, lun, _wr_protect),\
|
||||
TPASTE3(Lun_, lun, _removal),\
|
||||
TPASTE3(Lun_, lun, _mem_2_ram),\
|
||||
TPASTE3(Lun_, lun, _ram_2_mem),\
|
||||
TPASTE3(LUN_, lun, _NAME)\
|
||||
}
|
||||
#else
|
||||
#define Lun_desc_entry(lun) \
|
||||
{\
|
||||
TPASTE3(Lun_, lun, _test_unit_ready),\
|
||||
TPASTE3(Lun_, lun, _read_capacity),\
|
||||
TPASTE3(Lun_, lun, _unload),\
|
||||
TPASTE3(Lun_, lun, _wr_protect),\
|
||||
TPASTE3(Lun_, lun, _removal),\
|
||||
TPASTE3(LUN_, lun, _NAME)\
|
||||
}
|
||||
#endif
|
||||
|
||||
//! LUN descriptor table.
|
||||
static const struct
|
||||
{
|
||||
Ctrl_status (*test_unit_ready)(void);
|
||||
Ctrl_status (*read_capacity)(U32 *);
|
||||
bool (*unload)(bool);
|
||||
bool (*wr_protect)(void);
|
||||
bool (*removal)(void);
|
||||
#if ACCESS_USB == true
|
||||
Ctrl_status (*usb_read_10)(U32, U16);
|
||||
Ctrl_status (*usb_write_10)(U32, U16);
|
||||
#endif
|
||||
#if ACCESS_MEM_TO_RAM == true
|
||||
Ctrl_status (*mem_2_ram)(U32, void *);
|
||||
Ctrl_status (*ram_2_mem)(U32, const void *);
|
||||
#endif
|
||||
const char *name;
|
||||
} lun_desc[MAX_LUN] =
|
||||
{
|
||||
#if LUN_0 == ENABLE
|
||||
# ifndef Lun_0_unload
|
||||
# define Lun_0_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(0),
|
||||
#endif
|
||||
#if LUN_1 == ENABLE
|
||||
# ifndef Lun_1_unload
|
||||
# define Lun_1_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(1),
|
||||
#endif
|
||||
#if LUN_2 == ENABLE
|
||||
# ifndef Lun_2_unload
|
||||
# define Lun_2_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(2),
|
||||
#endif
|
||||
#if LUN_3 == ENABLE
|
||||
# ifndef Lun_3_unload
|
||||
# define Lun_3_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(3),
|
||||
#endif
|
||||
#if LUN_4 == ENABLE
|
||||
# ifndef Lun_4_unload
|
||||
# define Lun_4_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(4),
|
||||
#endif
|
||||
#if LUN_5 == ENABLE
|
||||
# ifndef Lun_5_unload
|
||||
# define Lun_5_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(5),
|
||||
#endif
|
||||
#if LUN_6 == ENABLE
|
||||
# ifndef Lun_6_unload
|
||||
# define Lun_6_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(6),
|
||||
#endif
|
||||
#if LUN_7 == ENABLE
|
||||
# ifndef Lun_7_unload
|
||||
# define Lun_7_unload NULL
|
||||
# endif
|
||||
Lun_desc_entry(7)
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
#if GLOBAL_WR_PROTECT == true
|
||||
bool g_wr_protect;
|
||||
#endif
|
||||
|
||||
|
||||
/*! \name Control Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
|
||||
#ifdef FREERTOS_USED
|
||||
|
||||
bool ctrl_access_init(void)
|
||||
{
|
||||
// If the handle to the protecting semaphore is not valid,
|
||||
if (!ctrl_access_semphr)
|
||||
{
|
||||
// try to create the semaphore.
|
||||
vSemaphoreCreateBinary(ctrl_access_semphr);
|
||||
|
||||
// If the semaphore could not be created, there is no backup solution.
|
||||
if (!ctrl_access_semphr) return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
/*! \brief Locks accesses to LUNs.
|
||||
*
|
||||
* \return \c true if the access was successfully locked, else \c false.
|
||||
*/
|
||||
static bool ctrl_access_lock(void)
|
||||
{
|
||||
// If the semaphore could not be created, there is no backup solution.
|
||||
if (!ctrl_access_semphr) return false;
|
||||
|
||||
// Wait for the semaphore.
|
||||
while (!xSemaphoreTake(ctrl_access_semphr, portMAX_DELAY));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // FREERTOS_USED
|
||||
|
||||
|
||||
U8 get_nb_lun(void)
|
||||
{
|
||||
#if MEM_USB == ENABLE
|
||||
# ifndef Lun_usb_get_lun
|
||||
# define Lun_usb_get_lun() host_get_lun()
|
||||
# endif
|
||||
U8 nb_lun;
|
||||
|
||||
if (!Ctrl_access_lock()) return MAX_LUN;
|
||||
|
||||
nb_lun = MAX_LUN + Lun_usb_get_lun();
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return nb_lun;
|
||||
#else
|
||||
return MAX_LUN;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
U8 get_cur_lun(void)
|
||||
{
|
||||
return LUN_ID_0;
|
||||
}
|
||||
|
||||
|
||||
Ctrl_status mem_test_unit_ready(U8 lun)
|
||||
{
|
||||
Ctrl_status status;
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].test_unit_ready() :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_test_unit_ready(lun - LUN_ID_USB);
|
||||
#else
|
||||
CTRL_FAIL;
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector)
|
||||
{
|
||||
Ctrl_status status;
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].read_capacity(u32_nb_sector) :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_read_capacity(lun - LUN_ID_USB, u32_nb_sector);
|
||||
#else
|
||||
CTRL_FAIL;
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
U8 mem_sector_size(U8 lun)
|
||||
{
|
||||
U8 sector_size;
|
||||
|
||||
if (!Ctrl_access_lock()) return 0;
|
||||
|
||||
sector_size =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? 1 :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_read_sector_size(lun - LUN_ID_USB);
|
||||
#else
|
||||
0;
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return sector_size;
|
||||
}
|
||||
|
||||
|
||||
bool mem_unload(U8 lun, bool unload)
|
||||
{
|
||||
bool unloaded;
|
||||
#if !MAX_LUN || !defined(Lun_usb_unload)
|
||||
UNUSED(lun);
|
||||
#endif
|
||||
|
||||
if (!Ctrl_access_lock()) return false;
|
||||
|
||||
unloaded =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ?
|
||||
(lun_desc[lun].unload ?
|
||||
lun_desc[lun].unload(unload) : !unload) :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
# if defined(Lun_usb_unload)
|
||||
Lun_usb_unload(lun - LUN_ID_USB, unload);
|
||||
# else
|
||||
!unload; /* Can not unload: load success, unload fail */
|
||||
# endif
|
||||
#else
|
||||
false; /* No mem, unload/load fail */
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return unloaded;
|
||||
}
|
||||
|
||||
bool mem_wr_protect(U8 lun)
|
||||
{
|
||||
bool wr_protect;
|
||||
|
||||
if (!Ctrl_access_lock()) return true;
|
||||
|
||||
wr_protect =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].wr_protect() :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_wr_protect(lun - LUN_ID_USB);
|
||||
#else
|
||||
true;
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return wr_protect;
|
||||
}
|
||||
|
||||
|
||||
bool mem_removal(U8 lun)
|
||||
{
|
||||
bool removal;
|
||||
#if MAX_LUN==0
|
||||
UNUSED(lun);
|
||||
#endif
|
||||
|
||||
if (!Ctrl_access_lock()) return true;
|
||||
|
||||
removal =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].removal() :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_removal();
|
||||
#else
|
||||
true;
|
||||
#endif
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return removal;
|
||||
}
|
||||
|
||||
|
||||
const char *mem_name(U8 lun)
|
||||
{
|
||||
#if MAX_LUN==0
|
||||
UNUSED(lun);
|
||||
#endif
|
||||
return
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].name :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
LUN_USB_NAME;
|
||||
#else
|
||||
NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
//! @}
|
||||
|
||||
|
||||
#if ACCESS_USB == true
|
||||
|
||||
/*! \name MEM <-> USB Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
|
||||
Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector)
|
||||
{
|
||||
Ctrl_status status;
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
memory_start_read_action(nb_sector);
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].usb_read_10(addr, nb_sector) :
|
||||
#endif
|
||||
CTRL_FAIL;
|
||||
memory_stop_read_action();
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector)
|
||||
{
|
||||
Ctrl_status status;
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
memory_start_write_action(nb_sector);
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].usb_write_10(addr, nb_sector) :
|
||||
#endif
|
||||
CTRL_FAIL;
|
||||
memory_stop_write_action();
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_USB == true
|
||||
|
||||
|
||||
#if ACCESS_MEM_TO_RAM == true
|
||||
|
||||
/*! \name MEM <-> RAM Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
|
||||
Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram)
|
||||
{
|
||||
Ctrl_status status;
|
||||
#if MAX_LUN==0
|
||||
UNUSED(lun);
|
||||
#endif
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
memory_start_read_action(1);
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].mem_2_ram(addr, ram) :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_mem_2_ram(addr, ram);
|
||||
#else
|
||||
CTRL_FAIL;
|
||||
#endif
|
||||
memory_stop_read_action();
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram)
|
||||
{
|
||||
Ctrl_status status;
|
||||
#if MAX_LUN==0
|
||||
UNUSED(lun);
|
||||
#endif
|
||||
|
||||
if (!Ctrl_access_lock()) return CTRL_FAIL;
|
||||
|
||||
memory_start_write_action(1);
|
||||
status =
|
||||
#if MAX_LUN
|
||||
(lun < MAX_LUN) ? lun_desc[lun].ram_2_mem(addr, ram) :
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
Lun_usb_ram_2_mem(addr, ram);
|
||||
#else
|
||||
CTRL_FAIL;
|
||||
#endif
|
||||
memory_stop_write_action();
|
||||
|
||||
Ctrl_access_unlock();
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_MEM_TO_RAM == true
|
||||
|
||||
|
||||
#if ACCESS_STREAM == true
|
||||
|
||||
/*! \name Streaming MEM <-> MEM Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
|
||||
#if ACCESS_MEM_TO_MEM == true
|
||||
|
||||
#include "fat.h"
|
||||
|
||||
Ctrl_status stream_mem_to_mem(U8 src_lun, U32 src_addr, U8 dest_lun, U32 dest_addr, U16 nb_sector)
|
||||
{
|
||||
COMPILER_ALIGNED(4)
|
||||
static U8 sector_buf[FS_512B];
|
||||
Ctrl_status status = CTRL_GOOD;
|
||||
|
||||
while (nb_sector--)
|
||||
{
|
||||
if ((status = memory_2_ram(src_lun, src_addr++, sector_buf)) != CTRL_GOOD) break;
|
||||
if ((status = ram_2_memory(dest_lun, dest_addr++, sector_buf)) != CTRL_GOOD) break;
|
||||
}
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
#endif // ACCESS_MEM_TO_MEM == true
|
||||
|
||||
|
||||
Ctrl_status stream_state(U8 id)
|
||||
{
|
||||
UNUSED(id);
|
||||
return CTRL_GOOD;
|
||||
}
|
||||
|
||||
|
||||
U16 stream_stop(U8 id)
|
||||
{
|
||||
UNUSED(id);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_STREAM
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
402
Marlin/src/HAL/DUE/usb/ctrl_access.h
Normal file
402
Marlin/src/HAL/DUE/usb/ctrl_access.h
Normal file
@ -0,0 +1,402 @@
|
||||
/*****************************************************************************
|
||||
*
|
||||
* \file
|
||||
*
|
||||
* \brief Abstraction layer for memory interfaces.
|
||||
*
|
||||
* This module contains the interfaces:
|
||||
* - MEM <-> USB;
|
||||
* - MEM <-> RAM;
|
||||
* - MEM <-> MEM.
|
||||
*
|
||||
* This module may be configured and expanded to support the following features:
|
||||
* - write-protected globals;
|
||||
* - password-protected data;
|
||||
* - specific features;
|
||||
* - etc.
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _CTRL_ACCESS_H_
|
||||
#define _CTRL_ACCESS_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \defgroup group_common_services_storage_ctrl_access Memory Control Access
|
||||
*
|
||||
* Common abstraction layer for memory interfaces. It provides interfaces between:
|
||||
* Memory and USB, Memory and RAM, Memory and Memory. Common API for XMEGA and UC3.
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
#include "compiler.h"
|
||||
#include "conf_access.h"
|
||||
|
||||
#ifndef SECTOR_SIZE
|
||||
#define SECTOR_SIZE 512
|
||||
#endif
|
||||
|
||||
//! Status returned by CTRL_ACCESS interfaces.
|
||||
typedef enum
|
||||
{
|
||||
CTRL_GOOD = PASS, //!< Success, memory ready.
|
||||
CTRL_FAIL = FAIL, //!< An error occurred.
|
||||
CTRL_NO_PRESENT = FAIL + 1, //!< Memory unplugged.
|
||||
CTRL_BUSY = FAIL + 2 //!< Memory not initialized or changed.
|
||||
} Ctrl_status;
|
||||
|
||||
|
||||
// FYI: Each Logical Unit Number (LUN) corresponds to a memory.
|
||||
|
||||
// Check LUN defines.
|
||||
#ifndef LUN_0
|
||||
#error LUN_0 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_1
|
||||
#error LUN_1 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_2
|
||||
#error LUN_2 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_3
|
||||
#error LUN_3 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_4
|
||||
#error LUN_4 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_5
|
||||
#error LUN_5 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_6
|
||||
#error LUN_6 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_7
|
||||
#error LUN_7 must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
#ifndef LUN_USB
|
||||
#error LUN_USB must be defined as ENABLE or DISABLE in conf_access.h
|
||||
#endif
|
||||
|
||||
/*! \name LUN IDs
|
||||
*/
|
||||
//! @{
|
||||
#define LUN_ID_0 (0) //!< First static LUN.
|
||||
#define LUN_ID_1 (LUN_ID_0 + LUN_0)
|
||||
#define LUN_ID_2 (LUN_ID_1 + LUN_1)
|
||||
#define LUN_ID_3 (LUN_ID_2 + LUN_2)
|
||||
#define LUN_ID_4 (LUN_ID_3 + LUN_3)
|
||||
#define LUN_ID_5 (LUN_ID_4 + LUN_4)
|
||||
#define LUN_ID_6 (LUN_ID_5 + LUN_5)
|
||||
#define LUN_ID_7 (LUN_ID_6 + LUN_6)
|
||||
#define MAX_LUN (LUN_ID_7 + LUN_7) //!< Number of static LUNs.
|
||||
#define LUN_ID_USB (MAX_LUN) //!< First dynamic LUN (USB host mass storage).
|
||||
//! @}
|
||||
|
||||
|
||||
// Include LUN header files.
|
||||
#if LUN_0 == ENABLE
|
||||
#include LUN_0_INCLUDE
|
||||
#endif
|
||||
#if LUN_1 == ENABLE
|
||||
#include LUN_1_INCLUDE
|
||||
#endif
|
||||
#if LUN_2 == ENABLE
|
||||
#include LUN_2_INCLUDE
|
||||
#endif
|
||||
#if LUN_3 == ENABLE
|
||||
#include LUN_3_INCLUDE
|
||||
#endif
|
||||
#if LUN_4 == ENABLE
|
||||
#include LUN_4_INCLUDE
|
||||
#endif
|
||||
#if LUN_5 == ENABLE
|
||||
#include LUN_5_INCLUDE
|
||||
#endif
|
||||
#if LUN_6 == ENABLE
|
||||
#include LUN_6_INCLUDE
|
||||
#endif
|
||||
#if LUN_7 == ENABLE
|
||||
#include LUN_7_INCLUDE
|
||||
#endif
|
||||
#if LUN_USB == ENABLE
|
||||
#include LUN_USB_INCLUDE
|
||||
#endif
|
||||
|
||||
|
||||
// Check the configuration of write protection in conf_access.h.
|
||||
#ifndef GLOBAL_WR_PROTECT
|
||||
#error GLOBAL_WR_PROTECT must be defined as true or false in conf_access.h
|
||||
#endif
|
||||
|
||||
|
||||
#if GLOBAL_WR_PROTECT == true
|
||||
|
||||
//! Write protect.
|
||||
extern bool g_wr_protect;
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
/*! \name Control Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
#ifdef FREERTOS_USED
|
||||
|
||||
/*! \brief Initializes the LUN access locker.
|
||||
*
|
||||
* \return \c true if the locker was successfully initialized, else \c false.
|
||||
*/
|
||||
extern bool ctrl_access_init(void);
|
||||
|
||||
#endif // FREERTOS_USED
|
||||
|
||||
/*! \brief Returns the number of LUNs.
|
||||
*
|
||||
* \return Number of LUNs in the system.
|
||||
*/
|
||||
extern U8 get_nb_lun(void);
|
||||
|
||||
/*! \brief Returns the current LUN.
|
||||
*
|
||||
* \return Current LUN.
|
||||
*
|
||||
* \todo Implement.
|
||||
*/
|
||||
extern U8 get_cur_lun(void);
|
||||
|
||||
/*! \brief Tests the memory state and initializes the memory if required.
|
||||
*
|
||||
* The TEST UNIT READY SCSI primary command allows an application client to poll
|
||||
* a LUN until it is ready without having to allocate memory for returned data.
|
||||
*
|
||||
* This command may be used to check the media status of LUNs with removable
|
||||
* media.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status mem_test_unit_ready(U8 lun);
|
||||
|
||||
/*! \brief Returns the address of the last valid sector (512 bytes) in the
|
||||
* memory.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param u32_nb_sector Pointer to the address of the last valid sector.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector);
|
||||
|
||||
/*! \brief Returns the size of the physical sector.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return Sector size (unit: 512 bytes).
|
||||
*/
|
||||
extern U8 mem_sector_size(U8 lun);
|
||||
|
||||
/*! \brief Unload/load the medium.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param unload \c true to unload the medium, \c false to load the medium.
|
||||
*
|
||||
* \return \c true if unload/load success, else \c false.
|
||||
*/
|
||||
extern bool mem_unload(U8 lun, bool unload);
|
||||
|
||||
/*! \brief Returns the write-protection state of the memory.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return \c true if the memory is write-protected, else \c false.
|
||||
*
|
||||
* \note Only used by removable memories with hardware-specific write
|
||||
* protection.
|
||||
*/
|
||||
extern bool mem_wr_protect(U8 lun);
|
||||
|
||||
/*! \brief Tells whether the memory is removable.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return \c true if the memory is removable, else \c false.
|
||||
*/
|
||||
extern bool mem_removal(U8 lun);
|
||||
|
||||
/*! \brief Returns a pointer to the LUN name.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
*
|
||||
* \return Pointer to the LUN name string.
|
||||
*/
|
||||
extern const char *mem_name(U8 lun);
|
||||
|
||||
//! @}
|
||||
|
||||
|
||||
#if ACCESS_USB == true
|
||||
|
||||
/*! \name MEM <-> USB Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
/*! \brief Transfers data from the memory to USB.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param addr Address of first memory sector to read.
|
||||
* \param nb_sector Number of sectors to transfer.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector);
|
||||
|
||||
/*! \brief Transfers data from USB to the memory.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param addr Address of first memory sector to write.
|
||||
* \param nb_sector Number of sectors to transfer.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector);
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_USB == true
|
||||
|
||||
|
||||
#if ACCESS_MEM_TO_RAM == true
|
||||
|
||||
/*! \name MEM <-> RAM Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
/*! \brief Copies 1 data sector from the memory to RAM.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param addr Address of first memory sector to read.
|
||||
* \param ram Pointer to RAM buffer to write.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram);
|
||||
|
||||
/*! \brief Copies 1 data sector from RAM to the memory.
|
||||
*
|
||||
* \param lun Logical Unit Number.
|
||||
* \param addr Address of first memory sector to write.
|
||||
* \param ram Pointer to RAM buffer to read.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram);
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_MEM_TO_RAM == true
|
||||
|
||||
|
||||
#if ACCESS_STREAM == true
|
||||
|
||||
/*! \name Streaming MEM <-> MEM Interface
|
||||
*/
|
||||
//! @{
|
||||
|
||||
//! Erroneous streaming data transfer ID.
|
||||
#define ID_STREAM_ERR 0xFF
|
||||
|
||||
#if ACCESS_MEM_TO_MEM == true
|
||||
|
||||
/*! \brief Copies data from one memory to another.
|
||||
*
|
||||
* \param src_lun Source Logical Unit Number.
|
||||
* \param src_addr Source address of first memory sector to read.
|
||||
* \param dest_lun Destination Logical Unit Number.
|
||||
* \param dest_addr Destination address of first memory sector to write.
|
||||
* \param nb_sector Number of sectors to copy.
|
||||
*
|
||||
* \return Status.
|
||||
*/
|
||||
extern Ctrl_status stream_mem_to_mem(U8 src_lun, U32 src_addr, U8 dest_lun, U32 dest_addr, U16 nb_sector);
|
||||
|
||||
#endif // ACCESS_MEM_TO_MEM == true
|
||||
|
||||
/*! \brief Returns the state of a streaming data transfer.
|
||||
*
|
||||
* \param id Transfer ID.
|
||||
*
|
||||
* \return Status.
|
||||
*
|
||||
* \todo Implement.
|
||||
*/
|
||||
extern Ctrl_status stream_state(U8 id);
|
||||
|
||||
/*! \brief Stops a streaming data transfer.
|
||||
*
|
||||
* \param id Transfer ID.
|
||||
*
|
||||
* \return Number of remaining sectors.
|
||||
*
|
||||
* \todo Implement.
|
||||
*/
|
||||
extern U16 stream_stop(U8 id);
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // ACCESS_STREAM == true
|
||||
|
||||
/**
|
||||
* \}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // _CTRL_ACCESS_H_
|
278
Marlin/src/HAL/DUE/usb/genclk.h
Normal file
278
Marlin/src/HAL/DUE/usb/genclk.h
Normal file
@ -0,0 +1,278 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Chip-specific generic clock management.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef CHIP_GENCLK_H_INCLUDED
|
||||
#define CHIP_GENCLK_H_INCLUDED
|
||||
|
||||
#include <osc.h>
|
||||
#include <pll.h>
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
/**
|
||||
* \weakgroup genclk_group
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \name Programmable Clock Identifiers (PCK)
|
||||
//@{
|
||||
#define GENCLK_PCK_0 0 //!< PCK0 ID
|
||||
#define GENCLK_PCK_1 1 //!< PCK1 ID
|
||||
#define GENCLK_PCK_2 2 //!< PCK2 ID
|
||||
//@}
|
||||
|
||||
//! \name Programmable Clock Sources (PCK)
|
||||
//@{
|
||||
|
||||
enum genclk_source {
|
||||
GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock
|
||||
GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock
|
||||
GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock
|
||||
GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock
|
||||
};
|
||||
|
||||
//@}
|
||||
|
||||
//! \name Programmable Clock Prescalers (PCK)
|
||||
//@{
|
||||
|
||||
enum genclk_divider {
|
||||
GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1
|
||||
GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2
|
||||
GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4
|
||||
GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8
|
||||
GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16
|
||||
GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32
|
||||
GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64
|
||||
};
|
||||
|
||||
//@}
|
||||
|
||||
struct genclk_config {
|
||||
uint32_t ctrl;
|
||||
};
|
||||
|
||||
static inline void genclk_config_defaults(struct genclk_config *p_cfg,
|
||||
uint32_t ul_id)
|
||||
{
|
||||
ul_id = ul_id;
|
||||
p_cfg->ctrl = 0;
|
||||
}
|
||||
|
||||
static inline void genclk_config_read(struct genclk_config *p_cfg,
|
||||
uint32_t ul_id)
|
||||
{
|
||||
p_cfg->ctrl = PMC->PMC_PCK[ul_id];
|
||||
}
|
||||
|
||||
static inline void genclk_config_write(const struct genclk_config *p_cfg,
|
||||
uint32_t ul_id)
|
||||
{
|
||||
PMC->PMC_PCK[ul_id] = p_cfg->ctrl;
|
||||
}
|
||||
|
||||
//! \name Programmable Clock Source and Prescaler configuration
|
||||
//@{
|
||||
|
||||
static inline void genclk_config_set_source(struct genclk_config *p_cfg,
|
||||
enum genclk_source e_src)
|
||||
{
|
||||
p_cfg->ctrl &= (~PMC_PCK_CSS_Msk);
|
||||
|
||||
switch (e_src) {
|
||||
case GENCLK_PCK_SRC_SLCK_RC:
|
||||
case GENCLK_PCK_SRC_SLCK_XTAL:
|
||||
case GENCLK_PCK_SRC_SLCK_BYPASS:
|
||||
p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK);
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_4M_RC:
|
||||
case GENCLK_PCK_SRC_MAINCK_8M_RC:
|
||||
case GENCLK_PCK_SRC_MAINCK_12M_RC:
|
||||
case GENCLK_PCK_SRC_MAINCK_XTAL:
|
||||
case GENCLK_PCK_SRC_MAINCK_BYPASS:
|
||||
p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK);
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_PLLACK:
|
||||
p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK);
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_PLLBCK:
|
||||
p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK);
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MCK:
|
||||
p_cfg->ctrl |= (PMC_PCK_CSS_MCK);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void genclk_config_set_divider(struct genclk_config *p_cfg,
|
||||
uint32_t e_divider)
|
||||
{
|
||||
p_cfg->ctrl &= ~PMC_PCK_PRES_Msk;
|
||||
p_cfg->ctrl |= e_divider;
|
||||
}
|
||||
|
||||
//@}
|
||||
|
||||
static inline void genclk_enable(const struct genclk_config *p_cfg,
|
||||
uint32_t ul_id)
|
||||
{
|
||||
PMC->PMC_PCK[ul_id] = p_cfg->ctrl;
|
||||
pmc_enable_pck(ul_id);
|
||||
}
|
||||
|
||||
static inline void genclk_disable(uint32_t ul_id)
|
||||
{
|
||||
pmc_disable_pck(ul_id);
|
||||
}
|
||||
|
||||
static inline void genclk_enable_source(enum genclk_source e_src)
|
||||
{
|
||||
switch (e_src) {
|
||||
case GENCLK_PCK_SRC_SLCK_RC:
|
||||
if (!osc_is_ready(OSC_SLCK_32K_RC)) {
|
||||
osc_enable(OSC_SLCK_32K_RC);
|
||||
osc_wait_ready(OSC_SLCK_32K_RC);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_SLCK_XTAL:
|
||||
if (!osc_is_ready(OSC_SLCK_32K_XTAL)) {
|
||||
osc_enable(OSC_SLCK_32K_XTAL);
|
||||
osc_wait_ready(OSC_SLCK_32K_XTAL);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_SLCK_BYPASS:
|
||||
if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) {
|
||||
osc_enable(OSC_SLCK_32K_BYPASS);
|
||||
osc_wait_ready(OSC_SLCK_32K_BYPASS);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_4M_RC:
|
||||
if (!osc_is_ready(OSC_MAINCK_4M_RC)) {
|
||||
osc_enable(OSC_MAINCK_4M_RC);
|
||||
osc_wait_ready(OSC_MAINCK_4M_RC);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_8M_RC:
|
||||
if (!osc_is_ready(OSC_MAINCK_8M_RC)) {
|
||||
osc_enable(OSC_MAINCK_8M_RC);
|
||||
osc_wait_ready(OSC_MAINCK_8M_RC);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_12M_RC:
|
||||
if (!osc_is_ready(OSC_MAINCK_12M_RC)) {
|
||||
osc_enable(OSC_MAINCK_12M_RC);
|
||||
osc_wait_ready(OSC_MAINCK_12M_RC);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_XTAL:
|
||||
if (!osc_is_ready(OSC_MAINCK_XTAL)) {
|
||||
osc_enable(OSC_MAINCK_XTAL);
|
||||
osc_wait_ready(OSC_MAINCK_XTAL);
|
||||
}
|
||||
break;
|
||||
|
||||
case GENCLK_PCK_SRC_MAINCK_BYPASS:
|
||||
if (!osc_is_ready(OSC_MAINCK_BYPASS)) {
|
||||
osc_enable(OSC_MAINCK_BYPASS);
|
||||
osc_wait_ready(OSC_MAINCK_BYPASS);
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_PLL0_SOURCE
|
||||
case GENCLK_PCK_SRC_PLLACK:
|
||||
pll_enable_config_defaults(0);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_PLL1_SOURCE
|
||||
case GENCLK_PCK_SRC_PLLBCK:
|
||||
pll_enable_config_defaults(1);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case GENCLK_PCK_SRC_MCK:
|
||||
break;
|
||||
|
||||
default:
|
||||
Assert(false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
//! @}
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif /* CHIP_GENCLK_H_INCLUDED */
|
339
Marlin/src/HAL/DUE/usb/mrepeat.h
Normal file
339
Marlin/src/HAL/DUE/usb/mrepeat.h
Normal file
@ -0,0 +1,339 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Preprocessor macro repeating utils.
|
||||
*
|
||||
* Copyright (c) 2010-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _MREPEAT_H_
|
||||
#define _MREPEAT_H_
|
||||
|
||||
/**
|
||||
* \defgroup group_sam_utils_mrepeat Preprocessor - Macro Repeat
|
||||
*
|
||||
* \ingroup group_sam_utils
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
#include "preprocessor.h"
|
||||
|
||||
|
||||
//! Maximal number of repetitions supported by MREPEAT.
|
||||
#define MREPEAT_LIMIT 256
|
||||
|
||||
/*! \brief Macro repeat.
|
||||
*
|
||||
* This macro represents a horizontal repetition construct.
|
||||
*
|
||||
* \param count The number of repetitious calls to macro. Valid values range from 0 to MREPEAT_LIMIT.
|
||||
* \param macro A binary operation of the form macro(n, data). This macro is expanded by MREPEAT with
|
||||
* the current repetition number and the auxiliary data argument.
|
||||
* \param data Auxiliary data passed to macro.
|
||||
*
|
||||
* \return <tt>macro(0, data) macro(1, data) ... macro(count - 1, data)</tt>
|
||||
*/
|
||||
#define MREPEAT(count, macro, data) TPASTE2(MREPEAT, count)(macro, data)
|
||||
|
||||
#define MREPEAT0( macro, data)
|
||||
#define MREPEAT1( macro, data) MREPEAT0( macro, data) macro( 0, data)
|
||||
#define MREPEAT2( macro, data) MREPEAT1( macro, data) macro( 1, data)
|
||||
#define MREPEAT3( macro, data) MREPEAT2( macro, data) macro( 2, data)
|
||||
#define MREPEAT4( macro, data) MREPEAT3( macro, data) macro( 3, data)
|
||||
#define MREPEAT5( macro, data) MREPEAT4( macro, data) macro( 4, data)
|
||||
#define MREPEAT6( macro, data) MREPEAT5( macro, data) macro( 5, data)
|
||||
#define MREPEAT7( macro, data) MREPEAT6( macro, data) macro( 6, data)
|
||||
#define MREPEAT8( macro, data) MREPEAT7( macro, data) macro( 7, data)
|
||||
#define MREPEAT9( macro, data) MREPEAT8( macro, data) macro( 8, data)
|
||||
#define MREPEAT10( macro, data) MREPEAT9( macro, data) macro( 9, data)
|
||||
#define MREPEAT11( macro, data) MREPEAT10( macro, data) macro( 10, data)
|
||||
#define MREPEAT12( macro, data) MREPEAT11( macro, data) macro( 11, data)
|
||||
#define MREPEAT13( macro, data) MREPEAT12( macro, data) macro( 12, data)
|
||||
#define MREPEAT14( macro, data) MREPEAT13( macro, data) macro( 13, data)
|
||||
#define MREPEAT15( macro, data) MREPEAT14( macro, data) macro( 14, data)
|
||||
#define MREPEAT16( macro, data) MREPEAT15( macro, data) macro( 15, data)
|
||||
#define MREPEAT17( macro, data) MREPEAT16( macro, data) macro( 16, data)
|
||||
#define MREPEAT18( macro, data) MREPEAT17( macro, data) macro( 17, data)
|
||||
#define MREPEAT19( macro, data) MREPEAT18( macro, data) macro( 18, data)
|
||||
#define MREPEAT20( macro, data) MREPEAT19( macro, data) macro( 19, data)
|
||||
#define MREPEAT21( macro, data) MREPEAT20( macro, data) macro( 20, data)
|
||||
#define MREPEAT22( macro, data) MREPEAT21( macro, data) macro( 21, data)
|
||||
#define MREPEAT23( macro, data) MREPEAT22( macro, data) macro( 22, data)
|
||||
#define MREPEAT24( macro, data) MREPEAT23( macro, data) macro( 23, data)
|
||||
#define MREPEAT25( macro, data) MREPEAT24( macro, data) macro( 24, data)
|
||||
#define MREPEAT26( macro, data) MREPEAT25( macro, data) macro( 25, data)
|
||||
#define MREPEAT27( macro, data) MREPEAT26( macro, data) macro( 26, data)
|
||||
#define MREPEAT28( macro, data) MREPEAT27( macro, data) macro( 27, data)
|
||||
#define MREPEAT29( macro, data) MREPEAT28( macro, data) macro( 28, data)
|
||||
#define MREPEAT30( macro, data) MREPEAT29( macro, data) macro( 29, data)
|
||||
#define MREPEAT31( macro, data) MREPEAT30( macro, data) macro( 30, data)
|
||||
#define MREPEAT32( macro, data) MREPEAT31( macro, data) macro( 31, data)
|
||||
#define MREPEAT33( macro, data) MREPEAT32( macro, data) macro( 32, data)
|
||||
#define MREPEAT34( macro, data) MREPEAT33( macro, data) macro( 33, data)
|
||||
#define MREPEAT35( macro, data) MREPEAT34( macro, data) macro( 34, data)
|
||||
#define MREPEAT36( macro, data) MREPEAT35( macro, data) macro( 35, data)
|
||||
#define MREPEAT37( macro, data) MREPEAT36( macro, data) macro( 36, data)
|
||||
#define MREPEAT38( macro, data) MREPEAT37( macro, data) macro( 37, data)
|
||||
#define MREPEAT39( macro, data) MREPEAT38( macro, data) macro( 38, data)
|
||||
#define MREPEAT40( macro, data) MREPEAT39( macro, data) macro( 39, data)
|
||||
#define MREPEAT41( macro, data) MREPEAT40( macro, data) macro( 40, data)
|
||||
#define MREPEAT42( macro, data) MREPEAT41( macro, data) macro( 41, data)
|
||||
#define MREPEAT43( macro, data) MREPEAT42( macro, data) macro( 42, data)
|
||||
#define MREPEAT44( macro, data) MREPEAT43( macro, data) macro( 43, data)
|
||||
#define MREPEAT45( macro, data) MREPEAT44( macro, data) macro( 44, data)
|
||||
#define MREPEAT46( macro, data) MREPEAT45( macro, data) macro( 45, data)
|
||||
#define MREPEAT47( macro, data) MREPEAT46( macro, data) macro( 46, data)
|
||||
#define MREPEAT48( macro, data) MREPEAT47( macro, data) macro( 47, data)
|
||||
#define MREPEAT49( macro, data) MREPEAT48( macro, data) macro( 48, data)
|
||||
#define MREPEAT50( macro, data) MREPEAT49( macro, data) macro( 49, data)
|
||||
#define MREPEAT51( macro, data) MREPEAT50( macro, data) macro( 50, data)
|
||||
#define MREPEAT52( macro, data) MREPEAT51( macro, data) macro( 51, data)
|
||||
#define MREPEAT53( macro, data) MREPEAT52( macro, data) macro( 52, data)
|
||||
#define MREPEAT54( macro, data) MREPEAT53( macro, data) macro( 53, data)
|
||||
#define MREPEAT55( macro, data) MREPEAT54( macro, data) macro( 54, data)
|
||||
#define MREPEAT56( macro, data) MREPEAT55( macro, data) macro( 55, data)
|
||||
#define MREPEAT57( macro, data) MREPEAT56( macro, data) macro( 56, data)
|
||||
#define MREPEAT58( macro, data) MREPEAT57( macro, data) macro( 57, data)
|
||||
#define MREPEAT59( macro, data) MREPEAT58( macro, data) macro( 58, data)
|
||||
#define MREPEAT60( macro, data) MREPEAT59( macro, data) macro( 59, data)
|
||||
#define MREPEAT61( macro, data) MREPEAT60( macro, data) macro( 60, data)
|
||||
#define MREPEAT62( macro, data) MREPEAT61( macro, data) macro( 61, data)
|
||||
#define MREPEAT63( macro, data) MREPEAT62( macro, data) macro( 62, data)
|
||||
#define MREPEAT64( macro, data) MREPEAT63( macro, data) macro( 63, data)
|
||||
#define MREPEAT65( macro, data) MREPEAT64( macro, data) macro( 64, data)
|
||||
#define MREPEAT66( macro, data) MREPEAT65( macro, data) macro( 65, data)
|
||||
#define MREPEAT67( macro, data) MREPEAT66( macro, data) macro( 66, data)
|
||||
#define MREPEAT68( macro, data) MREPEAT67( macro, data) macro( 67, data)
|
||||
#define MREPEAT69( macro, data) MREPEAT68( macro, data) macro( 68, data)
|
||||
#define MREPEAT70( macro, data) MREPEAT69( macro, data) macro( 69, data)
|
||||
#define MREPEAT71( macro, data) MREPEAT70( macro, data) macro( 70, data)
|
||||
#define MREPEAT72( macro, data) MREPEAT71( macro, data) macro( 71, data)
|
||||
#define MREPEAT73( macro, data) MREPEAT72( macro, data) macro( 72, data)
|
||||
#define MREPEAT74( macro, data) MREPEAT73( macro, data) macro( 73, data)
|
||||
#define MREPEAT75( macro, data) MREPEAT74( macro, data) macro( 74, data)
|
||||
#define MREPEAT76( macro, data) MREPEAT75( macro, data) macro( 75, data)
|
||||
#define MREPEAT77( macro, data) MREPEAT76( macro, data) macro( 76, data)
|
||||
#define MREPEAT78( macro, data) MREPEAT77( macro, data) macro( 77, data)
|
||||
#define MREPEAT79( macro, data) MREPEAT78( macro, data) macro( 78, data)
|
||||
#define MREPEAT80( macro, data) MREPEAT79( macro, data) macro( 79, data)
|
||||
#define MREPEAT81( macro, data) MREPEAT80( macro, data) macro( 80, data)
|
||||
#define MREPEAT82( macro, data) MREPEAT81( macro, data) macro( 81, data)
|
||||
#define MREPEAT83( macro, data) MREPEAT82( macro, data) macro( 82, data)
|
||||
#define MREPEAT84( macro, data) MREPEAT83( macro, data) macro( 83, data)
|
||||
#define MREPEAT85( macro, data) MREPEAT84( macro, data) macro( 84, data)
|
||||
#define MREPEAT86( macro, data) MREPEAT85( macro, data) macro( 85, data)
|
||||
#define MREPEAT87( macro, data) MREPEAT86( macro, data) macro( 86, data)
|
||||
#define MREPEAT88( macro, data) MREPEAT87( macro, data) macro( 87, data)
|
||||
#define MREPEAT89( macro, data) MREPEAT88( macro, data) macro( 88, data)
|
||||
#define MREPEAT90( macro, data) MREPEAT89( macro, data) macro( 89, data)
|
||||
#define MREPEAT91( macro, data) MREPEAT90( macro, data) macro( 90, data)
|
||||
#define MREPEAT92( macro, data) MREPEAT91( macro, data) macro( 91, data)
|
||||
#define MREPEAT93( macro, data) MREPEAT92( macro, data) macro( 92, data)
|
||||
#define MREPEAT94( macro, data) MREPEAT93( macro, data) macro( 93, data)
|
||||
#define MREPEAT95( macro, data) MREPEAT94( macro, data) macro( 94, data)
|
||||
#define MREPEAT96( macro, data) MREPEAT95( macro, data) macro( 95, data)
|
||||
#define MREPEAT97( macro, data) MREPEAT96( macro, data) macro( 96, data)
|
||||
#define MREPEAT98( macro, data) MREPEAT97( macro, data) macro( 97, data)
|
||||
#define MREPEAT99( macro, data) MREPEAT98( macro, data) macro( 98, data)
|
||||
#define MREPEAT100(macro, data) MREPEAT99( macro, data) macro( 99, data)
|
||||
#define MREPEAT101(macro, data) MREPEAT100(macro, data) macro(100, data)
|
||||
#define MREPEAT102(macro, data) MREPEAT101(macro, data) macro(101, data)
|
||||
#define MREPEAT103(macro, data) MREPEAT102(macro, data) macro(102, data)
|
||||
#define MREPEAT104(macro, data) MREPEAT103(macro, data) macro(103, data)
|
||||
#define MREPEAT105(macro, data) MREPEAT104(macro, data) macro(104, data)
|
||||
#define MREPEAT106(macro, data) MREPEAT105(macro, data) macro(105, data)
|
||||
#define MREPEAT107(macro, data) MREPEAT106(macro, data) macro(106, data)
|
||||
#define MREPEAT108(macro, data) MREPEAT107(macro, data) macro(107, data)
|
||||
#define MREPEAT109(macro, data) MREPEAT108(macro, data) macro(108, data)
|
||||
#define MREPEAT110(macro, data) MREPEAT109(macro, data) macro(109, data)
|
||||
#define MREPEAT111(macro, data) MREPEAT110(macro, data) macro(110, data)
|
||||
#define MREPEAT112(macro, data) MREPEAT111(macro, data) macro(111, data)
|
||||
#define MREPEAT113(macro, data) MREPEAT112(macro, data) macro(112, data)
|
||||
#define MREPEAT114(macro, data) MREPEAT113(macro, data) macro(113, data)
|
||||
#define MREPEAT115(macro, data) MREPEAT114(macro, data) macro(114, data)
|
||||
#define MREPEAT116(macro, data) MREPEAT115(macro, data) macro(115, data)
|
||||
#define MREPEAT117(macro, data) MREPEAT116(macro, data) macro(116, data)
|
||||
#define MREPEAT118(macro, data) MREPEAT117(macro, data) macro(117, data)
|
||||
#define MREPEAT119(macro, data) MREPEAT118(macro, data) macro(118, data)
|
||||
#define MREPEAT120(macro, data) MREPEAT119(macro, data) macro(119, data)
|
||||
#define MREPEAT121(macro, data) MREPEAT120(macro, data) macro(120, data)
|
||||
#define MREPEAT122(macro, data) MREPEAT121(macro, data) macro(121, data)
|
||||
#define MREPEAT123(macro, data) MREPEAT122(macro, data) macro(122, data)
|
||||
#define MREPEAT124(macro, data) MREPEAT123(macro, data) macro(123, data)
|
||||
#define MREPEAT125(macro, data) MREPEAT124(macro, data) macro(124, data)
|
||||
#define MREPEAT126(macro, data) MREPEAT125(macro, data) macro(125, data)
|
||||
#define MREPEAT127(macro, data) MREPEAT126(macro, data) macro(126, data)
|
||||
#define MREPEAT128(macro, data) MREPEAT127(macro, data) macro(127, data)
|
||||
#define MREPEAT129(macro, data) MREPEAT128(macro, data) macro(128, data)
|
||||
#define MREPEAT130(macro, data) MREPEAT129(macro, data) macro(129, data)
|
||||
#define MREPEAT131(macro, data) MREPEAT130(macro, data) macro(130, data)
|
||||
#define MREPEAT132(macro, data) MREPEAT131(macro, data) macro(131, data)
|
||||
#define MREPEAT133(macro, data) MREPEAT132(macro, data) macro(132, data)
|
||||
#define MREPEAT134(macro, data) MREPEAT133(macro, data) macro(133, data)
|
||||
#define MREPEAT135(macro, data) MREPEAT134(macro, data) macro(134, data)
|
||||
#define MREPEAT136(macro, data) MREPEAT135(macro, data) macro(135, data)
|
||||
#define MREPEAT137(macro, data) MREPEAT136(macro, data) macro(136, data)
|
||||
#define MREPEAT138(macro, data) MREPEAT137(macro, data) macro(137, data)
|
||||
#define MREPEAT139(macro, data) MREPEAT138(macro, data) macro(138, data)
|
||||
#define MREPEAT140(macro, data) MREPEAT139(macro, data) macro(139, data)
|
||||
#define MREPEAT141(macro, data) MREPEAT140(macro, data) macro(140, data)
|
||||
#define MREPEAT142(macro, data) MREPEAT141(macro, data) macro(141, data)
|
||||
#define MREPEAT143(macro, data) MREPEAT142(macro, data) macro(142, data)
|
||||
#define MREPEAT144(macro, data) MREPEAT143(macro, data) macro(143, data)
|
||||
#define MREPEAT145(macro, data) MREPEAT144(macro, data) macro(144, data)
|
||||
#define MREPEAT146(macro, data) MREPEAT145(macro, data) macro(145, data)
|
||||
#define MREPEAT147(macro, data) MREPEAT146(macro, data) macro(146, data)
|
||||
#define MREPEAT148(macro, data) MREPEAT147(macro, data) macro(147, data)
|
||||
#define MREPEAT149(macro, data) MREPEAT148(macro, data) macro(148, data)
|
||||
#define MREPEAT150(macro, data) MREPEAT149(macro, data) macro(149, data)
|
||||
#define MREPEAT151(macro, data) MREPEAT150(macro, data) macro(150, data)
|
||||
#define MREPEAT152(macro, data) MREPEAT151(macro, data) macro(151, data)
|
||||
#define MREPEAT153(macro, data) MREPEAT152(macro, data) macro(152, data)
|
||||
#define MREPEAT154(macro, data) MREPEAT153(macro, data) macro(153, data)
|
||||
#define MREPEAT155(macro, data) MREPEAT154(macro, data) macro(154, data)
|
||||
#define MREPEAT156(macro, data) MREPEAT155(macro, data) macro(155, data)
|
||||
#define MREPEAT157(macro, data) MREPEAT156(macro, data) macro(156, data)
|
||||
#define MREPEAT158(macro, data) MREPEAT157(macro, data) macro(157, data)
|
||||
#define MREPEAT159(macro, data) MREPEAT158(macro, data) macro(158, data)
|
||||
#define MREPEAT160(macro, data) MREPEAT159(macro, data) macro(159, data)
|
||||
#define MREPEAT161(macro, data) MREPEAT160(macro, data) macro(160, data)
|
||||
#define MREPEAT162(macro, data) MREPEAT161(macro, data) macro(161, data)
|
||||
#define MREPEAT163(macro, data) MREPEAT162(macro, data) macro(162, data)
|
||||
#define MREPEAT164(macro, data) MREPEAT163(macro, data) macro(163, data)
|
||||
#define MREPEAT165(macro, data) MREPEAT164(macro, data) macro(164, data)
|
||||
#define MREPEAT166(macro, data) MREPEAT165(macro, data) macro(165, data)
|
||||
#define MREPEAT167(macro, data) MREPEAT166(macro, data) macro(166, data)
|
||||
#define MREPEAT168(macro, data) MREPEAT167(macro, data) macro(167, data)
|
||||
#define MREPEAT169(macro, data) MREPEAT168(macro, data) macro(168, data)
|
||||
#define MREPEAT170(macro, data) MREPEAT169(macro, data) macro(169, data)
|
||||
#define MREPEAT171(macro, data) MREPEAT170(macro, data) macro(170, data)
|
||||
#define MREPEAT172(macro, data) MREPEAT171(macro, data) macro(171, data)
|
||||
#define MREPEAT173(macro, data) MREPEAT172(macro, data) macro(172, data)
|
||||
#define MREPEAT174(macro, data) MREPEAT173(macro, data) macro(173, data)
|
||||
#define MREPEAT175(macro, data) MREPEAT174(macro, data) macro(174, data)
|
||||
#define MREPEAT176(macro, data) MREPEAT175(macro, data) macro(175, data)
|
||||
#define MREPEAT177(macro, data) MREPEAT176(macro, data) macro(176, data)
|
||||
#define MREPEAT178(macro, data) MREPEAT177(macro, data) macro(177, data)
|
||||
#define MREPEAT179(macro, data) MREPEAT178(macro, data) macro(178, data)
|
||||
#define MREPEAT180(macro, data) MREPEAT179(macro, data) macro(179, data)
|
||||
#define MREPEAT181(macro, data) MREPEAT180(macro, data) macro(180, data)
|
||||
#define MREPEAT182(macro, data) MREPEAT181(macro, data) macro(181, data)
|
||||
#define MREPEAT183(macro, data) MREPEAT182(macro, data) macro(182, data)
|
||||
#define MREPEAT184(macro, data) MREPEAT183(macro, data) macro(183, data)
|
||||
#define MREPEAT185(macro, data) MREPEAT184(macro, data) macro(184, data)
|
||||
#define MREPEAT186(macro, data) MREPEAT185(macro, data) macro(185, data)
|
||||
#define MREPEAT187(macro, data) MREPEAT186(macro, data) macro(186, data)
|
||||
#define MREPEAT188(macro, data) MREPEAT187(macro, data) macro(187, data)
|
||||
#define MREPEAT189(macro, data) MREPEAT188(macro, data) macro(188, data)
|
||||
#define MREPEAT190(macro, data) MREPEAT189(macro, data) macro(189, data)
|
||||
#define MREPEAT191(macro, data) MREPEAT190(macro, data) macro(190, data)
|
||||
#define MREPEAT192(macro, data) MREPEAT191(macro, data) macro(191, data)
|
||||
#define MREPEAT193(macro, data) MREPEAT192(macro, data) macro(192, data)
|
||||
#define MREPEAT194(macro, data) MREPEAT193(macro, data) macro(193, data)
|
||||
#define MREPEAT195(macro, data) MREPEAT194(macro, data) macro(194, data)
|
||||
#define MREPEAT196(macro, data) MREPEAT195(macro, data) macro(195, data)
|
||||
#define MREPEAT197(macro, data) MREPEAT196(macro, data) macro(196, data)
|
||||
#define MREPEAT198(macro, data) MREPEAT197(macro, data) macro(197, data)
|
||||
#define MREPEAT199(macro, data) MREPEAT198(macro, data) macro(198, data)
|
||||
#define MREPEAT200(macro, data) MREPEAT199(macro, data) macro(199, data)
|
||||
#define MREPEAT201(macro, data) MREPEAT200(macro, data) macro(200, data)
|
||||
#define MREPEAT202(macro, data) MREPEAT201(macro, data) macro(201, data)
|
||||
#define MREPEAT203(macro, data) MREPEAT202(macro, data) macro(202, data)
|
||||
#define MREPEAT204(macro, data) MREPEAT203(macro, data) macro(203, data)
|
||||
#define MREPEAT205(macro, data) MREPEAT204(macro, data) macro(204, data)
|
||||
#define MREPEAT206(macro, data) MREPEAT205(macro, data) macro(205, data)
|
||||
#define MREPEAT207(macro, data) MREPEAT206(macro, data) macro(206, data)
|
||||
#define MREPEAT208(macro, data) MREPEAT207(macro, data) macro(207, data)
|
||||
#define MREPEAT209(macro, data) MREPEAT208(macro, data) macro(208, data)
|
||||
#define MREPEAT210(macro, data) MREPEAT209(macro, data) macro(209, data)
|
||||
#define MREPEAT211(macro, data) MREPEAT210(macro, data) macro(210, data)
|
||||
#define MREPEAT212(macro, data) MREPEAT211(macro, data) macro(211, data)
|
||||
#define MREPEAT213(macro, data) MREPEAT212(macro, data) macro(212, data)
|
||||
#define MREPEAT214(macro, data) MREPEAT213(macro, data) macro(213, data)
|
||||
#define MREPEAT215(macro, data) MREPEAT214(macro, data) macro(214, data)
|
||||
#define MREPEAT216(macro, data) MREPEAT215(macro, data) macro(215, data)
|
||||
#define MREPEAT217(macro, data) MREPEAT216(macro, data) macro(216, data)
|
||||
#define MREPEAT218(macro, data) MREPEAT217(macro, data) macro(217, data)
|
||||
#define MREPEAT219(macro, data) MREPEAT218(macro, data) macro(218, data)
|
||||
#define MREPEAT220(macro, data) MREPEAT219(macro, data) macro(219, data)
|
||||
#define MREPEAT221(macro, data) MREPEAT220(macro, data) macro(220, data)
|
||||
#define MREPEAT222(macro, data) MREPEAT221(macro, data) macro(221, data)
|
||||
#define MREPEAT223(macro, data) MREPEAT222(macro, data) macro(222, data)
|
||||
#define MREPEAT224(macro, data) MREPEAT223(macro, data) macro(223, data)
|
||||
#define MREPEAT225(macro, data) MREPEAT224(macro, data) macro(224, data)
|
||||
#define MREPEAT226(macro, data) MREPEAT225(macro, data) macro(225, data)
|
||||
#define MREPEAT227(macro, data) MREPEAT226(macro, data) macro(226, data)
|
||||
#define MREPEAT228(macro, data) MREPEAT227(macro, data) macro(227, data)
|
||||
#define MREPEAT229(macro, data) MREPEAT228(macro, data) macro(228, data)
|
||||
#define MREPEAT230(macro, data) MREPEAT229(macro, data) macro(229, data)
|
||||
#define MREPEAT231(macro, data) MREPEAT230(macro, data) macro(230, data)
|
||||
#define MREPEAT232(macro, data) MREPEAT231(macro, data) macro(231, data)
|
||||
#define MREPEAT233(macro, data) MREPEAT232(macro, data) macro(232, data)
|
||||
#define MREPEAT234(macro, data) MREPEAT233(macro, data) macro(233, data)
|
||||
#define MREPEAT235(macro, data) MREPEAT234(macro, data) macro(234, data)
|
||||
#define MREPEAT236(macro, data) MREPEAT235(macro, data) macro(235, data)
|
||||
#define MREPEAT237(macro, data) MREPEAT236(macro, data) macro(236, data)
|
||||
#define MREPEAT238(macro, data) MREPEAT237(macro, data) macro(237, data)
|
||||
#define MREPEAT239(macro, data) MREPEAT238(macro, data) macro(238, data)
|
||||
#define MREPEAT240(macro, data) MREPEAT239(macro, data) macro(239, data)
|
||||
#define MREPEAT241(macro, data) MREPEAT240(macro, data) macro(240, data)
|
||||
#define MREPEAT242(macro, data) MREPEAT241(macro, data) macro(241, data)
|
||||
#define MREPEAT243(macro, data) MREPEAT242(macro, data) macro(242, data)
|
||||
#define MREPEAT244(macro, data) MREPEAT243(macro, data) macro(243, data)
|
||||
#define MREPEAT245(macro, data) MREPEAT244(macro, data) macro(244, data)
|
||||
#define MREPEAT246(macro, data) MREPEAT245(macro, data) macro(245, data)
|
||||
#define MREPEAT247(macro, data) MREPEAT246(macro, data) macro(246, data)
|
||||
#define MREPEAT248(macro, data) MREPEAT247(macro, data) macro(247, data)
|
||||
#define MREPEAT249(macro, data) MREPEAT248(macro, data) macro(248, data)
|
||||
#define MREPEAT250(macro, data) MREPEAT249(macro, data) macro(249, data)
|
||||
#define MREPEAT251(macro, data) MREPEAT250(macro, data) macro(250, data)
|
||||
#define MREPEAT252(macro, data) MREPEAT251(macro, data) macro(251, data)
|
||||
#define MREPEAT253(macro, data) MREPEAT252(macro, data) macro(252, data)
|
||||
#define MREPEAT254(macro, data) MREPEAT253(macro, data) macro(253, data)
|
||||
#define MREPEAT255(macro, data) MREPEAT254(macro, data) macro(254, data)
|
||||
#define MREPEAT256(macro, data) MREPEAT255(macro, data) macro(255, data)
|
||||
|
||||
/**
|
||||
* \}
|
||||
*/
|
||||
|
||||
#endif // _MREPEAT_H_
|
261
Marlin/src/HAL/DUE/usb/osc.h
Normal file
261
Marlin/src/HAL/DUE/usb/osc.h
Normal file
@ -0,0 +1,261 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Chip-specific oscillator management functions.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef CHIP_OSC_H_INCLUDED
|
||||
#define CHIP_OSC_H_INCLUDED
|
||||
|
||||
#include "compiler.h"
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
/*
|
||||
* Below BOARD_XXX macros are related to the specific board, and
|
||||
* should be defined by the board code, otherwise default value are used.
|
||||
*/
|
||||
#ifndef BOARD_FREQ_SLCK_XTAL
|
||||
# warning The board slow clock xtal frequency has not been defined.
|
||||
# define BOARD_FREQ_SLCK_XTAL (32768UL)
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FREQ_SLCK_BYPASS
|
||||
# warning The board slow clock bypass frequency has not been defined.
|
||||
# define BOARD_FREQ_SLCK_BYPASS (32768UL)
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FREQ_MAINCK_XTAL
|
||||
# warning The board main clock xtal frequency has not been defined.
|
||||
# define BOARD_FREQ_MAINCK_XTAL (12000000UL)
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FREQ_MAINCK_BYPASS
|
||||
# warning The board main clock bypass frequency has not been defined.
|
||||
# define BOARD_FREQ_MAINCK_BYPASS (12000000UL)
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_OSC_STARTUP_US
|
||||
# warning The board main clock xtal startup time has not been defined.
|
||||
# define BOARD_OSC_STARTUP_US (15625UL)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \weakgroup osc_group
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \name Oscillator identifiers
|
||||
//@{
|
||||
#define OSC_SLCK_32K_RC 0 //!< Internal 32kHz RC oscillator.
|
||||
#define OSC_SLCK_32K_XTAL 1 //!< External 32kHz crystal oscillator.
|
||||
#define OSC_SLCK_32K_BYPASS 2 //!< External 32kHz bypass oscillator.
|
||||
#define OSC_MAINCK_4M_RC 3 //!< Internal 4MHz RC oscillator.
|
||||
#define OSC_MAINCK_8M_RC 4 //!< Internal 8MHz RC oscillator.
|
||||
#define OSC_MAINCK_12M_RC 5 //!< Internal 12MHz RC oscillator.
|
||||
#define OSC_MAINCK_XTAL 6 //!< External crystal oscillator.
|
||||
#define OSC_MAINCK_BYPASS 7 //!< External bypass oscillator.
|
||||
//@}
|
||||
|
||||
//! \name Oscillator clock speed in hertz
|
||||
//@{
|
||||
#define OSC_SLCK_32K_RC_HZ CHIP_FREQ_SLCK_RC //!< Internal 32kHz RC oscillator.
|
||||
#define OSC_SLCK_32K_XTAL_HZ BOARD_FREQ_SLCK_XTAL //!< External 32kHz crystal oscillator.
|
||||
#define OSC_SLCK_32K_BYPASS_HZ BOARD_FREQ_SLCK_BYPASS //!< External 32kHz bypass oscillator.
|
||||
#define OSC_MAINCK_4M_RC_HZ CHIP_FREQ_MAINCK_RC_4MHZ //!< Internal 4MHz RC oscillator.
|
||||
#define OSC_MAINCK_8M_RC_HZ CHIP_FREQ_MAINCK_RC_8MHZ //!< Internal 8MHz RC oscillator.
|
||||
#define OSC_MAINCK_12M_RC_HZ CHIP_FREQ_MAINCK_RC_12MHZ //!< Internal 12MHz RC oscillator.
|
||||
#define OSC_MAINCK_XTAL_HZ BOARD_FREQ_MAINCK_XTAL //!< External crystal oscillator.
|
||||
#define OSC_MAINCK_BYPASS_HZ BOARD_FREQ_MAINCK_BYPASS //!< External bypass oscillator.
|
||||
//@}
|
||||
|
||||
static inline void osc_enable(uint32_t ul_id)
|
||||
{
|
||||
switch (ul_id) {
|
||||
case OSC_SLCK_32K_RC:
|
||||
break;
|
||||
|
||||
case OSC_SLCK_32K_XTAL:
|
||||
pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL);
|
||||
break;
|
||||
|
||||
case OSC_SLCK_32K_BYPASS:
|
||||
pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS);
|
||||
break;
|
||||
|
||||
|
||||
case OSC_MAINCK_4M_RC:
|
||||
pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz);
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_8M_RC:
|
||||
pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz);
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_12M_RC:
|
||||
pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz);
|
||||
break;
|
||||
|
||||
|
||||
case OSC_MAINCK_XTAL:
|
||||
pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*,
|
||||
pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US,
|
||||
OSC_SLCK_32K_RC_HZ)*/);
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_BYPASS:
|
||||
pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*,
|
||||
pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US,
|
||||
OSC_SLCK_32K_RC_HZ)*/);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void osc_disable(uint32_t ul_id)
|
||||
{
|
||||
switch (ul_id) {
|
||||
case OSC_SLCK_32K_RC:
|
||||
case OSC_SLCK_32K_XTAL:
|
||||
case OSC_SLCK_32K_BYPASS:
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_4M_RC:
|
||||
case OSC_MAINCK_8M_RC:
|
||||
case OSC_MAINCK_12M_RC:
|
||||
pmc_osc_disable_fastrc();
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_XTAL:
|
||||
pmc_osc_disable_xtal(PMC_OSC_XTAL);
|
||||
break;
|
||||
|
||||
case OSC_MAINCK_BYPASS:
|
||||
pmc_osc_disable_xtal(PMC_OSC_BYPASS);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline bool osc_is_ready(uint32_t ul_id)
|
||||
{
|
||||
switch (ul_id) {
|
||||
case OSC_SLCK_32K_RC:
|
||||
return 1;
|
||||
|
||||
case OSC_SLCK_32K_XTAL:
|
||||
case OSC_SLCK_32K_BYPASS:
|
||||
return pmc_osc_is_ready_32kxtal();
|
||||
|
||||
case OSC_MAINCK_4M_RC:
|
||||
case OSC_MAINCK_8M_RC:
|
||||
case OSC_MAINCK_12M_RC:
|
||||
case OSC_MAINCK_XTAL:
|
||||
case OSC_MAINCK_BYPASS:
|
||||
return pmc_osc_is_ready_mainck();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static inline uint32_t osc_get_rate(uint32_t ul_id)
|
||||
{
|
||||
switch (ul_id) {
|
||||
case OSC_SLCK_32K_RC:
|
||||
return OSC_SLCK_32K_RC_HZ;
|
||||
|
||||
case OSC_SLCK_32K_XTAL:
|
||||
return BOARD_FREQ_SLCK_XTAL;
|
||||
|
||||
case OSC_SLCK_32K_BYPASS:
|
||||
return BOARD_FREQ_SLCK_BYPASS;
|
||||
|
||||
case OSC_MAINCK_4M_RC:
|
||||
return OSC_MAINCK_4M_RC_HZ;
|
||||
|
||||
case OSC_MAINCK_8M_RC:
|
||||
return OSC_MAINCK_8M_RC_HZ;
|
||||
|
||||
case OSC_MAINCK_12M_RC:
|
||||
return OSC_MAINCK_12M_RC_HZ;
|
||||
|
||||
case OSC_MAINCK_XTAL:
|
||||
return BOARD_FREQ_MAINCK_XTAL;
|
||||
|
||||
case OSC_MAINCK_BYPASS:
|
||||
return BOARD_FREQ_MAINCK_BYPASS;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Wait until the oscillator identified by \a id is ready
|
||||
*
|
||||
* This function will busy-wait for the oscillator identified by \a id
|
||||
* to become stable and ready to use as a clock source.
|
||||
*
|
||||
* \param id A number identifying the oscillator to wait for.
|
||||
*/
|
||||
static inline void osc_wait_ready(uint8_t id)
|
||||
{
|
||||
while (!osc_is_ready(id)) {
|
||||
/* Do nothing */
|
||||
}
|
||||
}
|
||||
|
||||
//! @}
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif /* CHIP_OSC_H_INCLUDED */
|
288
Marlin/src/HAL/DUE/usb/pll.h
Normal file
288
Marlin/src/HAL/DUE/usb/pll.h
Normal file
@ -0,0 +1,288 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Chip-specific PLL definitions.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef CHIP_PLL_H_INCLUDED
|
||||
#define CHIP_PLL_H_INCLUDED
|
||||
|
||||
#include "osc.h"
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
/**
|
||||
* \weakgroup pll_group
|
||||
* @{
|
||||
*/
|
||||
|
||||
#define PLL_OUTPUT_MIN_HZ 84000000
|
||||
#define PLL_OUTPUT_MAX_HZ 192000000
|
||||
|
||||
#define PLL_INPUT_MIN_HZ 8000000
|
||||
#define PLL_INPUT_MAX_HZ 16000000
|
||||
|
||||
#define NR_PLLS 2
|
||||
#define PLLA_ID 0
|
||||
#define UPLL_ID 1 //!< USB UTMI PLL.
|
||||
|
||||
#define PLL_UPLL_HZ 480000000
|
||||
|
||||
#define PLL_COUNT 0x3FU
|
||||
|
||||
enum pll_source {
|
||||
PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator.
|
||||
PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator.
|
||||
PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator.
|
||||
PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator.
|
||||
PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator.
|
||||
PLL_NR_SOURCES, //!< Number of PLL sources.
|
||||
};
|
||||
|
||||
struct pll_config {
|
||||
uint32_t ctrl;
|
||||
};
|
||||
|
||||
#define pll_get_default_rate(pll_id) \
|
||||
((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \
|
||||
* CONFIG_PLL##pll_id##_MUL) \
|
||||
/ CONFIG_PLL##pll_id##_DIV)
|
||||
|
||||
/* Force UTMI PLL parameters (Hardware defined) */
|
||||
#ifdef CONFIG_PLL1_SOURCE
|
||||
# undef CONFIG_PLL1_SOURCE
|
||||
#endif
|
||||
#ifdef CONFIG_PLL1_MUL
|
||||
# undef CONFIG_PLL1_MUL
|
||||
#endif
|
||||
#ifdef CONFIG_PLL1_DIV
|
||||
# undef CONFIG_PLL1_DIV
|
||||
#endif
|
||||
#define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL
|
||||
#define CONFIG_PLL1_MUL 0
|
||||
#define CONFIG_PLL1_DIV 0
|
||||
|
||||
/**
|
||||
* \note The SAM3X PLL hardware interprets mul as mul+1. For readability the hardware mul+1
|
||||
* is hidden in this implementation. Use mul as mul effective value.
|
||||
*/
|
||||
static inline void pll_config_init(struct pll_config *p_cfg,
|
||||
enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul)
|
||||
{
|
||||
uint32_t vco_hz;
|
||||
|
||||
Assert(e_src < PLL_NR_SOURCES);
|
||||
|
||||
if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */
|
||||
p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT);
|
||||
} else { /* PLLA */
|
||||
/* Calculate internal VCO frequency */
|
||||
vco_hz = osc_get_rate(e_src) / ul_div;
|
||||
Assert(vco_hz >= PLL_INPUT_MIN_HZ);
|
||||
Assert(vco_hz <= PLL_INPUT_MAX_HZ);
|
||||
|
||||
vco_hz *= ul_mul;
|
||||
Assert(vco_hz >= PLL_OUTPUT_MIN_HZ);
|
||||
Assert(vco_hz <= PLL_OUTPUT_MAX_HZ);
|
||||
|
||||
/* PMC hardware will automatically make it mul+1 */
|
||||
p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT);
|
||||
}
|
||||
}
|
||||
|
||||
#define pll_config_defaults(cfg, pll_id) \
|
||||
pll_config_init(cfg, \
|
||||
CONFIG_PLL##pll_id##_SOURCE, \
|
||||
CONFIG_PLL##pll_id##_DIV, \
|
||||
CONFIG_PLL##pll_id##_MUL)
|
||||
|
||||
static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id)
|
||||
{
|
||||
Assert(ul_pll_id < NR_PLLS);
|
||||
|
||||
if (ul_pll_id == PLLA_ID) {
|
||||
p_cfg->ctrl = PMC->CKGR_PLLAR;
|
||||
} else {
|
||||
p_cfg->ctrl = PMC->CKGR_UCKR;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id)
|
||||
{
|
||||
Assert(ul_pll_id < NR_PLLS);
|
||||
|
||||
if (ul_pll_id == PLLA_ID) {
|
||||
pmc_disable_pllack(); // Always stop PLL first!
|
||||
PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl;
|
||||
} else {
|
||||
PMC->CKGR_UCKR = p_cfg->ctrl;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id)
|
||||
{
|
||||
Assert(ul_pll_id < NR_PLLS);
|
||||
|
||||
if (ul_pll_id == PLLA_ID) {
|
||||
pmc_disable_pllack(); // Always stop PLL first!
|
||||
PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl;
|
||||
} else {
|
||||
PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* \note This will only disable the selected PLL, not the underlying oscillator (mainck).
|
||||
*/
|
||||
static inline void pll_disable(uint32_t ul_pll_id)
|
||||
{
|
||||
Assert(ul_pll_id < NR_PLLS);
|
||||
|
||||
if (ul_pll_id == PLLA_ID) {
|
||||
pmc_disable_pllack();
|
||||
} else {
|
||||
PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN;
|
||||
}
|
||||
}
|
||||
|
||||
static inline uint32_t pll_is_locked(uint32_t ul_pll_id)
|
||||
{
|
||||
Assert(ul_pll_id < NR_PLLS);
|
||||
|
||||
if (ul_pll_id == PLLA_ID) {
|
||||
return pmc_is_locked_pllack();
|
||||
} else {
|
||||
return pmc_is_locked_upll();
|
||||
}
|
||||
}
|
||||
|
||||
static inline void pll_enable_source(enum pll_source e_src)
|
||||
{
|
||||
switch (e_src) {
|
||||
case PLL_SRC_MAINCK_4M_RC:
|
||||
case PLL_SRC_MAINCK_8M_RC:
|
||||
case PLL_SRC_MAINCK_12M_RC:
|
||||
case PLL_SRC_MAINCK_XTAL:
|
||||
case PLL_SRC_MAINCK_BYPASS:
|
||||
osc_enable(e_src);
|
||||
osc_wait_ready(e_src);
|
||||
break;
|
||||
|
||||
default:
|
||||
Assert(false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void pll_enable_config_defaults(unsigned int ul_pll_id)
|
||||
{
|
||||
struct pll_config pllcfg;
|
||||
|
||||
if (pll_is_locked(ul_pll_id)) {
|
||||
return; // Pll already running
|
||||
}
|
||||
switch (ul_pll_id) {
|
||||
#ifdef CONFIG_PLL0_SOURCE
|
||||
case 0:
|
||||
pll_enable_source(CONFIG_PLL0_SOURCE);
|
||||
pll_config_init(&pllcfg,
|
||||
CONFIG_PLL0_SOURCE,
|
||||
CONFIG_PLL0_DIV,
|
||||
CONFIG_PLL0_MUL);
|
||||
break;
|
||||
#endif
|
||||
#ifdef CONFIG_PLL1_SOURCE
|
||||
case 1:
|
||||
pll_enable_source(CONFIG_PLL1_SOURCE);
|
||||
pll_config_init(&pllcfg,
|
||||
CONFIG_PLL1_SOURCE,
|
||||
CONFIG_PLL1_DIV,
|
||||
CONFIG_PLL1_MUL);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
Assert(false);
|
||||
break;
|
||||
}
|
||||
pll_enable(&pllcfg, ul_pll_id);
|
||||
while (!pll_is_locked(ul_pll_id));
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Wait for PLL \a pll_id to become locked
|
||||
*
|
||||
* \todo Use a timeout to avoid waiting forever and hanging the system
|
||||
*
|
||||
* \param pll_id The ID of the PLL to wait for.
|
||||
*
|
||||
* \retval STATUS_OK The PLL is now locked.
|
||||
* \retval ERR_TIMEOUT Timed out waiting for PLL to become locked.
|
||||
*/
|
||||
static inline int pll_wait_for_lock(unsigned int pll_id)
|
||||
{
|
||||
Assert(pll_id < NR_PLLS);
|
||||
|
||||
while (!pll_is_locked(pll_id)) {
|
||||
/* Do nothing */
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
//! @}
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif /* CHIP_PLL_H_INCLUDED */
|
55
Marlin/src/HAL/DUE/usb/preprocessor.h
Normal file
55
Marlin/src/HAL/DUE/usb/preprocessor.h
Normal file
@ -0,0 +1,55 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Preprocessor utils.
|
||||
*
|
||||
* Copyright (c) 2010-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _PREPROCESSOR_H_
|
||||
#define _PREPROCESSOR_H_
|
||||
|
||||
#include "tpaste.h"
|
||||
#include "stringz.h"
|
||||
#include "mrepeat.h"
|
||||
|
||||
|
||||
#endif // _PREPROCESSOR_H_
|
173
Marlin/src/HAL/DUE/usb/sbc_protocol.h
Normal file
173
Marlin/src/HAL/DUE/usb/sbc_protocol.h
Normal file
@ -0,0 +1,173 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief SCSI Block Commands
|
||||
*
|
||||
* This file contains definitions of some of the commands found in the
|
||||
* SCSI SBC-2 standard.
|
||||
*
|
||||
* Note that the SBC specification depends on several commands defined
|
||||
* by the SCSI Primary Commands (SPC) standard. Each version of the SBC
|
||||
* standard is meant to be used in conjunction with a specific version
|
||||
* of the SPC standard, as follows:
|
||||
* - SBC depends on SPC
|
||||
* - SBC-2 depends on SPC-3
|
||||
* - SBC-3 depends on SPC-4
|
||||
*
|
||||
* Copyright (c) 2014-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
#ifndef _SBC_PROTOCOL_H_
|
||||
#define _SBC_PROTOCOL_H_
|
||||
|
||||
|
||||
/**
|
||||
* \ingroup usb_msc_protocol
|
||||
* \defgroup usb_sbc_protocol SCSI Block Commands protocol definitions
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \name SCSI commands defined by SBC-2
|
||||
//@{
|
||||
#define SBC_FORMAT_UNIT 0x04
|
||||
#define SBC_READ6 0x08
|
||||
#define SBC_WRITE6 0x0A
|
||||
#define SBC_START_STOP_UNIT 0x1B
|
||||
#define SBC_READ_CAPACITY10 0x25
|
||||
#define SBC_READ10 0x28
|
||||
#define SBC_WRITE10 0x2A
|
||||
#define SBC_VERIFY10 0x2F
|
||||
//@}
|
||||
|
||||
//! \name SBC-2 Mode page definitions
|
||||
//@{
|
||||
|
||||
enum scsi_sbc_mode {
|
||||
SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page
|
||||
SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page
|
||||
SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page
|
||||
SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page
|
||||
};
|
||||
|
||||
|
||||
//! \name SBC-2 Device-Specific Parameter
|
||||
//@{
|
||||
#define SCSI_MS_SBC_WP 0x80 //!< Write Protected
|
||||
#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \brief SBC-2 Short LBA mode parameter block descriptor
|
||||
*/
|
||||
struct sbc_slba_block_desc {
|
||||
be32_t nr_blocks; //!< Number of Blocks
|
||||
be32_t block_len; //!< Block Length
|
||||
#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SBC-2 Caching mode page
|
||||
*/
|
||||
struct sbc_caching_mode_page {
|
||||
uint8_t page_code;
|
||||
uint8_t page_length;
|
||||
uint8_t flags2;
|
||||
#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control
|
||||
#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch
|
||||
#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted
|
||||
#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity
|
||||
#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable
|
||||
#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable
|
||||
#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor
|
||||
#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable
|
||||
uint8_t retention;
|
||||
be16_t dis_pf_transfer_len;
|
||||
be16_t min_prefetch;
|
||||
be16_t max_prefetch;
|
||||
be16_t max_prefetch_ceil;
|
||||
uint8_t flags12;
|
||||
#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write
|
||||
#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz
|
||||
#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead
|
||||
#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable
|
||||
uint8_t nr_cache_segments;
|
||||
be16_t cache_segment_size;
|
||||
uint8_t reserved[4];
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SBC-2 Read-Write Error Recovery mode page
|
||||
*/
|
||||
struct sbc_rdwr_error_recovery_mode_page {
|
||||
uint8_t page_code;
|
||||
uint8_t page_length;
|
||||
#define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A
|
||||
uint8_t flags1;
|
||||
#define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7)
|
||||
#define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6)
|
||||
#define SBC_MP_RW_ERR_RECOV_TB (1 << 5)
|
||||
#define SBC_MP_RW_ERR_RECOV_RC (1 << 4)
|
||||
#define SBC_MP_RW_ERR_RECOV_ERR (1 << 3)
|
||||
#define SBC_MP_RW_ERR_RECOV_PER (1 << 2)
|
||||
#define SBC_MP_RW_ERR_RECOV_DTE (1 << 1)
|
||||
#define SBC_MP_RW_ERR_RECOV_DCR (1 << 0)
|
||||
uint8_t read_retry_count;
|
||||
uint8_t correction_span;
|
||||
uint8_t head_offset_count;
|
||||
uint8_t data_strobe_offset_count;
|
||||
uint8_t flags2;
|
||||
uint8_t write_retry_count;
|
||||
uint8_t flags3;
|
||||
be16_t recovery_time_limit;
|
||||
};
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \brief SBC-2 READ CAPACITY (10) parameter data
|
||||
*/
|
||||
struct sbc_read_capacity10_data {
|
||||
be32_t max_lba; //!< LBA of last logical block
|
||||
be32_t block_len; //!< Number of bytes in the last logical block
|
||||
};
|
||||
|
||||
//@}
|
||||
|
||||
#endif // _SBC_PROTOCOL_H_
|
142
Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp
Normal file
142
Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp
Normal file
@ -0,0 +1,142 @@
|
||||
/**
|
||||
* Interface from Atmel USB MSD to Marlin SD card
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
#include "../../../sd/cardreader.h"
|
||||
extern "C" {
|
||||
#include "sd_mmc_spi_mem.h"
|
||||
}
|
||||
|
||||
#define SD_MMC_BLOCK_SIZE 512
|
||||
|
||||
void sd_mmc_spi_mem_init() {
|
||||
}
|
||||
|
||||
Ctrl_status sd_mmc_spi_test_unit_ready() {
|
||||
#ifdef DISABLE_DUE_SD_MMC
|
||||
return CTRL_NO_PRESENT;
|
||||
#endif
|
||||
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
|
||||
return CTRL_NO_PRESENT;
|
||||
return CTRL_GOOD;
|
||||
}
|
||||
|
||||
// NOTE: This function is defined as returning the address of the last block
|
||||
// in the card, which is cardSize() - 1
|
||||
Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector) {
|
||||
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
|
||||
return CTRL_NO_PRESENT;
|
||||
*nb_sector = card.getSd2Card().cardSize() - 1;
|
||||
return CTRL_GOOD;
|
||||
}
|
||||
|
||||
bool sd_mmc_spi_unload(bool) { return true; }
|
||||
|
||||
bool sd_mmc_spi_wr_protect() { return false; }
|
||||
|
||||
bool sd_mmc_spi_removal() {
|
||||
return (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted());
|
||||
}
|
||||
|
||||
#if ACCESS_USB == true
|
||||
/**
|
||||
* \name MEM <-> USB Interface
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "udi_msc.h"
|
||||
|
||||
COMPILER_WORD_ALIGNED
|
||||
uint8_t sector_buf[SD_MMC_BLOCK_SIZE];
|
||||
|
||||
// #define DEBUG_MMC
|
||||
|
||||
Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector) {
|
||||
#ifdef DISABLE_DUE_SD_MMC
|
||||
return CTRL_NO_PRESENT;
|
||||
#endif
|
||||
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
|
||||
return CTRL_NO_PRESENT;
|
||||
|
||||
#ifdef DEBUG_MMC
|
||||
{
|
||||
char buffer[80];
|
||||
sprintf_P(buffer, PSTR("SDRD: %d @ 0x%08x\n"), nb_sector, addr);
|
||||
PORT_REDIRECT(0);
|
||||
SERIAL_ECHO(buffer);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Start reading
|
||||
if (!card.getSd2Card().readStart(addr))
|
||||
return CTRL_FAIL;
|
||||
|
||||
// For each specified sector
|
||||
while (nb_sector--) {
|
||||
|
||||
// Read a sector
|
||||
card.getSd2Card().readData(sector_buf);
|
||||
|
||||
// RAM -> USB
|
||||
if (!udi_msc_trans_block(true, sector_buf, SD_MMC_BLOCK_SIZE, NULL)) {
|
||||
card.getSd2Card().readStop();
|
||||
return CTRL_FAIL;
|
||||
}
|
||||
}
|
||||
|
||||
// Stop reading
|
||||
card.getSd2Card().readStop();
|
||||
|
||||
// Done
|
||||
return CTRL_GOOD;
|
||||
}
|
||||
|
||||
Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) {
|
||||
#ifdef DISABLE_DUE_SD_MMC
|
||||
return CTRL_NO_PRESENT;
|
||||
#endif
|
||||
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
|
||||
return CTRL_NO_PRESENT;
|
||||
|
||||
#ifdef DEBUG_MMC
|
||||
{
|
||||
char buffer[80];
|
||||
sprintf_P(buffer, PSTR("SDWR: %d @ 0x%08x\n"), nb_sector, addr);
|
||||
PORT_REDIRECT(0);
|
||||
SERIAL_ECHO(buffer);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!card.getSd2Card().writeStart(addr, nb_sector))
|
||||
return CTRL_FAIL;
|
||||
|
||||
// For each specified sector
|
||||
while (nb_sector--) {
|
||||
|
||||
// USB -> RAM
|
||||
if (!udi_msc_trans_block(false, sector_buf, SD_MMC_BLOCK_SIZE, NULL)) {
|
||||
card.getSd2Card().writeStop();
|
||||
return CTRL_FAIL;
|
||||
}
|
||||
|
||||
// Write a sector
|
||||
card.getSd2Card().writeData(sector_buf);
|
||||
}
|
||||
|
||||
// Stop writing
|
||||
card.getSd2Card().writeStop();
|
||||
|
||||
// Done
|
||||
return CTRL_GOOD;
|
||||
}
|
||||
|
||||
#endif // ACCESS_USB == true
|
||||
|
||||
#endif // SDSUPPORT
|
||||
#endif // ARDUINO_ARCH_SAM
|
177
Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h
Normal file
177
Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h
Normal file
@ -0,0 +1,177 @@
|
||||
/*****************************************************************************
|
||||
*
|
||||
* \file
|
||||
*
|
||||
* \brief CTRL_ACCESS interface for SD/MMC card.
|
||||
*
|
||||
* Copyright (c) 2014-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _SD_MMC_SPI_MEM_H_
|
||||
#define _SD_MMC_SPI_MEM_H_
|
||||
|
||||
/**
|
||||
* \defgroup group_avr32_components_memory_sd_mmc_sd_mmc_spi_mem SD/MMC SPI Memory
|
||||
*
|
||||
* \ingroup group_avr32_components_memory_sd_mmc_sd_mmc_spi
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
#include "conf_access.h"
|
||||
|
||||
#if SD_MMC_SPI_MEM == DISABLE
|
||||
#error sd_mmc_spi_mem.h is #included although SD_MMC_SPI_MEM is disabled
|
||||
#endif
|
||||
|
||||
|
||||
#include "ctrl_access.h"
|
||||
|
||||
|
||||
//_____ D E F I N I T I O N S ______________________________________________
|
||||
|
||||
#define SD_MMC_REMOVED 0
|
||||
#define SD_MMC_INSERTED 1
|
||||
#define SD_MMC_REMOVING 2
|
||||
|
||||
|
||||
//---- CONTROL FONCTIONS ----
|
||||
//!
|
||||
//! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI.
|
||||
//!/
|
||||
extern void sd_mmc_spi_mem_init(void);
|
||||
|
||||
//!
|
||||
//! @brief This function tests the state of the SD_MMC memory and sends it to the Host.
|
||||
//! For a PC, this device is seen as a removable media
|
||||
//! Before indicating any modification of the status of the media (GOOD->NO_PRESENT or vice-versa),
|
||||
//! the function must return the BUSY data to make the PC accepting the change
|
||||
//!
|
||||
//! @return Ctrl_status
|
||||
//! Media is ready -> CTRL_GOOD
|
||||
//! Media not present -> CTRL_NO_PRESENT
|
||||
//! Media has changed -> CTRL_BUSY
|
||||
//!/
|
||||
extern Ctrl_status sd_mmc_spi_test_unit_ready(void);
|
||||
|
||||
//!
|
||||
//! @brief This function gives the address of the last valid sector.
|
||||
//!
|
||||
//! @param *nb_sector number of sector (sector = 512B). OUT
|
||||
//!
|
||||
//! @return Ctrl_status
|
||||
//! Media ready -> CTRL_GOOD
|
||||
//! Media not present -> CTRL_NO_PRESENT
|
||||
//!/
|
||||
extern Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector);
|
||||
|
||||
/*! \brief Unload/Load the SD/MMC card selected
|
||||
*
|
||||
* The START STOP UNIT SCSI optional command allows an application client to
|
||||
* eject the removable medium on a LUN.
|
||||
*
|
||||
* \param unload \c true to unload the medium, \c false to load the medium.
|
||||
*
|
||||
* \return \c true if unload/load done success.
|
||||
*/
|
||||
extern bool sd_mmc_spi_unload(bool unload);
|
||||
|
||||
//!
|
||||
//! @brief This function returns the write protected status of the memory.
|
||||
//!
|
||||
//! Only used by memory removal with a HARDWARE SPECIFIC write protected detection
|
||||
//! ! The user must unplug the memory to change this write protected status,
|
||||
//! which cannot be for a SD_MMC.
|
||||
//!
|
||||
//! @return false -> the memory is not write-protected (always)
|
||||
//!/
|
||||
extern bool sd_mmc_spi_wr_protect(void);
|
||||
|
||||
//!
|
||||
//! @brief This function tells if the memory has been removed or not.
|
||||
//!
|
||||
//! @return false -> The memory isn't removed
|
||||
//!
|
||||
extern bool sd_mmc_spi_removal(void);
|
||||
|
||||
|
||||
//---- ACCESS DATA FONCTIONS ----
|
||||
|
||||
#if ACCESS_USB == true
|
||||
// Standard functions for open in read/write mode the device
|
||||
|
||||
//!
|
||||
//! @brief This function performs a read operation of n sectors from a given address on.
|
||||
//! (sector = 512B)
|
||||
//!
|
||||
//! DATA FLOW is: SD_MMC => USB
|
||||
//!
|
||||
//! @param addr Sector address to start the read from
|
||||
//! @param nb_sector Number of sectors to transfer
|
||||
//!
|
||||
//! @return Ctrl_status
|
||||
//! It is ready -> CTRL_GOOD
|
||||
//! A error occur -> CTRL_FAIL
|
||||
//!
|
||||
extern Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector);
|
||||
|
||||
//! This function initializes the SD/MMC memory for a write operation
|
||||
//!
|
||||
//! DATA FLOW is: USB => SD_MMC
|
||||
//!
|
||||
//! (sector = 512B)
|
||||
//! @param addr Sector address to start write
|
||||
//! @param nb_sector Number of sectors to transfer
|
||||
//!
|
||||
//! @return Ctrl_status
|
||||
//! It is ready -> CTRL_GOOD
|
||||
//! An error occurs -> CTRL_FAIL
|
||||
//!
|
||||
extern Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector);
|
||||
|
||||
#endif // #if ACCESS_USB == true
|
||||
|
||||
/**
|
||||
* \}
|
||||
*/
|
||||
|
||||
#endif // _SD_MMC_SPI_MEM_H_
|
337
Marlin/src/HAL/DUE/usb/spc_protocol.h
Normal file
337
Marlin/src/HAL/DUE/usb/spc_protocol.h
Normal file
@ -0,0 +1,337 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief SCSI Primary Commands
|
||||
*
|
||||
* This file contains definitions of some of the commands found in the
|
||||
* SPC-2 standard.
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
#ifndef _SPC_PROTOCOL_H_
|
||||
#define _SPC_PROTOCOL_H_
|
||||
|
||||
/**
|
||||
* \ingroup usb_msc_protocol
|
||||
* \defgroup usb_spc_protocol SCSI Primary Commands protocol definitions
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \name SCSI commands defined by SPC-2
|
||||
//@{
|
||||
#define SPC_TEST_UNIT_READY 0x00
|
||||
#define SPC_REQUEST_SENSE 0x03
|
||||
#define SPC_INQUIRY 0x12
|
||||
#define SPC_MODE_SELECT6 0x15
|
||||
#define SPC_MODE_SENSE6 0x1A
|
||||
#define SPC_SEND_DIAGNOSTIC 0x1D
|
||||
#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E
|
||||
#define SPC_MODE_SENSE10 0x5A
|
||||
#define SPC_REPORT_LUNS 0xA0
|
||||
//@}
|
||||
|
||||
//! \brief May be set in byte 0 of the INQUIRY CDB
|
||||
//@{
|
||||
//! Enable Vital Product Data
|
||||
#define SCSI_INQ_REQ_EVPD 0x01
|
||||
//! Command Support Data specified by the PAGE OR OPERATION CODE field
|
||||
#define SCSI_INQ_REQ_CMDT 0x02
|
||||
//@}
|
||||
|
||||
COMPILER_PACK_SET(1)
|
||||
|
||||
/**
|
||||
* \brief SCSI Standard Inquiry data structure
|
||||
*/
|
||||
struct scsi_inquiry_data {
|
||||
uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type
|
||||
#define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected
|
||||
#define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected
|
||||
#define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported
|
||||
#define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC)
|
||||
#define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access
|
||||
#define SCSI_INQ_DT_PRINTER 0x02 //!< Printer
|
||||
#define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device
|
||||
#define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device
|
||||
#define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device
|
||||
#define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory
|
||||
#define SCSI_INQ_DT_MC 0x08 //!< Medium Changer
|
||||
#define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller
|
||||
#define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services
|
||||
#define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access
|
||||
#define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer
|
||||
#define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands
|
||||
#define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage
|
||||
#define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral
|
||||
uint8_t flags1; //!< Flags (byte 1)
|
||||
#define SCSI_INQ_RMB 0x80 //!< Removable Medium
|
||||
uint8_t version; //!< Version
|
||||
#define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance
|
||||
#define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC)
|
||||
#define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2)
|
||||
#define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2)
|
||||
#define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3)
|
||||
uint8_t flags3; //!< Flags (byte 3)
|
||||
#define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported
|
||||
#define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing
|
||||
#define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format
|
||||
uint8_t addl_len; //!< Additional Length (n-4)
|
||||
#define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot
|
||||
uint8_t flags5; //!< Flags (byte 5)
|
||||
#define SCSI_INQ_SCCS 0x80
|
||||
uint8_t flags6; //!< Flags (byte 6)
|
||||
#define SCSI_INQ_BQUE 0x80
|
||||
#define SCSI_INQ_ENCSERV 0x40
|
||||
#define SCSI_INQ_MULTIP 0x10
|
||||
#define SCSI_INQ_MCHGR 0x08
|
||||
#define SCSI_INQ_ADDR16 0x01
|
||||
uint8_t flags7; //!< Flags (byte 7)
|
||||
#define SCSI_INQ_WBUS16 0x20
|
||||
#define SCSI_INQ_SYNC 0x10
|
||||
#define SCSI_INQ_LINKED 0x08
|
||||
#define SCSI_INQ_CMDQUE 0x02
|
||||
uint8_t vendor_id[8]; //!< T10 Vendor Identification
|
||||
uint8_t product_id[16]; //!< Product Identification
|
||||
uint8_t product_rev[4]; //!< Product Revision Level
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SCSI Standard Request sense data structure
|
||||
*/
|
||||
struct scsi_request_sense_data {
|
||||
/* 1st byte: REQUEST SENSE response flags*/
|
||||
uint8_t valid_reponse_code;
|
||||
#define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information
|
||||
#define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F
|
||||
#define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors)
|
||||
#define SCSI_SENSE_DEFERRED 0x71
|
||||
|
||||
/* 2nd byte */
|
||||
uint8_t obsolete;
|
||||
|
||||
/* 3rd byte */
|
||||
uint8_t sense_flag_key;
|
||||
#define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark.
|
||||
#define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists.
|
||||
#define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium.
|
||||
#define SCSI_SENSE_RESERVED 0x10 //!< Reserved
|
||||
#define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key
|
||||
|
||||
/* 4th to 7th bytes - INFORMATION field */
|
||||
uint8_t information[4];
|
||||
|
||||
/* 8th byte - ADDITIONAL SENSE LENGTH field */
|
||||
uint8_t AddSenseLen;
|
||||
#define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8)
|
||||
|
||||
/* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */
|
||||
uint8_t CmdSpecINFO[4];
|
||||
|
||||
/* 13th byte - ADDITIONAL SENSE CODE field */
|
||||
uint8_t AddSenseCode;
|
||||
|
||||
/* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */
|
||||
uint8_t AddSnsCodeQlfr;
|
||||
|
||||
/* 15th byte - FIELD REPLACEABLE UNIT CODE field */
|
||||
uint8_t FldReplUnitCode;
|
||||
|
||||
/* 16th byte */
|
||||
uint8_t SenseKeySpec[3];
|
||||
#define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information
|
||||
};
|
||||
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
/* Vital Product Data page codes */
|
||||
enum scsi_vpd_page_code {
|
||||
SCSI_VPD_SUPPORTED_PAGES = 0x00,
|
||||
SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80,
|
||||
SCSI_VPD_DEVICE_IDENTIFICATION = 0x83,
|
||||
};
|
||||
#define SCSI_VPD_HEADER_SIZE 4
|
||||
|
||||
/* Constants associated with the Device Identification VPD page */
|
||||
#define SCSI_VPD_ID_HEADER_SIZE 4
|
||||
|
||||
#define SCSI_VPD_CODE_SET_BINARY 1
|
||||
#define SCSI_VPD_CODE_SET_ASCII 2
|
||||
#define SCSI_VPD_CODE_SET_UTF8 3
|
||||
|
||||
#define SCSI_VPD_ID_TYPE_T10 1
|
||||
|
||||
|
||||
/* Sense keys */
|
||||
enum scsi_sense_key {
|
||||
SCSI_SK_NO_SENSE = 0x0,
|
||||
SCSI_SK_RECOVERED_ERROR = 0x1,
|
||||
SCSI_SK_NOT_READY = 0x2,
|
||||
SCSI_SK_MEDIUM_ERROR = 0x3,
|
||||
SCSI_SK_HARDWARE_ERROR = 0x4,
|
||||
SCSI_SK_ILLEGAL_REQUEST = 0x5,
|
||||
SCSI_SK_UNIT_ATTENTION = 0x6,
|
||||
SCSI_SK_DATA_PROTECT = 0x7,
|
||||
SCSI_SK_BLANK_CHECK = 0x8,
|
||||
SCSI_SK_VENDOR_SPECIFIC = 0x9,
|
||||
SCSI_SK_COPY_ABORTED = 0xA,
|
||||
SCSI_SK_ABORTED_COMMAND = 0xB,
|
||||
SCSI_SK_VOLUME_OVERFLOW = 0xD,
|
||||
SCSI_SK_MISCOMPARE = 0xE,
|
||||
};
|
||||
|
||||
/* Additional Sense Code / Additional Sense Code Qualifier pairs */
|
||||
enum scsi_asc_ascq {
|
||||
SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000,
|
||||
SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405,
|
||||
SCSI_ASC_WRITE_ERROR = 0x0C00,
|
||||
SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100,
|
||||
SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000,
|
||||
SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400,
|
||||
SCSI_ASC_WRITE_PROTECTED = 0x2700,
|
||||
SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800,
|
||||
SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00,
|
||||
SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SPC-2 Mode parameter
|
||||
* This subclause describes the block descriptors and the pages
|
||||
* used with MODE SELECT and MODE SENSE commands
|
||||
* that are applicable to all SCSI devices.
|
||||
*/
|
||||
enum scsi_spc_mode {
|
||||
SCSI_MS_MODE_VENDOR_SPEC = 0x00,
|
||||
SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page
|
||||
SCSI_MS_MODE_ALL = 0x3F,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SPC-2 Informational exceptions control page
|
||||
* See chapter 8.3.8
|
||||
*/
|
||||
struct spc_control_page_info_execpt {
|
||||
uint8_t page_code;
|
||||
uint8_t page_length;
|
||||
#define SPC_MP_INFEXP_PAGE_LENGTH 0x0A
|
||||
uint8_t flags1;
|
||||
#define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control
|
||||
#define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted
|
||||
#define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity
|
||||
#define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable
|
||||
#define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable
|
||||
#define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit
|
||||
uint8_t mrie;
|
||||
#define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00
|
||||
#define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01
|
||||
#define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02
|
||||
#define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03
|
||||
#define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04
|
||||
#define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05
|
||||
#define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06
|
||||
be32_t interval_timer;
|
||||
be32_t report_count;
|
||||
};
|
||||
|
||||
|
||||
enum scsi_spc_mode_sense_pc {
|
||||
SCSI_MS_SENSE_PC_CURRENT = 0,
|
||||
SCSI_MS_SENSE_PC_CHANGEABLE = 1,
|
||||
SCSI_MS_SENSE_PC_DEFAULT = 2,
|
||||
SCSI_MS_SENSE_PC_SAVED = 3,
|
||||
};
|
||||
|
||||
|
||||
|
||||
static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb)
|
||||
{
|
||||
return (cdb[1] >> 3) & 1;
|
||||
}
|
||||
|
||||
static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb)
|
||||
{
|
||||
return cdb[2] & 0x3F;
|
||||
}
|
||||
|
||||
static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb)
|
||||
{
|
||||
return cdb[2] >> 6;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief SCSI Mode Parameter Header used by MODE SELECT(6) and MODE
|
||||
* SENSE(6)
|
||||
*/
|
||||
struct scsi_mode_param_header6 {
|
||||
uint8_t mode_data_length; //!< Number of bytes after this
|
||||
uint8_t medium_type; //!< Medium Type
|
||||
uint8_t device_specific_parameter; //!< Defined by command set
|
||||
uint8_t block_descriptor_length; //!< Length of block descriptors
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SCSI Mode Parameter Header used by MODE SELECT(10) and MODE
|
||||
* SENSE(10)
|
||||
*/
|
||||
struct scsi_mode_param_header10 {
|
||||
be16_t mode_data_length; //!< Number of bytes after this
|
||||
uint8_t medium_type; //!< Medium Type
|
||||
uint8_t device_specific_parameter; //!< Defined by command set
|
||||
uint8_t flags4; //!< LONGLBA in bit 0
|
||||
uint8_t reserved;
|
||||
be16_t block_descriptor_length; //!< Length of block descriptors
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief SCSI Page_0 Mode Page header (SPF not set)
|
||||
*/
|
||||
struct scsi_mode_page_0_header {
|
||||
uint8_t page_code;
|
||||
#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable
|
||||
#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format
|
||||
uint8_t page_length; //!< Number of bytes after this
|
||||
#define SCSI_MS_PAGE_LEN(total) ((total) - 2)
|
||||
};
|
||||
|
||||
//@}
|
||||
|
||||
#endif // SPC_PROTOCOL_H_
|
85
Marlin/src/HAL/DUE/usb/stringz.h
Normal file
85
Marlin/src/HAL/DUE/usb/stringz.h
Normal file
@ -0,0 +1,85 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Preprocessor stringizing utils.
|
||||
*
|
||||
* Copyright (c) 2010-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _STRINGZ_H_
|
||||
#define _STRINGZ_H_
|
||||
|
||||
/**
|
||||
* \defgroup group_sam_utils_stringz Preprocessor - Stringize
|
||||
*
|
||||
* \ingroup group_sam_utils
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
/*! \brief Stringize.
|
||||
*
|
||||
* Stringize a preprocessing token, this token being allowed to be \#defined.
|
||||
*
|
||||
* May be used only within macros with the token passed as an argument if the token is \#defined.
|
||||
*
|
||||
* For example, writing STRINGZ(PIN) within a macro \#defined by PIN_NAME(PIN)
|
||||
* and invoked as PIN_NAME(PIN0) with PIN0 \#defined as A0 is equivalent to
|
||||
* writing "A0".
|
||||
*/
|
||||
#define STRINGZ(x) #x
|
||||
|
||||
/*! \brief Absolute stringize.
|
||||
*
|
||||
* Stringize a preprocessing token, this token being allowed to be \#defined.
|
||||
*
|
||||
* No restriction of use if the token is \#defined.
|
||||
*
|
||||
* For example, writing ASTRINGZ(PIN0) anywhere with PIN0 \#defined as A0 is
|
||||
* equivalent to writing "A0".
|
||||
*/
|
||||
#define ASTRINGZ(x) STRINGZ(x)
|
||||
|
||||
/**
|
||||
* \}
|
||||
*/
|
||||
|
||||
#endif // _STRINGZ_H_
|
122
Marlin/src/HAL/DUE/usb/sysclk.c
Normal file
122
Marlin/src/HAL/DUE/usb/sysclk.c
Normal file
@ -0,0 +1,122 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Chip-specific system clock management functions.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "sysclk.h"
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
/**
|
||||
* \weakgroup sysclk_group
|
||||
* @{
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_USBCLK_SOURCE) || defined(__DOXYGEN__)
|
||||
/**
|
||||
* \brief Enable full speed USB clock.
|
||||
*
|
||||
* \note The SAM3X PMC hardware interprets div as div+1. For readability the hardware div+1
|
||||
* is hidden in this implementation. Use div as div effective value.
|
||||
*
|
||||
* \param pll_id Source of the USB clock.
|
||||
* \param div Actual clock divisor. Must be superior to 0.
|
||||
*/
|
||||
void sysclk_enable_usb(void)
|
||||
{
|
||||
Assert(CONFIG_USBCLK_DIV > 0);
|
||||
|
||||
#ifdef CONFIG_PLL0_SOURCE
|
||||
if (CONFIG_USBCLK_SOURCE == USBCLK_SRC_PLL0) {
|
||||
struct pll_config pllcfg;
|
||||
|
||||
pll_enable_source(CONFIG_PLL0_SOURCE);
|
||||
pll_config_defaults(&pllcfg, 0);
|
||||
pll_enable(&pllcfg, 0);
|
||||
pll_wait_for_lock(0);
|
||||
pmc_switch_udpck_to_pllack(CONFIG_USBCLK_DIV - 1);
|
||||
pmc_enable_udpck();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (CONFIG_USBCLK_SOURCE == USBCLK_SRC_UPLL) {
|
||||
|
||||
pmc_enable_upll_clock();
|
||||
pmc_switch_udpck_to_upllck(CONFIG_USBCLK_DIV - 1);
|
||||
pmc_enable_udpck();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable full speed USB clock.
|
||||
*
|
||||
* \note This implementation does not switch off the PLL, it just turns off the USB clock.
|
||||
*/
|
||||
void sysclk_disable_usb(void)
|
||||
{
|
||||
pmc_disable_udpck();
|
||||
}
|
||||
#endif // CONFIG_USBCLK_SOURCE
|
||||
|
||||
//! @}
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
229
Marlin/src/HAL/DUE/usb/sysclk.h
Normal file
229
Marlin/src/HAL/DUE/usb/sysclk.h
Normal file
@ -0,0 +1,229 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Chip-specific system clock management functions.
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef CHIP_SYSCLK_H_INCLUDED
|
||||
#define CHIP_SYSCLK_H_INCLUDED
|
||||
|
||||
#include "osc.h"
|
||||
#include "pll.h"
|
||||
|
||||
/**
|
||||
* \page sysclk_quickstart Quick Start Guide for the System Clock Management service (SAM3A)
|
||||
*
|
||||
* This is the quick start guide for the \ref sysclk_group "System Clock Management"
|
||||
* service, with step-by-step instructions on how to configure and use the service for
|
||||
* specific use cases.
|
||||
*
|
||||
* \section sysclk_quickstart_usecases System Clock Management use cases
|
||||
* - \ref sysclk_quickstart_basic
|
||||
*
|
||||
* \section sysclk_quickstart_basic Basic usage of the System Clock Management service
|
||||
* This section will present a basic use case for the System Clock Management service.
|
||||
* This use case will configure the main system clock to 84MHz, using an internal PLL
|
||||
* module to multiply the frequency of a crystal attached to the microcontroller.
|
||||
*
|
||||
* \subsection sysclk_quickstart_use_case_1_prereq Prerequisites
|
||||
* - None
|
||||
*
|
||||
* \subsection sysclk_quickstart_use_case_1_setup_steps Initialization code
|
||||
* Add to the application initialization code:
|
||||
* \code
|
||||
sysclk_init();
|
||||
\endcode
|
||||
*
|
||||
* \subsection sysclk_quickstart_use_case_1_setup_steps_workflow Workflow
|
||||
* -# Configure the system clocks according to the settings in conf_clock.h:
|
||||
* \code sysclk_init(); \endcode
|
||||
*
|
||||
* \subsection sysclk_quickstart_use_case_1_example_code Example code
|
||||
* Add or uncomment the following in your conf_clock.h header file, commenting out all other
|
||||
* definitions of the same symbol(s):
|
||||
* \code
|
||||
#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK
|
||||
|
||||
// Fpll0 = (Fclk * PLL_mul) / PLL_div
|
||||
#define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL
|
||||
#define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL)
|
||||
#define CONFIG_PLL0_DIV 1
|
||||
|
||||
// Fbus = Fsys / BUS_div
|
||||
#define CONFIG_SYSCLK_PRES SYSCLK_PRES_1
|
||||
\endcode
|
||||
*
|
||||
* \subsection sysclk_quickstart_use_case_1_example_workflow Workflow
|
||||
* -# Configure the main system clock to use the output of the PLL module as its source:
|
||||
* \code #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK \endcode
|
||||
* -# Configure the PLL module to use the fast external fast crystal oscillator as its source:
|
||||
* \code #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL \endcode
|
||||
* -# Configure the PLL module to multiply the external fast crystal oscillator frequency up to 84MHz:
|
||||
* \code
|
||||
#define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL)
|
||||
#define CONFIG_PLL0_DIV 1
|
||||
\endcode
|
||||
* \note For user boards, \c BOARD_FREQ_MAINCK_XTAL should be defined in the board \c conf_board.h configuration
|
||||
* file as the frequency of the fast crystal attached to the microcontroller.
|
||||
* -# Configure the main clock to run at the full 84MHz, disable scaling of the main system clock speed:
|
||||
* \code
|
||||
#define CONFIG_SYSCLK_PRES SYSCLK_PRES_1
|
||||
\endcode
|
||||
* \note Some dividers are powers of two, while others are integer division factors. Refer to the
|
||||
* formulas in the conf_clock.h template commented above each division define.
|
||||
*/
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
/**
|
||||
* \weakgroup sysclk_group
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \name Configuration Symbols
|
||||
//@{
|
||||
/**
|
||||
* \def CONFIG_SYSCLK_SOURCE
|
||||
* \brief Initial/static main system clock source
|
||||
*
|
||||
* The main system clock will be configured to use this clock during
|
||||
* initialization.
|
||||
*/
|
||||
#ifndef CONFIG_SYSCLK_SOURCE
|
||||
# define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC
|
||||
#endif
|
||||
/**
|
||||
* \def CONFIG_SYSCLK_PRES
|
||||
* \brief Initial CPU clock divider (mck)
|
||||
*
|
||||
* The MCK will run at
|
||||
* \f[
|
||||
* f_{MCK} = \frac{f_{sys}}{\mathrm{CONFIG\_SYSCLK\_PRES}}\,\mbox{Hz}
|
||||
* \f]
|
||||
* after initialization.
|
||||
*/
|
||||
#ifndef CONFIG_SYSCLK_PRES
|
||||
# define CONFIG_SYSCLK_PRES 0
|
||||
#endif
|
||||
|
||||
//@}
|
||||
|
||||
//! \name Master Clock Sources (MCK)
|
||||
//@{
|
||||
#define SYSCLK_SRC_SLCK_RC 0 //!< Internal 32kHz RC oscillator as master source clock
|
||||
#define SYSCLK_SRC_SLCK_XTAL 1 //!< External 32kHz crystal oscillator as master source clock
|
||||
#define SYSCLK_SRC_SLCK_BYPASS 2 //!< External 32kHz bypass oscillator as master source clock
|
||||
#define SYSCLK_SRC_MAINCK_4M_RC 3 //!< Internal 4MHz RC oscillator as master source clock
|
||||
#define SYSCLK_SRC_MAINCK_8M_RC 4 //!< Internal 8MHz RC oscillator as master source clock
|
||||
#define SYSCLK_SRC_MAINCK_12M_RC 5 //!< Internal 12MHz RC oscillator as master source clock
|
||||
#define SYSCLK_SRC_MAINCK_XTAL 6 //!< External crystal oscillator as master source clock
|
||||
#define SYSCLK_SRC_MAINCK_BYPASS 7 //!< External bypass oscillator as master source clock
|
||||
#define SYSCLK_SRC_PLLACK 8 //!< Use PLLACK as master source clock
|
||||
#define SYSCLK_SRC_UPLLCK 9 //!< Use UPLLCK as master source clock
|
||||
//@}
|
||||
|
||||
//! \name Master Clock Prescalers (MCK)
|
||||
//@{
|
||||
#define SYSCLK_PRES_1 PMC_MCKR_PRES_CLK_1 //!< Set master clock prescaler to 1
|
||||
#define SYSCLK_PRES_2 PMC_MCKR_PRES_CLK_2 //!< Set master clock prescaler to 2
|
||||
#define SYSCLK_PRES_4 PMC_MCKR_PRES_CLK_4 //!< Set master clock prescaler to 4
|
||||
#define SYSCLK_PRES_8 PMC_MCKR_PRES_CLK_8 //!< Set master clock prescaler to 8
|
||||
#define SYSCLK_PRES_16 PMC_MCKR_PRES_CLK_16 //!< Set master clock prescaler to 16
|
||||
#define SYSCLK_PRES_32 PMC_MCKR_PRES_CLK_32 //!< Set master clock prescaler to 32
|
||||
#define SYSCLK_PRES_64 PMC_MCKR_PRES_CLK_64 //!< Set master clock prescaler to 64
|
||||
#define SYSCLK_PRES_3 PMC_MCKR_PRES_CLK_3 //!< Set master clock prescaler to 3
|
||||
//@}
|
||||
|
||||
//! \name USB Clock Sources
|
||||
//@{
|
||||
#define USBCLK_SRC_PLL0 0 //!< Use PLLA
|
||||
#define USBCLK_SRC_UPLL 1 //!< Use UPLL
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \def CONFIG_USBCLK_SOURCE
|
||||
* \brief Configuration symbol for the USB generic clock source
|
||||
*
|
||||
* Sets the clock source to use for the USB. The source must also be properly
|
||||
* configured.
|
||||
*
|
||||
* Define this to one of the \c USBCLK_SRC_xxx settings. Leave it undefined if
|
||||
* USB is not required.
|
||||
*/
|
||||
#ifdef __DOXYGEN__
|
||||
# define CONFIG_USBCLK_SOURCE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def CONFIG_USBCLK_DIV
|
||||
* \brief Configuration symbol for the USB generic clock divider setting
|
||||
*
|
||||
* Sets the clock division for the USB generic clock. If a USB clock source is
|
||||
* selected with CONFIG_USBCLK_SOURCE, this configuration symbol must also be
|
||||
* defined.
|
||||
*/
|
||||
#ifdef __DOXYGEN__
|
||||
# define CONFIG_USBCLK_DIV
|
||||
#endif
|
||||
|
||||
|
||||
extern void sysclk_enable_usb(void);
|
||||
extern void sysclk_disable_usb(void);
|
||||
|
||||
//! @}
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif /* CHIP_SYSCLK_H_INCLUDED */
|
105
Marlin/src/HAL/DUE/usb/tpaste.h
Normal file
105
Marlin/src/HAL/DUE/usb/tpaste.h
Normal file
@ -0,0 +1,105 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Preprocessor token pasting utils.
|
||||
*
|
||||
* Copyright (c) 2010-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _TPASTE_H_
|
||||
#define _TPASTE_H_
|
||||
|
||||
/**
|
||||
* \defgroup group_sam_utils_tpaste Preprocessor - Token Paste
|
||||
*
|
||||
* \ingroup group_sam_utils
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
/*! \name Token Paste
|
||||
*
|
||||
* Paste N preprocessing tokens together, these tokens being allowed to be \#defined.
|
||||
*
|
||||
* May be used only within macros with the tokens passed as arguments if the tokens are \#defined.
|
||||
*
|
||||
* For example, writing TPASTE2(U, WIDTH) within a macro \#defined by
|
||||
* UTYPE(WIDTH) and invoked as UTYPE(UL_WIDTH) with UL_WIDTH \#defined as 32 is
|
||||
* equivalent to writing U32.
|
||||
*/
|
||||
//! @{
|
||||
#define TPASTE2( a, b) a##b
|
||||
#define TPASTE3( a, b, c) a##b##c
|
||||
#define TPASTE4( a, b, c, d) a##b##c##d
|
||||
#define TPASTE5( a, b, c, d, e) a##b##c##d##e
|
||||
#define TPASTE6( a, b, c, d, e, f) a##b##c##d##e##f
|
||||
#define TPASTE7( a, b, c, d, e, f, g) a##b##c##d##e##f##g
|
||||
#define TPASTE8( a, b, c, d, e, f, g, h) a##b##c##d##e##f##g##h
|
||||
#define TPASTE9( a, b, c, d, e, f, g, h, i) a##b##c##d##e##f##g##h##i
|
||||
#define TPASTE10(a, b, c, d, e, f, g, h, i, j) a##b##c##d##e##f##g##h##i##j
|
||||
//! @}
|
||||
|
||||
/*! \name Absolute Token Paste
|
||||
*
|
||||
* Paste N preprocessing tokens together, these tokens being allowed to be \#defined.
|
||||
*
|
||||
* No restriction of use if the tokens are \#defined.
|
||||
*
|
||||
* For example, writing ATPASTE2(U, UL_WIDTH) anywhere with UL_WIDTH \#defined
|
||||
* as 32 is equivalent to writing U32.
|
||||
*/
|
||||
//! @{
|
||||
#define ATPASTE2( a, b) TPASTE2( a, b)
|
||||
#define ATPASTE3( a, b, c) TPASTE3( a, b, c)
|
||||
#define ATPASTE4( a, b, c, d) TPASTE4( a, b, c, d)
|
||||
#define ATPASTE5( a, b, c, d, e) TPASTE5( a, b, c, d, e)
|
||||
#define ATPASTE6( a, b, c, d, e, f) TPASTE6( a, b, c, d, e, f)
|
||||
#define ATPASTE7( a, b, c, d, e, f, g) TPASTE7( a, b, c, d, e, f, g)
|
||||
#define ATPASTE8( a, b, c, d, e, f, g, h) TPASTE8( a, b, c, d, e, f, g, h)
|
||||
#define ATPASTE9( a, b, c, d, e, f, g, h, i) TPASTE9( a, b, c, d, e, f, g, h, i)
|
||||
#define ATPASTE10(a, b, c, d, e, f, g, h, i, j) TPASTE10(a, b, c, d, e, f, g, h, i, j)
|
||||
//! @}
|
||||
|
||||
/**
|
||||
* \}
|
||||
*/
|
||||
|
||||
#endif // _TPASTE_H_
|
1149
Marlin/src/HAL/DUE/usb/udc.c
Normal file
1149
Marlin/src/HAL/DUE/usb/udc.c
Normal file
File diff suppressed because it is too large
Load Diff
697
Marlin/src/HAL/DUE/usb/udc.h
Normal file
697
Marlin/src/HAL/DUE/usb/udc.h
Normal file
@ -0,0 +1,697 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Interface of the USB Device Controller (UDC)
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDC_H_
|
||||
#define _UDC_H_
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "usb_protocol.h"
|
||||
#include "udc_desc.h"
|
||||
#include "udd.h"
|
||||
|
||||
#if USB_DEVICE_VENDOR_ID == 0
|
||||
# error USB_DEVICE_VENDOR_ID cannot be equal to 0
|
||||
#endif
|
||||
|
||||
#if USB_DEVICE_PRODUCT_ID == 0
|
||||
# error USB_DEVICE_PRODUCT_ID cannot be equal to 0
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \ingroup usb_device_group
|
||||
* \defgroup udc_group USB Device Controller (UDC)
|
||||
*
|
||||
* The UDC provides a high-level abstraction of the usb device.
|
||||
* You can use these functions to control the main device state
|
||||
* (start/attach/wakeup).
|
||||
*
|
||||
* \section USB_DEVICE_CONF USB Device Custom configuration
|
||||
* The following USB Device configuration must be included in the conf_usb.h
|
||||
* file of the application.
|
||||
*
|
||||
* USB_DEVICE_VENDOR_ID (Word)<br>
|
||||
* Vendor ID provided by USB org (ATMEL 0x03EB).
|
||||
*
|
||||
* USB_DEVICE_PRODUCT_ID (Word)<br>
|
||||
* Product ID (Referenced in usb_atmel.h).
|
||||
*
|
||||
* USB_DEVICE_MAJOR_VERSION (Byte)<br>
|
||||
* Major version of the device
|
||||
*
|
||||
* USB_DEVICE_MINOR_VERSION (Byte)<br>
|
||||
* Minor version of the device
|
||||
*
|
||||
* USB_DEVICE_MANUFACTURE_NAME (string)<br>
|
||||
* ASCII name for the manufacture
|
||||
*
|
||||
* USB_DEVICE_PRODUCT_NAME (string)<br>
|
||||
* ASCII name for the product
|
||||
*
|
||||
* USB_DEVICE_SERIAL_NAME (string)<br>
|
||||
* ASCII name to enable and set a serial number
|
||||
*
|
||||
* USB_DEVICE_POWER (Numeric)<br>
|
||||
* (unit mA) Maximum device power
|
||||
*
|
||||
* USB_DEVICE_ATTR (Byte)<br>
|
||||
* USB attributes available:
|
||||
* - USB_CONFIG_ATTR_SELF_POWERED
|
||||
* - USB_CONFIG_ATTR_REMOTE_WAKEUP
|
||||
* Note: if remote wake enabled then defines remotewakeup callbacks,
|
||||
* see Table 5-2. External API from UDC - Callback
|
||||
*
|
||||
* USB_DEVICE_LOW_SPEED (Only defined)<br>
|
||||
* Force the USB Device to run in low speed
|
||||
*
|
||||
* USB_DEVICE_HS_SUPPORT (Only defined)<br>
|
||||
* Authorize the USB Device to run in high speed
|
||||
*
|
||||
* USB_DEVICE_MAX_EP (Byte)<br>
|
||||
* Define the maximum endpoint number used by the USB Device.<br>
|
||||
* This one is already defined in UDI default configuration.
|
||||
* Ex:
|
||||
* - When endpoint control 0x00, endpoint 0x01 and
|
||||
* endpoint 0x82 is used then USB_DEVICE_MAX_EP=2
|
||||
* - When only endpoint control 0x00 is used then USB_DEVICE_MAX_EP=0
|
||||
* - When endpoint 0x01 and endpoint 0x81 is used then USB_DEVICE_MAX_EP=1<br>
|
||||
* (configuration not possible on USBB interface)
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief Authorizes the VBUS event
|
||||
*
|
||||
* \return true, if the VBUS monitoring is possible.
|
||||
*
|
||||
* \section udc_vbus_monitoring VBus monitoring used cases
|
||||
*
|
||||
* The VBus monitoring is used only for USB SELF Power application.
|
||||
*
|
||||
* - By default the USB device is automatically attached when Vbus is high
|
||||
* or when USB is start for devices without internal Vbus monitoring.
|
||||
* conf_usb.h file does not contains define USB_DEVICE_ATTACH_AUTO_DISABLE.
|
||||
* \code //#define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode
|
||||
*
|
||||
* - Add custom VBUS monitoring. conf_usb.h file contains define
|
||||
* USB_DEVICE_ATTACH_AUTO_DISABLE:
|
||||
* \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode
|
||||
* User C file contains:
|
||||
* \code
|
||||
// Authorize VBUS monitoring
|
||||
if (!udc_include_vbus_monitoring()) {
|
||||
// Implement custom VBUS monitoring via GPIO or other
|
||||
}
|
||||
Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other
|
||||
{
|
||||
// Attach USB Device
|
||||
udc_attach();
|
||||
}
|
||||
\endcode
|
||||
*
|
||||
* - Case of battery charging. conf_usb.h file contains define
|
||||
* USB_DEVICE_ATTACH_AUTO_DISABLE:
|
||||
* \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode
|
||||
* User C file contains:
|
||||
* \code
|
||||
Event VBUS present() // VBUS interrupt or GPIO interrupt or ..
|
||||
{
|
||||
// Authorize battery charging, but wait key press to start USB.
|
||||
}
|
||||
Event Key press()
|
||||
{
|
||||
// Stop batteries charging
|
||||
// Start USB
|
||||
udc_attach();
|
||||
}
|
||||
\endcode
|
||||
*/
|
||||
static inline bool udc_include_vbus_monitoring(void)
|
||||
{
|
||||
return udd_include_vbus_monitoring();
|
||||
}
|
||||
|
||||
/*! \brief Start the USB Device stack
|
||||
*/
|
||||
void udc_start(void);
|
||||
|
||||
/*! \brief Stop the USB Device stack
|
||||
*/
|
||||
void udc_stop(void);
|
||||
|
||||
/**
|
||||
* \brief Attach device to the bus when possible
|
||||
*
|
||||
* \warning If a VBus control is included in driver,
|
||||
* then it will attach device when an acceptable Vbus
|
||||
* level from the host is detected.
|
||||
*/
|
||||
static inline void udc_attach(void)
|
||||
{
|
||||
udd_attach();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* \brief Detaches the device from the bus
|
||||
*
|
||||
* The driver must remove pull-up on USB line D- or D+.
|
||||
*/
|
||||
static inline void udc_detach(void)
|
||||
{
|
||||
udd_detach();
|
||||
}
|
||||
|
||||
|
||||
/*! \brief The USB driver sends a resume signal called \e "Upstream Resume"
|
||||
* This is authorized only when the remote wakeup feature is enabled by host.
|
||||
*/
|
||||
static inline void udc_remotewakeup(void)
|
||||
{
|
||||
udd_send_remotewakeup();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* \brief Returns a pointer on the current interface descriptor
|
||||
*
|
||||
* \return pointer on the current interface descriptor.
|
||||
*/
|
||||
usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
|
||||
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \ingroup usb_group
|
||||
* \defgroup usb_device_group USB Stack Device
|
||||
*
|
||||
* This module includes USB Stack Device implementation.
|
||||
* The stack is divided in three parts:
|
||||
* - USB Device Controller (UDC) provides USB chapter 9 compliance
|
||||
* - USB Device Interface (UDI) provides USB Class compliance
|
||||
* - USB Device Driver (UDD) provides USB Driver for each Atmel MCU
|
||||
|
||||
* Many USB Device applications can be implemented on Atmel MCU.
|
||||
* Atmel provides many application notes for different applications:
|
||||
* - AVR4900, provides general information about Device Stack
|
||||
* - AVR4901, explains how to create a new class
|
||||
* - AVR4902, explains how to create a composite device
|
||||
* - AVR49xx, all device classes provided in ASF have an application note
|
||||
*
|
||||
* A basic USB knowledge is required to understand the USB Device
|
||||
* Class application notes (HID,MS,CDC,PHDC,...).
|
||||
* Then, to create an USB device with
|
||||
* only one class provided by ASF, refer directly to the application note
|
||||
* corresponding to this USB class. The USB Device application note for
|
||||
* New Class and Composite is dedicated to advanced USB users.
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! @}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \ingroup udc_group
|
||||
* \defgroup udc_basic_use_case_setup_prereq USB Device Controller (UDC) - Prerequisites
|
||||
* Common prerequisites for all USB devices.
|
||||
*
|
||||
* This module is based on USB device stack full interrupt driven, and supporting
|
||||
* \ref sleepmgr_group sleepmgr. For AVR and SAM3/4 devices the \ref clk_group clock services
|
||||
* is supported. For SAMD devices the \ref asfdoc_sam0_system_clock_group clock driver is supported.
|
||||
*
|
||||
* The following procedure must be executed to setup the project correctly:
|
||||
* - Specify the clock configuration:
|
||||
* - XMEGA USB devices need 48MHz clock input.\n
|
||||
* XMEGA USB devices need CPU frequency higher than 12MHz.\n
|
||||
* You can use either an internal RC48MHz auto calibrated by Start of Frames
|
||||
* or an external OSC.
|
||||
* - UC3 and SAM3/4 devices without USB high speed support need 48MHz clock input.\n
|
||||
* You must use a PLL and an external OSC.
|
||||
* - UC3 and SAM3/4 devices with USB high speed support need 12MHz clock input.\n
|
||||
* You must use an external OSC.
|
||||
* - UC3 devices with USBC hardware need CPU frequency higher than 25MHz.
|
||||
* - SAMD devices without USB high speed support need 48MHz clock input.\n
|
||||
* You should use DFLL with USBCRM.
|
||||
* - In conf_board.h, the define CONF_BOARD_USB_PORT must be added to enable USB lines.
|
||||
* (Not mandatory for all boards)
|
||||
* - Enable interrupts
|
||||
* - Initialize the clock service
|
||||
*
|
||||
* The usage of \ref sleepmgr_group sleepmgr service is optional, but recommended to reduce power
|
||||
* consumption:
|
||||
* - Initialize the sleep manager service
|
||||
* - Activate sleep mode when the application is in IDLE state
|
||||
*
|
||||
* \subpage udc_conf_clock.
|
||||
*
|
||||
* for AVR and SAM3/4 devices, add to the initialization code:
|
||||
* \code
|
||||
sysclk_init();
|
||||
irq_initialize_vectors();
|
||||
cpu_irq_enable();
|
||||
board_init();
|
||||
sleepmgr_init(); // Optional
|
||||
\endcode
|
||||
*
|
||||
* For SAMD devices, add to the initialization code:
|
||||
* \code
|
||||
system_init();
|
||||
irq_initialize_vectors();
|
||||
cpu_irq_enable();
|
||||
sleepmgr_init(); // Optional
|
||||
\endcode
|
||||
* Add to the main IDLE loop:
|
||||
* \code
|
||||
sleepmgr_enter_sleep(); // Optional
|
||||
\endcode
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* \ingroup udc_group
|
||||
* \defgroup udc_basic_use_case_setup_code USB Device Controller (UDC) - Example code
|
||||
* Common example code for all USB devices.
|
||||
*
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_VENDOR_ID 0x03EB
|
||||
#define USB_DEVICE_PRODUCT_ID 0xXXXX
|
||||
#define USB_DEVICE_MAJOR_VERSION 1
|
||||
#define USB_DEVICE_MINOR_VERSION 0
|
||||
#define USB_DEVICE_POWER 100
|
||||
#define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
void usb_init(void)
|
||||
{
|
||||
udc_start();
|
||||
}
|
||||
\endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \ingroup udc_group
|
||||
* \defgroup udc_basic_use_case_setup_flow USB Device Controller (UDC) - Workflow
|
||||
* Common workflow for all USB devices.
|
||||
*
|
||||
* -# Ensure that conf_usb.h is available and contains the following configuration
|
||||
* which is the main USB device configuration:
|
||||
* - \code // Vendor ID provided by USB org (ATMEL 0x03EB)
|
||||
#define USB_DEVICE_VENDOR_ID 0x03EB // Type Word
|
||||
// Product ID (Atmel PID referenced in usb_atmel.h)
|
||||
#define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word
|
||||
// Major version of the device
|
||||
#define USB_DEVICE_MAJOR_VERSION 1 // Type Byte
|
||||
// Minor version of the device
|
||||
#define USB_DEVICE_MINOR_VERSION 0 // Type Byte
|
||||
// Maximum device power (mA)
|
||||
#define USB_DEVICE_POWER 100 // Type 9-bits
|
||||
// USB attributes to enable features
|
||||
#define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode
|
||||
* -# Call the USB device stack start function to enable stack and start USB:
|
||||
* - \code udc_start(); \endcode
|
||||
* \note In case of USB dual roles (Device and Host) managed through USB OTG connector
|
||||
* (USB ID pin), the call of udc_start() must be removed and replaced by uhc_start().
|
||||
* SeRefer to "AVR4950 section 6.1 Dual roles" for further information about dual roles.
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_conf_clock conf_clock.h examples with USB support
|
||||
*
|
||||
* Content of XMEGA conf_clock.h:
|
||||
* \code
|
||||
// Configuration based on internal RC:
|
||||
// USB clock need of 48Mhz
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC
|
||||
#define CONFIG_OSC_RC32_CAL 48000000UL
|
||||
#define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF
|
||||
// CPU clock need of clock > 12MHz to run with USB (Here 24MHz)
|
||||
#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ
|
||||
#define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2
|
||||
#define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for AT32UC3A0, AT32UC3A1, AT32UC3B devices (USBB):
|
||||
* \code
|
||||
// Configuration based on 12MHz external OSC:
|
||||
#define CONFIG_PLL1_SOURCE PLL_SRC_OSC0
|
||||
#define CONFIG_PLL1_MUL 8
|
||||
#define CONFIG_PLL1_DIV 2
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1
|
||||
#define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div)
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for AT32UC3A3, AT32UC3A4 devices (USBB with high speed support):
|
||||
* \code
|
||||
// Configuration based on 12MHz external OSC:
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0
|
||||
#define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div)
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for AT32UC3C, ATUCXXD, ATUCXXL3U, ATUCXXL4U devices (USBC):
|
||||
* \code
|
||||
// Configuration based on 12MHz external OSC:
|
||||
#define CONFIG_PLL1_SOURCE PLL_SRC_OSC0
|
||||
#define CONFIG_PLL1_MUL 8
|
||||
#define CONFIG_PLL1_DIV 2
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1
|
||||
#define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div)
|
||||
// CPU clock need of clock > 25MHz to run with USBC
|
||||
#define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for SAM3S, SAM3SD, SAM4S devices (UPD: USB Peripheral Device):
|
||||
* \code
|
||||
// PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div)
|
||||
#define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL
|
||||
#define CONFIG_PLL1_MUL 16
|
||||
#define CONFIG_PLL1_DIV 2
|
||||
// USB Clock Source Options (Fusb = FpllX / USB_div)
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1
|
||||
#define CONFIG_USBCLK_DIV 2
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for SAM3U device (UPDHS: USB Peripheral Device High Speed):
|
||||
* \code
|
||||
// USB Clock Source fixed at UPLL.
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clock.h for SAM3X, SAM3A devices (UOTGHS: USB OTG High Speed):
|
||||
* \code
|
||||
// USB Clock Source fixed at UPLL.
|
||||
#define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL
|
||||
#define CONFIG_USBCLK_DIV 1
|
||||
\endcode
|
||||
*
|
||||
* Content of conf_clocks.h for SAMD devices (USB):
|
||||
* \code
|
||||
// System clock bus configuration
|
||||
# define CONF_CLOCK_FLASH_WAIT_STATES 2
|
||||
|
||||
// USB Clock Source fixed at DFLL.
|
||||
// SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop
|
||||
# define CONF_CLOCK_DFLL_ENABLE true
|
||||
# define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY
|
||||
# define CONF_CLOCK_DFLL_ON_DEMAND true
|
||||
|
||||
// Set this to true to configure the GCLK when running clocks_init.
|
||||
// If set to false, none of the GCLK generators will be configured in clocks_init().
|
||||
# define CONF_CLOCK_CONFIGURE_GCLK true
|
||||
|
||||
// Configure GCLK generator 0 (Main Clock)
|
||||
# define CONF_CLOCK_GCLK_0_ENABLE true
|
||||
# define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true
|
||||
# define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL
|
||||
# define CONF_CLOCK_GCLK_0_PRESCALER 1
|
||||
# define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false
|
||||
\endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_use_case_1 Change USB speed
|
||||
*
|
||||
* In this use case, the USB device is used with different USB speeds.
|
||||
*
|
||||
* \section udc_use_case_1_setup Setup steps
|
||||
*
|
||||
* Prior to implement this use case, be sure to have already
|
||||
* apply the UDI module "basic use case".
|
||||
*
|
||||
* \section udc_use_case_1_usage Usage steps
|
||||
*
|
||||
* \subsection udc_use_case_1_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#if // Low speed
|
||||
#define USB_DEVICE_LOW_SPEED
|
||||
// #define USB_DEVICE_HS_SUPPORT
|
||||
|
||||
#elif // Full speed
|
||||
// #define USB_DEVICE_LOW_SPEED
|
||||
// #define USB_DEVICE_HS_SUPPORT
|
||||
|
||||
#elif // High speed
|
||||
// #define USB_DEVICE_LOW_SPEED
|
||||
#define USB_DEVICE_HS_SUPPORT
|
||||
|
||||
#endif
|
||||
\endcode
|
||||
*
|
||||
* \subsection udc_use_case_1_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required for a USB device low speed (1.5Mbit/s):
|
||||
* - \code #define USB_DEVICE_LOW_SPEED
|
||||
//#define USB_DEVICE_HS_SUPPORT \endcode
|
||||
* -# Ensure that conf_usb.h contains the following parameters
|
||||
* required for a USB device full speed (12Mbit/s):
|
||||
* - \code //#define USB_DEVICE_LOW_SPEED
|
||||
//#define USB_DEVICE_HS_SUPPORT \endcode
|
||||
* -# Ensure that conf_usb.h contains the following parameters
|
||||
* required for a USB device high speed (480Mbit/s):
|
||||
* - \code //#define USB_DEVICE_LOW_SPEED
|
||||
#define USB_DEVICE_HS_SUPPORT \endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_use_case_2 Use USB strings
|
||||
*
|
||||
* In this use case, the usual USB strings is added in the USB device.
|
||||
*
|
||||
* \section udc_use_case_2_setup Setup steps
|
||||
* Prior to implement this use case, be sure to have already
|
||||
* apply the UDI module "basic use case".
|
||||
*
|
||||
* \section udc_use_case_2_usage Usage steps
|
||||
*
|
||||
* \subsection udc_use_case_2_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_MANUFACTURE_NAME "Manufacture name"
|
||||
#define USB_DEVICE_PRODUCT_NAME "Product name"
|
||||
#define USB_DEVICE_SERIAL_NAME "12...EF"
|
||||
\endcode
|
||||
*
|
||||
* \subsection udc_use_case_2_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required to enable different USB strings:
|
||||
* - \code // Static ASCII name for the manufacture
|
||||
#define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode
|
||||
* - \code // Static ASCII name for the product
|
||||
#define USB_DEVICE_PRODUCT_NAME "Product name" \endcode
|
||||
* - \code // Static ASCII name to enable and set a serial number
|
||||
#define USB_DEVICE_SERIAL_NAME "12...EF" \endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_use_case_3 Use USB remote wakeup feature
|
||||
*
|
||||
* In this use case, the USB remote wakeup feature is enabled.
|
||||
*
|
||||
* \section udc_use_case_3_setup Setup steps
|
||||
* Prior to implement this use case, be sure to have already
|
||||
* apply the UDI module "basic use case".
|
||||
*
|
||||
* \section udc_use_case_3_usage Usage steps
|
||||
*
|
||||
* \subsection udc_use_case_3_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_ATTR \
|
||||
(USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED)
|
||||
#define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable()
|
||||
extern void my_callback_remotewakeup_enable(void);
|
||||
#define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable()
|
||||
extern void my_callback_remotewakeup_disable(void);
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
void my_callback_remotewakeup_enable(void)
|
||||
{
|
||||
// Enable application wakeup events (e.g. enable GPIO interrupt)
|
||||
}
|
||||
void my_callback_remotewakeup_disable(void)
|
||||
{
|
||||
// Disable application wakeup events (e.g. disable GPIO interrupt)
|
||||
}
|
||||
|
||||
void my_interrupt_event(void)
|
||||
{
|
||||
udc_remotewakeup();
|
||||
}
|
||||
\endcode
|
||||
*
|
||||
* \subsection udc_use_case_3_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required to enable remote wakeup feature:
|
||||
* - \code // Authorizes the remote wakeup feature
|
||||
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode
|
||||
* - \code // Define callback called when the host enables the remotewakeup feature
|
||||
#define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable()
|
||||
extern void my_callback_remotewakeup_enable(void); \endcode
|
||||
* - \code // Define callback called when the host disables the remotewakeup feature
|
||||
#define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable()
|
||||
extern void my_callback_remotewakeup_disable(void); \endcode
|
||||
* -# Send a remote wakeup (USB upstream):
|
||||
* - \code udc_remotewakeup(); \endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_use_case_5 Bus power application recommendations
|
||||
*
|
||||
* In this use case, the USB device BUS power feature is enabled.
|
||||
* This feature requires a correct power consumption management.
|
||||
*
|
||||
* \section udc_use_case_5_setup Setup steps
|
||||
* Prior to implement this use case, be sure to have already
|
||||
* apply the UDI module "basic use case".
|
||||
*
|
||||
* \section udc_use_case_5_usage Usage steps
|
||||
*
|
||||
* \subsection udc_use_case_5_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED)
|
||||
#define UDC_SUSPEND_EVENT() user_callback_suspend_action()
|
||||
extern void user_callback_suspend_action(void)
|
||||
#define UDC_RESUME_EVENT() user_callback_resume_action()
|
||||
extern void user_callback_resume_action(void)
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
void user_callback_suspend_action(void)
|
||||
{
|
||||
// Disable hardware component to reduce power consumption
|
||||
}
|
||||
void user_callback_resume_action(void)
|
||||
{
|
||||
// Re-enable hardware component
|
||||
}
|
||||
\endcode
|
||||
*
|
||||
* \subsection udc_use_case_5_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters:
|
||||
* - \code // Authorizes the BUS power feature
|
||||
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode
|
||||
* - \code // Define callback called when the host suspend the USB line
|
||||
#define UDC_SUSPEND_EVENT() user_callback_suspend_action()
|
||||
extern void user_callback_suspend_action(void); \endcode
|
||||
* - \code // Define callback called when the host or device resume the USB line
|
||||
#define UDC_RESUME_EVENT() user_callback_resume_action()
|
||||
extern void user_callback_resume_action(void); \endcode
|
||||
* -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus):
|
||||
* - \code void user_callback_suspend_action(void)
|
||||
{
|
||||
turn_off_components();
|
||||
} \endcode
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udc_use_case_6 USB dynamic serial number
|
||||
*
|
||||
* In this use case, the USB serial strings is dynamic.
|
||||
* For a static serial string refer to \ref udc_use_case_2.
|
||||
*
|
||||
* \section udc_use_case_6_setup Setup steps
|
||||
* Prior to implement this use case, be sure to have already
|
||||
* apply the UDI module "basic use case".
|
||||
*
|
||||
* \section udc_use_case_6_usage Usage steps
|
||||
*
|
||||
* \subsection udc_use_case_6_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_SERIAL_NAME
|
||||
#define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number
|
||||
#define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12
|
||||
extern uint8_t serial_number[];
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH];
|
||||
|
||||
void init_build_usb_serial_number(void)
|
||||
{
|
||||
serial_number[0] = 'A';
|
||||
serial_number[1] = 'B';
|
||||
...
|
||||
serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C';
|
||||
} \endcode
|
||||
*
|
||||
* \subsection udc_use_case_6_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required to enable a USB serial number strings dynamically:
|
||||
* - \code #define USB_DEVICE_SERIAL_NAME // Define this empty
|
||||
#define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer
|
||||
#define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array
|
||||
extern uint8_t serial_number[]; // Declare external serial array \endcode
|
||||
* -# Before start USB stack, initialize the serial array
|
||||
* - \code
|
||||
uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH];
|
||||
|
||||
void init_build_usb_serial_number(void)
|
||||
{
|
||||
serial_number[0] = 'A';
|
||||
serial_number[1] = 'B';
|
||||
...
|
||||
serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C';
|
||||
} \endcode
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#endif // _UDC_H_
|
135
Marlin/src/HAL/DUE/usb/udc_desc.h
Normal file
135
Marlin/src/HAL/DUE/usb/udc_desc.h
Normal file
@ -0,0 +1,135 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Common API for USB Device Interface
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDC_DESC_H_
|
||||
#define _UDC_DESC_H_
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "usb_protocol.h"
|
||||
#include "udi.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \ingroup udc_group
|
||||
* \defgroup udc_desc_group USB Device Descriptor
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief Defines the memory's location of USB descriptors
|
||||
*
|
||||
* By default the Descriptor is stored in RAM
|
||||
* (UDC_DESC_STORAGE is defined empty).
|
||||
*
|
||||
* If you have need to free RAM space,
|
||||
* it is possible to put descriptor in flash in following case:
|
||||
* - USB driver authorize flash transfer (USBB on UC3 and USB on Mega)
|
||||
* - USB Device is not high speed (UDC no need to change USB descriptors)
|
||||
*
|
||||
* For UC3 application used "const".
|
||||
*
|
||||
* For Mega application used "code".
|
||||
*/
|
||||
#define UDC_DESC_STORAGE
|
||||
// Descriptor storage in internal RAM
|
||||
#if (defined UDC_DATA_USE_HRAM_SUPPORT)
|
||||
# if defined(__GNUC__)
|
||||
# define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0")))
|
||||
# define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0")))
|
||||
# elif defined(__ICCAVR32__)
|
||||
# define UDC_DATA(x) COMPILER_ALIGNED(x) __data32
|
||||
# define UDC_BSS(x) COMPILER_ALIGNED(x) __data32
|
||||
# endif
|
||||
#else
|
||||
# define UDC_DATA(x) COMPILER_ALIGNED(x)
|
||||
# define UDC_BSS(x) COMPILER_ALIGNED(x)
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* \brief Configuration descriptor and UDI link for one USB speed
|
||||
*/
|
||||
typedef struct {
|
||||
//! USB configuration descriptor
|
||||
usb_conf_desc_t UDC_DESC_STORAGE *desc;
|
||||
//! Array of UDI API pointer
|
||||
udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis;
|
||||
} udc_config_speed_t;
|
||||
|
||||
|
||||
/**
|
||||
* \brief All information about the USB Device
|
||||
*/
|
||||
typedef struct {
|
||||
//! USB device descriptor for low or full speed
|
||||
usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs;
|
||||
//! USB configuration descriptor and UDI API pointers for low or full speed
|
||||
udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs;
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
//! USB device descriptor for high speed
|
||||
usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs;
|
||||
//! USB device qualifier, only use in high speed mode
|
||||
usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier;
|
||||
//! USB configuration descriptor and UDI API pointers for high speed
|
||||
udc_config_speed_t UDC_DESC_STORAGE *conf_hs;
|
||||
#endif
|
||||
usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos;
|
||||
} udc_config_t;
|
||||
|
||||
//! Global variables of USB Device Descriptor and UDI links
|
||||
extern UDC_DESC_STORAGE udc_config_t udc_config;
|
||||
|
||||
//@}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // _UDC_DESC_H_
|
396
Marlin/src/HAL/DUE/usb/udd.h
Normal file
396
Marlin/src/HAL/DUE/usb/udd.h
Normal file
@ -0,0 +1,396 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Common API for USB Device Drivers (UDD)
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDD_H_
|
||||
#define _UDD_H_
|
||||
|
||||
#include "usb_protocol.h"
|
||||
#include "udc_desc.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \ingroup usb_device_group
|
||||
* \defgroup udd_group USB Device Driver (UDD)
|
||||
*
|
||||
* The UDD driver provides a low-level abstraction of the device
|
||||
* controller hardware. Most events coming from the hardware such as
|
||||
* interrupts, which may cause the UDD to call into the UDC and UDI.
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! \brief Endpoint identifier
|
||||
typedef uint8_t udd_ep_id_t;
|
||||
|
||||
//! \brief Endpoint transfer status
|
||||
//! Returned in parameters of callback register via udd_ep_run routine.
|
||||
typedef enum {
|
||||
UDD_EP_TRANSFER_OK = 0,
|
||||
UDD_EP_TRANSFER_ABORT = 1,
|
||||
} udd_ep_status_t;
|
||||
|
||||
/**
|
||||
* \brief Global variable to give and record information of the setup request management
|
||||
*
|
||||
* This global variable allows to decode and response a setup request.
|
||||
* It can be updated by udc_process_setup() from UDC or *setup() from UDIs.
|
||||
*/
|
||||
typedef struct {
|
||||
//! Data received in USB SETUP packet
|
||||
//! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD.
|
||||
usb_setup_req_t req;
|
||||
|
||||
//! Point to buffer to send or fill with data following SETUP packet
|
||||
//! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer)
|
||||
uint8_t *payload;
|
||||
|
||||
//! Size of buffer to send or fill, and content the number of byte transfered
|
||||
uint16_t payload_size;
|
||||
|
||||
//! Callback called after reception of ZLP from setup request
|
||||
void (*callback)(void);
|
||||
|
||||
//! Callback called when the buffer given (.payload) is full or empty.
|
||||
//! This one return false to abort data transfer, or true with a new buffer in .payload.
|
||||
bool (*over_under_run)(void);
|
||||
} udd_ctrl_request_t;
|
||||
extern udd_ctrl_request_t udd_g_ctrlreq;
|
||||
|
||||
//! Return true if the setup request \a udd_g_ctrlreq indicates IN data transfer
|
||||
#define Udd_setup_is_in() \
|
||||
(USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK))
|
||||
|
||||
//! Return true if the setup request \a udd_g_ctrlreq indicates OUT data transfer
|
||||
#define Udd_setup_is_out() \
|
||||
(USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK))
|
||||
|
||||
//! Return the type of the SETUP request \a udd_g_ctrlreq. \see usb_reqtype.
|
||||
#define Udd_setup_type() \
|
||||
(udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK)
|
||||
|
||||
//! Return the recipient of the SETUP request \a udd_g_ctrlreq. \see usb_recipient
|
||||
#define Udd_setup_recipient() \
|
||||
(udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK)
|
||||
|
||||
/**
|
||||
* \brief End of halt callback function type.
|
||||
* Registered by routine udd_ep_wait_stall_clear()
|
||||
* Callback called when endpoint stall is cleared.
|
||||
*/
|
||||
typedef void (*udd_callback_halt_cleared_t)(void);
|
||||
|
||||
/**
|
||||
* \brief End of transfer callback function type.
|
||||
* Registered by routine udd_ep_run()
|
||||
* Callback called by USB interrupt after data transfer or abort (reset,...).
|
||||
*
|
||||
* \param status UDD_EP_TRANSFER_OK, if transfer is complete
|
||||
* \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted
|
||||
* \param n number of data transfered
|
||||
*/
|
||||
typedef void (*udd_callback_trans_t) (udd_ep_status_t status,
|
||||
iram_size_t nb_transfered, udd_ep_id_t ep);
|
||||
|
||||
/**
|
||||
* \brief Authorizes the VBUS event
|
||||
*
|
||||
* \return true, if the VBUS monitoring is possible.
|
||||
*/
|
||||
bool udd_include_vbus_monitoring(void);
|
||||
|
||||
/**
|
||||
* \brief Enables the USB Device mode
|
||||
*/
|
||||
void udd_enable(void);
|
||||
|
||||
/**
|
||||
* \brief Disables the USB Device mode
|
||||
*/
|
||||
void udd_disable(void);
|
||||
|
||||
/**
|
||||
* \brief Attach device to the bus when possible
|
||||
*
|
||||
* \warning If a VBus control is included in driver,
|
||||
* then it will attach device when an acceptable Vbus
|
||||
* level from the host is detected.
|
||||
*/
|
||||
void udd_attach(void);
|
||||
|
||||
/**
|
||||
* \brief Detaches the device from the bus
|
||||
*
|
||||
* The driver must remove pull-up on USB line D- or D+.
|
||||
*/
|
||||
void udd_detach(void);
|
||||
|
||||
/**
|
||||
* \brief Test whether the USB Device Controller is running at high
|
||||
* speed or not.
|
||||
*
|
||||
* \return \c true if the Device is running at high speed mode, otherwise \c false.
|
||||
*/
|
||||
bool udd_is_high_speed(void);
|
||||
|
||||
/**
|
||||
* \brief Changes the USB address of device
|
||||
*
|
||||
* \param address New USB address
|
||||
*/
|
||||
void udd_set_address(uint8_t address);
|
||||
|
||||
/**
|
||||
* \brief Returns the USB address of device
|
||||
*
|
||||
* \return USB address
|
||||
*/
|
||||
uint8_t udd_getaddress(void);
|
||||
|
||||
/**
|
||||
* \brief Returns the current start of frame number
|
||||
*
|
||||
* \return current start of frame number.
|
||||
*/
|
||||
uint16_t udd_get_frame_number(void);
|
||||
|
||||
/**
|
||||
* \brief Returns the current micro start of frame number
|
||||
*
|
||||
* \return current micro start of frame number required in high speed mode.
|
||||
*/
|
||||
uint16_t udd_get_micro_frame_number(void);
|
||||
|
||||
/*! \brief The USB driver sends a resume signal called Upstream Resume
|
||||
*/
|
||||
void udd_send_remotewakeup(void);
|
||||
|
||||
/**
|
||||
* \brief Load setup payload
|
||||
*
|
||||
* \param payload Pointer on payload
|
||||
* \param payload_size Size of payload
|
||||
*/
|
||||
void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size );
|
||||
|
||||
|
||||
/**
|
||||
* \name Endpoint Management
|
||||
*
|
||||
* The following functions allow drivers to create and remove
|
||||
* endpoints, as well as set, clear and query their "halted" and
|
||||
* "wedged" states.
|
||||
*/
|
||||
//@{
|
||||
|
||||
#if (USB_DEVICE_MAX_EP != 0)
|
||||
|
||||
/**
|
||||
* \brief Configures and enables an endpoint
|
||||
*
|
||||
* \param ep Endpoint number including direction (USB_EP_DIR_IN/USB_EP_DIR_OUT).
|
||||
* \param bmAttributes Attributes of endpoint declared in the descriptor.
|
||||
* \param MaxEndpointSize Endpoint maximum size
|
||||
*
|
||||
* \return \c 1 if the endpoint is enabled, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes,
|
||||
uint16_t MaxEndpointSize);
|
||||
|
||||
/**
|
||||
* \brief Disables an endpoint
|
||||
*
|
||||
* \param ep Endpoint number including direction (USB_EP_DIR_IN/USB_EP_DIR_OUT).
|
||||
*/
|
||||
void udd_ep_free(udd_ep_id_t ep);
|
||||
|
||||
/**
|
||||
* \brief Check if the endpoint \a ep is halted.
|
||||
*
|
||||
* \param ep The ID of the endpoint to check.
|
||||
*
|
||||
* \return \c 1 if \a ep is halted, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_is_halted(udd_ep_id_t ep);
|
||||
|
||||
/**
|
||||
* \brief Set the halted state of the endpoint \a ep
|
||||
*
|
||||
* After calling this function, any transaction on \a ep will result
|
||||
* in a STALL handshake being sent. Any pending transactions will be
|
||||
* performed first, however.
|
||||
*
|
||||
* \param ep The ID of the endpoint to be halted
|
||||
*
|
||||
* \return \c 1 if \a ep is halted, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_set_halt(udd_ep_id_t ep);
|
||||
|
||||
/**
|
||||
* \brief Clear the halted state of the endpoint \a ep
|
||||
*
|
||||
* After calling this function, any transaction on \a ep will
|
||||
* be handled normally, i.e. a STALL handshake will not be sent, and
|
||||
* the data toggle sequence will start at DATA0.
|
||||
*
|
||||
* \param ep The ID of the endpoint to be un-halted
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_clear_halt(udd_ep_id_t ep);
|
||||
|
||||
/**
|
||||
* \brief Registers a callback to call when endpoint halt is cleared
|
||||
*
|
||||
* \param ep The ID of the endpoint to use
|
||||
* \param callback NULL or function to call when endpoint halt is cleared
|
||||
*
|
||||
* \warning if the endpoint is not halted then the \a callback is called immediately.
|
||||
*
|
||||
* \return \c 1 if the register is accepted, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_wait_stall_clear(udd_ep_id_t ep,
|
||||
udd_callback_halt_cleared_t callback);
|
||||
|
||||
/**
|
||||
* \brief Allows to receive or send data on an endpoint
|
||||
*
|
||||
* The driver uses a specific DMA USB to transfer data
|
||||
* from internal RAM to endpoint, if this one is available.
|
||||
* When the transfer is finished or aborted (stall, reset, ...), the \a callback is called.
|
||||
* The \a callback returns the transfer status and eventually the number of byte transfered.
|
||||
* Note: The control endpoint is not authorized.
|
||||
*
|
||||
* \param ep The ID of the endpoint to use
|
||||
* \param b_shortpacket Enabled automatic short packet
|
||||
* \param buf Buffer on Internal RAM to send or fill.
|
||||
* It must be align, then use COMPILER_WORD_ALIGNED.
|
||||
* \param buf_size Buffer size to send or fill
|
||||
* \param callback NULL or function to call at the end of transfer
|
||||
*
|
||||
* \warning About \a b_shortpacket, for IN endpoint it means that a short packet
|
||||
* (or a Zero Length Packet) will be sent to the USB line to properly close the usb
|
||||
* transfer at the end of the data transfer.
|
||||
* For Bulk and Interrupt OUT endpoint, it will automatically stop the transfer
|
||||
* at the end of the data transfer (received short packet).
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket,
|
||||
uint8_t * buf, iram_size_t buf_size,
|
||||
udd_callback_trans_t callback);
|
||||
/**
|
||||
* \brief Aborts transfer on going on endpoint
|
||||
*
|
||||
* If a transfer is on going, then it is stopped and
|
||||
* the callback registered is called to signal the end of transfer.
|
||||
* Note: The control endpoint is not authorized.
|
||||
*
|
||||
* \param ep Endpoint to abort
|
||||
*/
|
||||
void udd_ep_abort(udd_ep_id_t ep);
|
||||
|
||||
#endif
|
||||
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* \name High speed test mode management
|
||||
*
|
||||
* The following functions allow the device to jump to a specific test mode required in high speed mode.
|
||||
*/
|
||||
//@{
|
||||
void udd_test_mode_j(void);
|
||||
void udd_test_mode_k(void);
|
||||
void udd_test_mode_se0_nak(void);
|
||||
void udd_test_mode_packet(void);
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* \name UDC callbacks to provide for UDD
|
||||
*
|
||||
* The following callbacks are used by UDD.
|
||||
*/
|
||||
//@{
|
||||
|
||||
/**
|
||||
* \brief Decodes and manages a setup request
|
||||
*
|
||||
* The driver call it when a SETUP packet is received.
|
||||
* The \c udd_g_ctrlreq contains the data of SETUP packet.
|
||||
* If this callback accepts the setup request then it must
|
||||
* return \c 1 and eventually update \c udd_g_ctrlreq to send or receive data.
|
||||
*
|
||||
* \return \c 1 if the request is accepted, otherwise \c 0.
|
||||
*/
|
||||
extern bool udc_process_setup(void);
|
||||
|
||||
/**
|
||||
* \brief Reset the UDC
|
||||
*
|
||||
* The UDC must reset all configuration.
|
||||
*/
|
||||
extern void udc_reset(void);
|
||||
|
||||
/**
|
||||
* \brief To signal that a SOF is occurred
|
||||
*
|
||||
* The UDC must send the signal to all UDIs enabled
|
||||
*/
|
||||
extern void udc_sof_notify(void);
|
||||
|
||||
//@}
|
||||
|
||||
//@}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // _UDD_H_
|
133
Marlin/src/HAL/DUE/usb/udi.h
Normal file
133
Marlin/src/HAL/DUE/usb/udi.h
Normal file
@ -0,0 +1,133 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Common API for USB Device Interface
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDI_H_
|
||||
#define _UDI_H_
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "usb_protocol.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \ingroup usb_device_group
|
||||
* \defgroup udi_group USB Device Interface (UDI)
|
||||
* The UDI provides a common API for all classes,
|
||||
* and this is used by UDC for the main control of USB Device interface.
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief UDI API.
|
||||
*
|
||||
* The callbacks within this structure are called only by
|
||||
* USB Device Controller (UDC)
|
||||
*
|
||||
* The udc_get_interface_desc() can be use by UDI to know the interface descriptor
|
||||
* selected by UDC.
|
||||
*/
|
||||
typedef struct {
|
||||
/**
|
||||
* \brief Enable the interface.
|
||||
*
|
||||
* This function is called when the host selects a configuration
|
||||
* to which this interface belongs through a Set Configuration
|
||||
* request, and when the host selects an alternate setting of
|
||||
* this interface through a Set Interface request.
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
bool (*enable)(void);
|
||||
|
||||
/**
|
||||
* \brief Disable the interface.
|
||||
*
|
||||
* This function is called when this interface is currently
|
||||
* active, and
|
||||
* - the host selects any configuration through a Set
|
||||
* Configuration request, or
|
||||
* - the host issues a USB reset, or
|
||||
* - the device is detached from the host (i.e. Vbus is no
|
||||
* longer present)
|
||||
*/
|
||||
void (*disable)(void);
|
||||
|
||||
/**
|
||||
* \brief Handle a control request directed at an interface.
|
||||
*
|
||||
* This function is called when this interface is currently
|
||||
* active and the host sends a SETUP request
|
||||
* with this interface as the recipient.
|
||||
*
|
||||
* Use udd_g_ctrlreq to decode and response to SETUP request.
|
||||
*
|
||||
* \return \c 1 if this interface supports the SETUP request, otherwise \c 0.
|
||||
*/
|
||||
bool (*setup)(void);
|
||||
|
||||
/**
|
||||
* \brief Returns the current setting of the selected interface.
|
||||
*
|
||||
* This function is called when UDC when know alternate setting of selected interface.
|
||||
*
|
||||
* \return alternate setting of selected interface
|
||||
*/
|
||||
uint8_t (*getsetting)(void);
|
||||
|
||||
/**
|
||||
* \brief To signal that a SOF is occurred
|
||||
*/
|
||||
void (*sof_notify)(void);
|
||||
} udi_api_t;
|
||||
|
||||
//@}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // _UDI_H_
|
1155
Marlin/src/HAL/DUE/usb/udi_cdc.c
Normal file
1155
Marlin/src/HAL/DUE/usb/udi_cdc.c
Normal file
File diff suppressed because it is too large
Load Diff
810
Marlin/src/HAL/DUE/usb/udi_cdc.h
Normal file
810
Marlin/src/HAL/DUE/usb/udi_cdc.h
Normal file
@ -0,0 +1,810 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB Device Communication Device Class (CDC) interface definitions.
|
||||
*
|
||||
* Copyright (c) 2009-2016 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDI_CDC_H_
|
||||
#define _UDI_CDC_H_
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "usb_protocol.h"
|
||||
#include "usb_protocol_cdc.h"
|
||||
#include "udd.h"
|
||||
#include "udc_desc.h"
|
||||
#include "udi.h"
|
||||
|
||||
// Check the number of port
|
||||
#ifndef UDI_CDC_PORT_NB
|
||||
# define UDI_CDC_PORT_NB 1
|
||||
#endif
|
||||
#if (UDI_CDC_PORT_NB < 1) || (UDI_CDC_PORT_NB > 7)
|
||||
# error UDI_CDC_PORT_NB must be between 1 and 7
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \addtogroup udi_cdc_group_udc
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Global structure which contains standard UDI API for UDC
|
||||
extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_comm;
|
||||
extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_data;
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \ingroup udi_cdc_group
|
||||
* \defgroup udi_cdc_group_desc USB interface descriptors
|
||||
*
|
||||
* The following structures provide predefined USB interface descriptors.
|
||||
* It must be used to define the final USB descriptors.
|
||||
*/
|
||||
//@{
|
||||
|
||||
/**
|
||||
* \brief Communication Class interface descriptor
|
||||
*
|
||||
* Interface descriptor with associated functional and endpoint
|
||||
* descriptors for the CDC Communication Class interface.
|
||||
*/
|
||||
typedef struct {
|
||||
//! Standard interface descriptor
|
||||
usb_iface_desc_t iface;
|
||||
//! CDC Header functional descriptor
|
||||
usb_cdc_hdr_desc_t header;
|
||||
//! CDC Abstract Control Model functional descriptor
|
||||
usb_cdc_acm_desc_t acm;
|
||||
//! CDC Union functional descriptor
|
||||
usb_cdc_union_desc_t union_desc;
|
||||
//! CDC Call Management functional descriptor
|
||||
usb_cdc_call_mgmt_desc_t call_mgmt;
|
||||
//! Notification endpoint descriptor
|
||||
usb_ep_desc_t ep_notify;
|
||||
} udi_cdc_comm_desc_t;
|
||||
|
||||
|
||||
/**
|
||||
* \brief Data Class interface descriptor
|
||||
*
|
||||
* Interface descriptor with associated endpoint descriptors for the
|
||||
* CDC Data Class interface.
|
||||
*/
|
||||
typedef struct {
|
||||
//! Standard interface descriptor
|
||||
usb_iface_desc_t iface;
|
||||
//! Data IN/OUT endpoint descriptors
|
||||
usb_ep_desc_t ep_in;
|
||||
usb_ep_desc_t ep_out;
|
||||
} udi_cdc_data_desc_t;
|
||||
|
||||
|
||||
//! CDC communication endpoints size for all speeds
|
||||
#define UDI_CDC_COMM_EP_SIZE 64
|
||||
//! CDC data endpoints size for FS speed (8B, 16B, 32B, 64B)
|
||||
#define UDI_CDC_DATA_EPS_FS_SIZE 64
|
||||
//! CDC data endpoints size for HS speed (512B only)
|
||||
#define UDI_CDC_DATA_EPS_HS_SIZE 512
|
||||
|
||||
/**
|
||||
* \name Content of interface descriptors
|
||||
* Up to 7 CDC interfaces can be implemented on a USB device.
|
||||
*/
|
||||
//@{
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_0
|
||||
#define UDI_CDC_IAD_STRING_ID_0 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_0
|
||||
#define UDI_CDC_COMM_STRING_ID_0 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_0
|
||||
#define UDI_CDC_DATA_STRING_ID_0 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_0 UDI_CDC_IAD_DESC(0)
|
||||
#define UDI_CDC_COMM_DESC_0 UDI_CDC_COMM_DESC(0)
|
||||
#define UDI_CDC_DATA_DESC_0_FS UDI_CDC_DATA_DESC_FS(0)
|
||||
#define UDI_CDC_DATA_DESC_0_HS UDI_CDC_DATA_DESC_HS(0)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_1
|
||||
#define UDI_CDC_IAD_STRING_ID_1 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_1
|
||||
#define UDI_CDC_COMM_STRING_ID_1 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_1
|
||||
#define UDI_CDC_DATA_STRING_ID_1 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_1 UDI_CDC_IAD_DESC(1)
|
||||
#define UDI_CDC_COMM_DESC_1 UDI_CDC_COMM_DESC(1)
|
||||
#define UDI_CDC_DATA_DESC_1_FS UDI_CDC_DATA_DESC_FS(1)
|
||||
#define UDI_CDC_DATA_DESC_1_HS UDI_CDC_DATA_DESC_HS(1)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_2
|
||||
#define UDI_CDC_IAD_STRING_ID_2 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_2
|
||||
#define UDI_CDC_COMM_STRING_ID_2 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_2
|
||||
#define UDI_CDC_DATA_STRING_ID_2 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_2 UDI_CDC_IAD_DESC(2)
|
||||
#define UDI_CDC_COMM_DESC_2 UDI_CDC_COMM_DESC(2)
|
||||
#define UDI_CDC_DATA_DESC_2_FS UDI_CDC_DATA_DESC_FS(2)
|
||||
#define UDI_CDC_DATA_DESC_2_HS UDI_CDC_DATA_DESC_HS(2)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_3
|
||||
#define UDI_CDC_IAD_STRING_ID_3 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_3
|
||||
#define UDI_CDC_COMM_STRING_ID_3 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_3
|
||||
#define UDI_CDC_DATA_STRING_ID_3 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_3 UDI_CDC_IAD_DESC(3)
|
||||
#define UDI_CDC_COMM_DESC_3 UDI_CDC_COMM_DESC(3)
|
||||
#define UDI_CDC_DATA_DESC_3_FS UDI_CDC_DATA_DESC_FS(3)
|
||||
#define UDI_CDC_DATA_DESC_3_HS UDI_CDC_DATA_DESC_HS(3)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_4
|
||||
#define UDI_CDC_IAD_STRING_ID_4 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_4
|
||||
#define UDI_CDC_COMM_STRING_ID_4 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_4
|
||||
#define UDI_CDC_DATA_STRING_ID_4 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_4 UDI_CDC_IAD_DESC(4)
|
||||
#define UDI_CDC_COMM_DESC_4 UDI_CDC_COMM_DESC(4)
|
||||
#define UDI_CDC_DATA_DESC_4_FS UDI_CDC_DATA_DESC_FS(4)
|
||||
#define UDI_CDC_DATA_DESC_4_HS UDI_CDC_DATA_DESC_HS(4)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_5
|
||||
#define UDI_CDC_IAD_STRING_ID_5 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_5
|
||||
#define UDI_CDC_COMM_STRING_ID_5 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_5
|
||||
#define UDI_CDC_DATA_STRING_ID_5 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_5 UDI_CDC_IAD_DESC(5)
|
||||
#define UDI_CDC_COMM_DESC_5 UDI_CDC_COMM_DESC(5)
|
||||
#define UDI_CDC_DATA_DESC_5_FS UDI_CDC_DATA_DESC_FS(5)
|
||||
#define UDI_CDC_DATA_DESC_5_HS UDI_CDC_DATA_DESC_HS(5)
|
||||
|
||||
//! By default no string associated to these interfaces
|
||||
#ifndef UDI_CDC_IAD_STRING_ID_6
|
||||
#define UDI_CDC_IAD_STRING_ID_6 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_COMM_STRING_ID_6
|
||||
#define UDI_CDC_COMM_STRING_ID_6 0
|
||||
#endif
|
||||
#ifndef UDI_CDC_DATA_STRING_ID_6
|
||||
#define UDI_CDC_DATA_STRING_ID_6 0
|
||||
#endif
|
||||
#define UDI_CDC_IAD_DESC_6 UDI_CDC_IAD_DESC(6)
|
||||
#define UDI_CDC_COMM_DESC_6 UDI_CDC_COMM_DESC(6)
|
||||
#define UDI_CDC_DATA_DESC_6_FS UDI_CDC_DATA_DESC_FS(6)
|
||||
#define UDI_CDC_DATA_DESC_6_HS UDI_CDC_DATA_DESC_HS(6)
|
||||
//@}
|
||||
|
||||
|
||||
//! Content of CDC IAD interface descriptor for all speeds
|
||||
#define UDI_CDC_IAD_DESC(port) { \
|
||||
.bLength = sizeof(usb_iad_desc_t),\
|
||||
.bDescriptorType = USB_DT_IAD,\
|
||||
.bInterfaceCount = 2,\
|
||||
.bFunctionClass = CDC_CLASS_COMM,\
|
||||
.bFunctionSubClass = CDC_SUBCLASS_ACM,\
|
||||
.bFunctionProtocol = CDC_PROTOCOL_V25TER,\
|
||||
.bFirstInterface = UDI_CDC_COMM_IFACE_NUMBER_##port,\
|
||||
.iFunction = UDI_CDC_IAD_STRING_ID_##port,\
|
||||
}
|
||||
|
||||
//! Content of CDC COMM interface descriptor for all speeds
|
||||
#define UDI_CDC_COMM_DESC(port) { \
|
||||
.iface.bLength = sizeof(usb_iface_desc_t),\
|
||||
.iface.bDescriptorType = USB_DT_INTERFACE,\
|
||||
.iface.bAlternateSetting = 0,\
|
||||
.iface.bNumEndpoints = 1,\
|
||||
.iface.bInterfaceClass = CDC_CLASS_COMM,\
|
||||
.iface.bInterfaceSubClass = CDC_SUBCLASS_ACM,\
|
||||
.iface.bInterfaceProtocol = CDC_PROTOCOL_V25TER,\
|
||||
.header.bFunctionLength = sizeof(usb_cdc_hdr_desc_t),\
|
||||
.header.bDescriptorType = CDC_CS_INTERFACE,\
|
||||
.header.bDescriptorSubtype = CDC_SCS_HEADER,\
|
||||
.header.bcdCDC = LE16(0x0110),\
|
||||
.call_mgmt.bFunctionLength = sizeof(usb_cdc_call_mgmt_desc_t),\
|
||||
.call_mgmt.bDescriptorType = CDC_CS_INTERFACE,\
|
||||
.call_mgmt.bDescriptorSubtype = CDC_SCS_CALL_MGMT,\
|
||||
.call_mgmt.bmCapabilities = \
|
||||
CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\
|
||||
.acm.bFunctionLength = sizeof(usb_cdc_acm_desc_t),\
|
||||
.acm.bDescriptorType = CDC_CS_INTERFACE,\
|
||||
.acm.bDescriptorSubtype = CDC_SCS_ACM,\
|
||||
.acm.bmCapabilities = CDC_ACM_SUPPORT_LINE_REQUESTS,\
|
||||
.union_desc.bFunctionLength = sizeof(usb_cdc_union_desc_t),\
|
||||
.union_desc.bDescriptorType = CDC_CS_INTERFACE,\
|
||||
.union_desc.bDescriptorSubtype= CDC_SCS_UNION,\
|
||||
.ep_notify.bLength = sizeof(usb_ep_desc_t),\
|
||||
.ep_notify.bDescriptorType = USB_DT_ENDPOINT,\
|
||||
.ep_notify.bmAttributes = USB_EP_TYPE_INTERRUPT,\
|
||||
.ep_notify.wMaxPacketSize = LE16(UDI_CDC_COMM_EP_SIZE),\
|
||||
.ep_notify.bInterval = 0x10,\
|
||||
.ep_notify.bEndpointAddress = UDI_CDC_COMM_EP_##port,\
|
||||
.iface.bInterfaceNumber = UDI_CDC_COMM_IFACE_NUMBER_##port,\
|
||||
.call_mgmt.bDataInterface = UDI_CDC_DATA_IFACE_NUMBER_##port,\
|
||||
.union_desc.bMasterInterface = UDI_CDC_COMM_IFACE_NUMBER_##port,\
|
||||
.union_desc.bSlaveInterface0 = UDI_CDC_DATA_IFACE_NUMBER_##port,\
|
||||
.iface.iInterface = UDI_CDC_COMM_STRING_ID_##port,\
|
||||
}
|
||||
|
||||
//! Content of CDC DATA interface descriptors
|
||||
#define UDI_CDC_DATA_DESC_COMMON \
|
||||
.iface.bLength = sizeof(usb_iface_desc_t),\
|
||||
.iface.bDescriptorType = USB_DT_INTERFACE,\
|
||||
.iface.bAlternateSetting = 0,\
|
||||
.iface.bNumEndpoints = 2,\
|
||||
.iface.bInterfaceClass = CDC_CLASS_DATA,\
|
||||
.iface.bInterfaceSubClass = 0,\
|
||||
.iface.bInterfaceProtocol = 0,\
|
||||
.ep_in.bLength = sizeof(usb_ep_desc_t),\
|
||||
.ep_in.bDescriptorType = USB_DT_ENDPOINT,\
|
||||
.ep_in.bmAttributes = USB_EP_TYPE_BULK,\
|
||||
.ep_in.bInterval = 0,\
|
||||
.ep_out.bLength = sizeof(usb_ep_desc_t),\
|
||||
.ep_out.bDescriptorType = USB_DT_ENDPOINT,\
|
||||
.ep_out.bmAttributes = USB_EP_TYPE_BULK,\
|
||||
.ep_out.bInterval = 0,
|
||||
|
||||
#define UDI_CDC_DATA_DESC_FS(port) { \
|
||||
UDI_CDC_DATA_DESC_COMMON \
|
||||
.ep_in.wMaxPacketSize = LE16(UDI_CDC_DATA_EPS_FS_SIZE),\
|
||||
.ep_out.wMaxPacketSize = LE16(UDI_CDC_DATA_EPS_FS_SIZE),\
|
||||
.ep_in.bEndpointAddress = UDI_CDC_DATA_EP_IN_##port,\
|
||||
.ep_out.bEndpointAddress = UDI_CDC_DATA_EP_OUT_##port,\
|
||||
.iface.bInterfaceNumber = UDI_CDC_DATA_IFACE_NUMBER_##port,\
|
||||
.iface.iInterface = UDI_CDC_DATA_STRING_ID_##port,\
|
||||
}
|
||||
|
||||
#define UDI_CDC_DATA_DESC_HS(port) { \
|
||||
UDI_CDC_DATA_DESC_COMMON \
|
||||
.ep_in.wMaxPacketSize = LE16(UDI_CDC_DATA_EPS_HS_SIZE),\
|
||||
.ep_out.wMaxPacketSize = LE16(UDI_CDC_DATA_EPS_HS_SIZE),\
|
||||
.ep_in.bEndpointAddress = UDI_CDC_DATA_EP_IN_##port,\
|
||||
.ep_out.bEndpointAddress = UDI_CDC_DATA_EP_OUT_##port,\
|
||||
.iface.bInterfaceNumber = UDI_CDC_DATA_IFACE_NUMBER_##port,\
|
||||
.iface.iInterface = UDI_CDC_DATA_STRING_ID_##port,\
|
||||
}
|
||||
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \ingroup udi_group
|
||||
* \defgroup udi_cdc_group USB Device Interface (UDI) for Communication Class Device (CDC)
|
||||
*
|
||||
* Common APIs used by high level application to use this USB class.
|
||||
*
|
||||
* These routines are used to transfer and control data
|
||||
* to/from USB CDC endpoint.
|
||||
*
|
||||
* See \ref udi_cdc_quickstart.
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \name Interface for application with single CDC interface support
|
||||
*/
|
||||
//@{
|
||||
|
||||
/**
|
||||
* \brief Notify a state change of DCD signal
|
||||
*
|
||||
* \param b_set DCD is enabled if true, else disabled
|
||||
*/
|
||||
void udi_cdc_ctrl_signal_dcd(bool b_set);
|
||||
|
||||
/**
|
||||
* \brief Notify a state change of DSR signal
|
||||
*
|
||||
* \param b_set DSR is enabled if true, else disabled
|
||||
*/
|
||||
void udi_cdc_ctrl_signal_dsr(bool b_set);
|
||||
|
||||
/**
|
||||
* \brief Notify a framing error
|
||||
*/
|
||||
void udi_cdc_signal_framing_error(void);
|
||||
|
||||
/**
|
||||
* \brief Notify a parity error
|
||||
*/
|
||||
void udi_cdc_signal_parity_error(void);
|
||||
|
||||
/**
|
||||
* \brief Notify a overrun
|
||||
*/
|
||||
void udi_cdc_signal_overrun(void);
|
||||
|
||||
/**
|
||||
* \brief Gets the number of byte received
|
||||
*
|
||||
* \return the number of data available
|
||||
*/
|
||||
iram_size_t udi_cdc_get_nb_received_data(void);
|
||||
|
||||
/**
|
||||
* \brief This function checks if a character has been received on the CDC line
|
||||
*
|
||||
* \return \c 1 if a byte is ready to be read.
|
||||
*/
|
||||
bool udi_cdc_is_rx_ready(void);
|
||||
|
||||
/**
|
||||
* \brief Waits and gets a value on CDC line
|
||||
*
|
||||
* \return value read on CDC line
|
||||
*/
|
||||
int udi_cdc_getc(void);
|
||||
|
||||
/**
|
||||
* \brief Reads a RAM buffer on CDC line
|
||||
*
|
||||
* \param buf Values read
|
||||
* \param size Number of value read
|
||||
*
|
||||
* \return the number of data remaining
|
||||
*/
|
||||
iram_size_t udi_cdc_read_buf(void* buf, iram_size_t size);
|
||||
|
||||
/**
|
||||
* \brief Non polling reads of a up to 'size' data from CDC line
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param buf Buffer where to store read data
|
||||
* \param size Maximum number of data to read (size of buffer)
|
||||
*
|
||||
* \return the number of data effectively read
|
||||
*/
|
||||
iram_size_t udi_cdc_read_no_polling(void* buf, iram_size_t size);
|
||||
|
||||
/**
|
||||
* \brief Gets the number of free byte in TX buffer
|
||||
*
|
||||
* \return the number of free byte in TX buffer
|
||||
*/
|
||||
iram_size_t udi_cdc_get_free_tx_buffer(void);
|
||||
|
||||
/**
|
||||
* \brief This function checks if a new character sent is possible
|
||||
* The type int is used to support scanf redirection from compiler LIB.
|
||||
*
|
||||
* \return \c 1 if a new character can be sent
|
||||
*/
|
||||
bool udi_cdc_is_tx_ready(void);
|
||||
|
||||
/**
|
||||
* \brief Puts a byte on CDC line
|
||||
* The type int is used to support printf redirection from compiler LIB.
|
||||
*
|
||||
* \param value Value to put
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
int udi_cdc_putc(int value);
|
||||
|
||||
/**
|
||||
* \brief Writes a RAM buffer on CDC line
|
||||
*
|
||||
* \param buf Values to write
|
||||
* \param size Number of value to write
|
||||
*
|
||||
* \return the number of data remaining
|
||||
*/
|
||||
iram_size_t udi_cdc_write_buf(const void* buf, iram_size_t size);
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \name Interface for application with multi CDC interfaces support
|
||||
*/
|
||||
//@{
|
||||
|
||||
/**
|
||||
* \brief Notify a state change of DCD signal
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param b_set DCD is enabled if true, else disabled
|
||||
*/
|
||||
void udi_cdc_multi_ctrl_signal_dcd(uint8_t port, bool b_set);
|
||||
|
||||
/**
|
||||
* \brief Notify a state change of DSR signal
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param b_set DSR is enabled if true, else disabled
|
||||
*/
|
||||
void udi_cdc_multi_ctrl_signal_dsr(uint8_t port, bool b_set);
|
||||
|
||||
/**
|
||||
* \brief Notify a framing error
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*/
|
||||
void udi_cdc_multi_signal_framing_error(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Notify a parity error
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*/
|
||||
void udi_cdc_multi_signal_parity_error(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Notify a overrun
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*/
|
||||
void udi_cdc_multi_signal_overrun(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Gets the number of byte received
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*
|
||||
* \return the number of data available
|
||||
*/
|
||||
iram_size_t udi_cdc_multi_get_nb_received_data(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief This function checks if a character has been received on the CDC line
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*
|
||||
* \return \c 1 if a byte is ready to be read.
|
||||
*/
|
||||
bool udi_cdc_multi_is_rx_ready(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Waits and gets a value on CDC line
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*
|
||||
* \return value read on CDC line
|
||||
*/
|
||||
int udi_cdc_multi_getc(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Reads a RAM buffer on CDC line
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param buf Values read
|
||||
* \param size Number of values read
|
||||
*
|
||||
* \return the number of data remaining
|
||||
*/
|
||||
iram_size_t udi_cdc_multi_read_buf(uint8_t port, void* buf, iram_size_t size);
|
||||
|
||||
/**
|
||||
* \brief Gets the number of free byte in TX buffer
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*
|
||||
* \return the number of free byte in TX buffer
|
||||
*/
|
||||
iram_size_t udi_cdc_multi_get_free_tx_buffer(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief This function checks if a new character sent is possible
|
||||
* The type int is used to support scanf redirection from compiler LIB.
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
*
|
||||
* \return \c 1 if a new character can be sent
|
||||
*/
|
||||
bool udi_cdc_multi_is_tx_ready(uint8_t port);
|
||||
|
||||
/**
|
||||
* \brief Puts a byte on CDC line
|
||||
* The type int is used to support printf redirection from compiler LIB.
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param value Value to put
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
int udi_cdc_multi_putc(uint8_t port, int value);
|
||||
|
||||
/**
|
||||
* \brief Writes a RAM buffer on CDC line
|
||||
*
|
||||
* \param port Communication port number to manage
|
||||
* \param buf Values to write
|
||||
* \param size Number of value to write
|
||||
*
|
||||
* \return the number of data remaining
|
||||
*/
|
||||
iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t size);
|
||||
//@}
|
||||
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \page udi_cdc_quickstart Quick start guide for USB device Communication Class Device module (UDI CDC)
|
||||
*
|
||||
* This is the quick start guide for the \ref udi_cdc_group
|
||||
* "USB device interface CDC module (UDI CDC)" with step-by-step instructions on
|
||||
* how to configure and use the modules in a selection of use cases.
|
||||
*
|
||||
* The use cases contain several code fragments. The code fragments in the
|
||||
* steps for setup can be copied into a custom initialization function, while
|
||||
* the steps for usage can be copied into, e.g., the main application function.
|
||||
*
|
||||
* \section udi_cdc_basic_use_case Basic use case
|
||||
* In this basic use case, the "USB CDC (Single Interface Device)" module is used
|
||||
* with only one communication port.
|
||||
* The "USB CDC (Composite Device)" module usage is described in \ref udi_cdc_use_cases
|
||||
* "Advanced use cases".
|
||||
*
|
||||
* \section udi_cdc_basic_use_case_setup Setup steps
|
||||
* \subsection udi_cdc_basic_use_case_setup_prereq Prerequisites
|
||||
* \copydetails udc_basic_use_case_setup_prereq
|
||||
* \subsection udi_cdc_basic_use_case_setup_code Example code
|
||||
* \copydetails udc_basic_use_case_setup_code
|
||||
* \subsection udi_cdc_basic_use_case_setup_flow Workflow
|
||||
* \copydetails udc_basic_use_case_setup_flow
|
||||
*
|
||||
* \section udi_cdc_basic_use_case_usage Usage steps
|
||||
*
|
||||
* \subsection udi_cdc_basic_use_case_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable()
|
||||
extern bool my_callback_cdc_enable(void);
|
||||
#define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable()
|
||||
extern void my_callback_cdc_disable(void);
|
||||
#define UDI_CDC_LOW_RATE
|
||||
|
||||
#define UDI_CDC_DEFAULT_RATE 115200
|
||||
#define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1
|
||||
#define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE
|
||||
#define UDI_CDC_DEFAULT_DATABITS 8
|
||||
|
||||
#include "udi_cdc_conf.h" // At the end of conf_usb.h file
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
static bool my_flag_autorize_cdc_transfert = false;
|
||||
bool my_callback_cdc_enable(void)
|
||||
{
|
||||
my_flag_autorize_cdc_transfert = true;
|
||||
return true;
|
||||
}
|
||||
void my_callback_cdc_disable(void)
|
||||
{
|
||||
my_flag_autorize_cdc_transfert = false;
|
||||
}
|
||||
|
||||
void task(void)
|
||||
{
|
||||
if (my_flag_autorize_cdc_transfert) {
|
||||
udi_cdc_putc('A');
|
||||
udi_cdc_getc();
|
||||
}
|
||||
}
|
||||
\endcode
|
||||
*
|
||||
* \subsection udi_cdc_basic_use_case_setup_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following configuration,
|
||||
* which is the USB device CDC configuration:
|
||||
* - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode
|
||||
* \note The USB serial number is mandatory when a CDC interface is used.
|
||||
* - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable()
|
||||
extern bool my_callback_cdc_enable(void); \endcode
|
||||
* \note After the device enumeration (detecting and identifying USB devices),
|
||||
* the USB host starts the device configuration. When the USB CDC interface
|
||||
* from the device is accepted by the host, the USB host enables this interface and the
|
||||
* UDI_CDC_ENABLE_EXT() callback function is called and return true.
|
||||
* Thus, when this event is received, the data transfer on CDC interface are authorized.
|
||||
* - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable()
|
||||
extern void my_callback_cdc_disable(void); \endcode
|
||||
* \note When the USB device is unplugged or is reset by the USB host, the USB
|
||||
* interface is disabled and the UDI_CDC_DISABLE_EXT() callback function
|
||||
* is called. Thus, the data transfer must be stopped on CDC interface.
|
||||
* - \code #define UDI_CDC_LOW_RATE \endcode
|
||||
* \note Define it when the transfer CDC Device to Host is a low rate
|
||||
* (<512000 bauds) to reduce CDC buffers size.
|
||||
* - \code #define UDI_CDC_DEFAULT_RATE 115200
|
||||
#define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1
|
||||
#define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE
|
||||
#define UDI_CDC_DEFAULT_DATABITS 8 \endcode
|
||||
* \note Default configuration of communication port at startup.
|
||||
* -# Send or wait data on CDC line:
|
||||
* - \code // Waits and gets a value on CDC line
|
||||
int udi_cdc_getc(void);
|
||||
// Reads a RAM buffer on CDC line
|
||||
iram_size_t udi_cdc_read_buf(int* buf, iram_size_t size);
|
||||
// Puts a byte on CDC line
|
||||
int udi_cdc_putc(int value);
|
||||
// Writes a RAM buffer on CDC line
|
||||
iram_size_t udi_cdc_write_buf(const int* buf, iram_size_t size); \endcode
|
||||
*
|
||||
* \section udi_cdc_use_cases Advanced use cases
|
||||
* For more advanced use of the UDI CDC module, see the following use cases:
|
||||
* - \subpage udi_cdc_use_case_composite
|
||||
* - \subpage udc_use_case_1
|
||||
* - \subpage udc_use_case_2
|
||||
* - \subpage udc_use_case_3
|
||||
* - \subpage udc_use_case_4
|
||||
* - \subpage udc_use_case_5
|
||||
* - \subpage udc_use_case_6
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udi_cdc_use_case_composite CDC in a composite device
|
||||
*
|
||||
* A USB Composite Device is a USB Device which uses more than one USB class.
|
||||
* In this use case, the "USB CDC (Composite Device)" module is used to
|
||||
* create a USB composite device. Thus, this USB module can be associated with
|
||||
* another "Composite Device" module, like "USB HID Mouse (Composite Device)".
|
||||
*
|
||||
* Also, you can refer to application note
|
||||
* <A href="http://www.atmel.com/dyn/resources/prod_documents/doc8445.pdf">
|
||||
* AVR4902 ASF - USB Composite Device</A>.
|
||||
*
|
||||
* \section udi_cdc_use_case_composite_setup Setup steps
|
||||
* For the setup code of this use case to work, the
|
||||
* \ref udi_cdc_basic_use_case "basic use case" must be followed.
|
||||
*
|
||||
* \section udi_cdc_use_case_composite_usage Usage steps
|
||||
*
|
||||
* \subsection udi_cdc_use_case_composite_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
#define USB_DEVICE_NB_INTERFACE (X+2)
|
||||
#define USB_DEVICE_MAX_EP (X+3)
|
||||
|
||||
#define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_0 X+0
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_0 X+1
|
||||
|
||||
#define UDI_COMPOSITE_DESC_T \
|
||||
usb_iad_desc_t udi_cdc_iad; \
|
||||
udi_cdc_comm_desc_t udi_cdc_comm; \
|
||||
udi_cdc_data_desc_t udi_cdc_data; \
|
||||
...
|
||||
#define UDI_COMPOSITE_DESC_FS \
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \
|
||||
...
|
||||
#define UDI_COMPOSITE_DESC_HS \
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \
|
||||
...
|
||||
#define UDI_COMPOSITE_API \
|
||||
&udi_api_cdc_comm, \
|
||||
&udi_api_cdc_data, \
|
||||
...
|
||||
\endcode
|
||||
*
|
||||
* \subsection udi_cdc_use_case_composite_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required for a USB composite device configuration:
|
||||
* - \code // Endpoint control size, This must be:
|
||||
// - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM)
|
||||
// - 64 for a high speed device
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
// Total Number of interfaces on this USB device.
|
||||
// Add 2 for CDC.
|
||||
#define USB_DEVICE_NB_INTERFACE (X+2)
|
||||
// Total number of endpoints on this USB device.
|
||||
// This must include each endpoint for each interface.
|
||||
// Add 3 for CDC.
|
||||
#define USB_DEVICE_MAX_EP (X+3) \endcode
|
||||
* -# Ensure that conf_usb.h contains the description of
|
||||
* composite device:
|
||||
* - \code // The endpoint numbers chosen by you for the CDC.
|
||||
// The endpoint numbers starting from 1.
|
||||
#define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint
|
||||
// The interface index of an interface starting from 0
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_0 X+0
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode
|
||||
* -# Ensure that conf_usb.h contains the following parameters
|
||||
* required for a USB composite device configuration:
|
||||
* - \code // USB Interfaces descriptor structure
|
||||
#define UDI_COMPOSITE_DESC_T \
|
||||
...
|
||||
usb_iad_desc_t udi_cdc_iad; \
|
||||
udi_cdc_comm_desc_t udi_cdc_comm; \
|
||||
udi_cdc_data_desc_t udi_cdc_data; \
|
||||
...
|
||||
// USB Interfaces descriptor value for Full Speed
|
||||
#define UDI_COMPOSITE_DESC_FS \
|
||||
...
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \
|
||||
...
|
||||
// USB Interfaces descriptor value for High Speed
|
||||
#define UDI_COMPOSITE_DESC_HS \
|
||||
...
|
||||
.udi_cdc_iad = UDI_CDC_IAD_DESC_0, \
|
||||
.udi_cdc_comm = UDI_CDC_COMM_DESC_0, \
|
||||
.udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \
|
||||
...
|
||||
// USB Interface APIs
|
||||
#define UDI_COMPOSITE_API \
|
||||
...
|
||||
&udi_api_cdc_comm, \
|
||||
&udi_api_cdc_data, \
|
||||
... \endcode
|
||||
* - \note The descriptors order given in the four lists above must be the
|
||||
* same as the order defined by all interface indexes. The interface index
|
||||
* orders are defined through UDI_X_IFACE_NUMBER defines.\n
|
||||
* Also, the CDC requires a USB Interface Association Descriptor (IAD) for
|
||||
* composite device.
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // _UDI_CDC_H_
|
156
Marlin/src/HAL/DUE/usb/udi_cdc_conf.h
Normal file
156
Marlin/src/HAL/DUE/usb/udi_cdc_conf.h
Normal file
@ -0,0 +1,156 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Default CDC configuration for a USB Device with a single interface
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDI_CDC_CONF_H_
|
||||
#define _UDI_CDC_CONF_H_
|
||||
|
||||
#include "usb_protocol_cdc.h"
|
||||
#include "conf_usb.h"
|
||||
|
||||
#ifndef UDI_CDC_PORT_NB
|
||||
# define UDI_CDC_PORT_NB 1
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \addtogroup udi_cdc_group_single_desc
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Control endpoint size (Endpoint 0)
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
|
||||
#if XMEGA
|
||||
/**
|
||||
* \name Endpoint configuration on XMEGA
|
||||
* The XMEGA supports a IN and OUT endpoint with the same number endpoint,
|
||||
* thus XMEGA can support up to 7 CDC interfaces.
|
||||
*/
|
||||
//@{
|
||||
#define UDI_CDC_DATA_EP_IN_0 ( 1 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_0 ( 2 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_0 ( 2 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_1 ( 3 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_1 ( 4 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_1 ( 4 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_2 ( 5 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_2 ( 6 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_2 ( 6 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_3 ( 7 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_3 ( 8 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_3 ( 8 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_4 ( 9 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_4 (10 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_4 (10 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_5 (11 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_5 (12 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_5 (12 | USB_EP_DIR_IN) // Notify endpoint
|
||||
#define UDI_CDC_DATA_EP_IN_6 (13 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_6 (14 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_6 (14 | USB_EP_DIR_IN) // Notify endpoint
|
||||
//! 2 endpoints numbers used per CDC interface
|
||||
#define USB_DEVICE_MAX_EP (2*UDI_CDC_PORT_NB)
|
||||
//@}
|
||||
|
||||
#else
|
||||
|
||||
/**
|
||||
* \name Default endpoint configuration
|
||||
* The USBB, UDP, UDPHS and UOTGHS interfaces can support up to 2 CDC interfaces.
|
||||
*/
|
||||
//@{
|
||||
# if UDI_CDC_PORT_NB > 2
|
||||
# error USBB, UDP, UDPHS and UOTGHS interfaces have not enought endpoints.
|
||||
# endif
|
||||
#define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX
|
||||
#define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX
|
||||
#define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint
|
||||
# if SAM3U
|
||||
/* For 3U max endpoint size of 4 is 64, use 5 and 6 as bulk tx and rx */
|
||||
# define UDI_CDC_DATA_EP_IN_1 (6 | USB_EP_DIR_IN) // TX
|
||||
# define UDI_CDC_DATA_EP_OUT_1 (5 | USB_EP_DIR_OUT) // RX
|
||||
# define UDI_CDC_COMM_EP_1 (4 | USB_EP_DIR_IN) // Notify
|
||||
# else
|
||||
# define UDI_CDC_DATA_EP_IN_1 (4 | USB_EP_DIR_IN) // TX
|
||||
# define UDI_CDC_DATA_EP_OUT_1 (5 | USB_EP_DIR_OUT) // RX
|
||||
# define UDI_CDC_COMM_EP_1 (6 | USB_EP_DIR_IN) // Notify
|
||||
# endif
|
||||
//! 3 endpoints used per CDC interface
|
||||
#undef USB_DEVICE_MAX_EP // undefine this definition in header file
|
||||
#define USB_DEVICE_MAX_EP (3*UDI_CDC_PORT_NB)
|
||||
//@}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \name Default Interface numbers
|
||||
*/
|
||||
//@{
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_0 0
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_0 1
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_1 2
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_1 3
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_2 4
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_2 5
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_3 6
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_3 7
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_4 8
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_4 9
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_5 10
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_5 11
|
||||
#define UDI_CDC_COMM_IFACE_NUMBER_6 12
|
||||
#define UDI_CDC_DATA_IFACE_NUMBER_6 13
|
||||
//@}
|
||||
|
||||
//@}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // _UDI_CDC_CONF_H_
|
261
Marlin/src/HAL/DUE/usb/udi_cdc_desc.c
Normal file
261
Marlin/src/HAL/DUE/usb/udi_cdc_desc.c
Normal file
@ -0,0 +1,261 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Default descriptors for a USB Device with a single interface CDC
|
||||
*
|
||||
* Copyright (c) 2009-2016 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "udd.h"
|
||||
#include "udc_desc.h"
|
||||
#include "udi_cdc.h"
|
||||
|
||||
#if DISABLED(SDSUPPORT)
|
||||
|
||||
/**
|
||||
* \defgroup udi_cdc_group_single_desc USB device descriptors for a single interface
|
||||
*
|
||||
* The following structures provide the USB device descriptors required for
|
||||
* USB Device with a single interface CDC.
|
||||
*
|
||||
* It is ready to use and do not require more definition.
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Two interfaces for a CDC device
|
||||
#define USB_DEVICE_NB_INTERFACE (2*UDI_CDC_PORT_NB)
|
||||
|
||||
#ifdef USB_DEVICE_LPM_SUPPORT
|
||||
# define USB_VERSION USB_V2_1
|
||||
#else
|
||||
# define USB_VERSION USB_V2_0
|
||||
#endif
|
||||
|
||||
//! USB Device Descriptor
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = {
|
||||
.bLength = sizeof(usb_dev_desc_t),
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = LE16(USB_VERSION),
|
||||
#if UDI_CDC_PORT_NB > 1
|
||||
.bDeviceClass = 0,
|
||||
#else
|
||||
.bDeviceClass = CDC_CLASS_DEVICE,
|
||||
#endif
|
||||
.bDeviceSubClass = 0,
|
||||
.bDeviceProtocol = 0,
|
||||
.bMaxPacketSize0 = USB_DEVICE_EP_CTRL_SIZE,
|
||||
.idVendor = LE16(USB_DEVICE_VENDOR_ID),
|
||||
.idProduct = LE16(USB_DEVICE_PRODUCT_ID),
|
||||
.bcdDevice = LE16((USB_DEVICE_MAJOR_VERSION << 8)
|
||||
| USB_DEVICE_MINOR_VERSION),
|
||||
#ifdef USB_DEVICE_MANUFACTURE_NAME
|
||||
.iManufacturer = 1,
|
||||
#else
|
||||
.iManufacturer = 0, // No manufacture string
|
||||
#endif
|
||||
#ifdef USB_DEVICE_PRODUCT_NAME
|
||||
.iProduct = 2,
|
||||
#else
|
||||
.iProduct = 0, // No product string
|
||||
#endif
|
||||
#if (defined USB_DEVICE_SERIAL_NAME || defined USB_DEVICE_GET_SERIAL_NAME_POINTER)
|
||||
.iSerialNumber = 3,
|
||||
#else
|
||||
.iSerialNumber = 0, // No serial string
|
||||
#endif
|
||||
.bNumConfigurations = 1
|
||||
};
|
||||
|
||||
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
//! USB Device Qualifier Descriptor for HS
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE usb_dev_qual_desc_t udc_device_qual = {
|
||||
.bLength = sizeof(usb_dev_qual_desc_t),
|
||||
.bDescriptorType = USB_DT_DEVICE_QUALIFIER,
|
||||
.bcdUSB = LE16(USB_VERSION),
|
||||
#if UDI_CDC_PORT_NB > 1
|
||||
.bDeviceClass = 0,
|
||||
#else
|
||||
.bDeviceClass = CDC_CLASS_DEVICE,
|
||||
#endif
|
||||
.bDeviceSubClass = 0,
|
||||
.bDeviceProtocol = 0,
|
||||
.bMaxPacketSize0 = USB_DEVICE_EP_CTRL_SIZE,
|
||||
.bNumConfigurations = 1
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef USB_DEVICE_LPM_SUPPORT
|
||||
//! USB Device Qualifier Descriptor
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE usb_dev_lpm_desc_t udc_device_lpm = {
|
||||
.bos.bLength = sizeof(usb_dev_bos_desc_t),
|
||||
.bos.bDescriptorType = USB_DT_BOS,
|
||||
.bos.wTotalLength = LE16(sizeof(usb_dev_bos_desc_t) + sizeof(usb_dev_capa_ext_desc_t)),
|
||||
.bos.bNumDeviceCaps = 1,
|
||||
.capa_ext.bLength = sizeof(usb_dev_capa_ext_desc_t),
|
||||
.capa_ext.bDescriptorType = USB_DT_DEVICE_CAPABILITY,
|
||||
.capa_ext.bDevCapabilityType = USB_DC_USB20_EXTENSION,
|
||||
.capa_ext.bmAttributes = USB_DC_EXT_LPM,
|
||||
};
|
||||
#endif
|
||||
|
||||
//! Structure for USB Device Configuration Descriptor
|
||||
COMPILER_PACK_SET(1)
|
||||
typedef struct {
|
||||
usb_conf_desc_t conf;
|
||||
#if UDI_CDC_PORT_NB == 1
|
||||
udi_cdc_comm_desc_t udi_cdc_comm_0;
|
||||
udi_cdc_data_desc_t udi_cdc_data_0;
|
||||
#else
|
||||
# define UDI_CDC_DESC_STRUCTURE(index, unused) \
|
||||
usb_iad_desc_t udi_cdc_iad_##index; \
|
||||
udi_cdc_comm_desc_t udi_cdc_comm_##index; \
|
||||
udi_cdc_data_desc_t udi_cdc_data_##index;
|
||||
MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_DESC_STRUCTURE, ~)
|
||||
# undef UDI_CDC_DESC_STRUCTURE
|
||||
#endif
|
||||
} udc_desc_t;
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
//! USB Device Configuration Descriptor filled for full and high speed
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE udc_desc_t udc_desc_fs = {
|
||||
.conf.bLength = sizeof(usb_conf_desc_t),
|
||||
.conf.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.conf.wTotalLength = LE16(sizeof(udc_desc_t)),
|
||||
.conf.bNumInterfaces = USB_DEVICE_NB_INTERFACE,
|
||||
.conf.bConfigurationValue = 1,
|
||||
.conf.iConfiguration = 0,
|
||||
.conf.bmAttributes = USB_CONFIG_ATTR_MUST_SET | USB_DEVICE_ATTR,
|
||||
.conf.bMaxPower = USB_CONFIG_MAX_POWER(USB_DEVICE_POWER),
|
||||
#if UDI_CDC_PORT_NB == 1
|
||||
.udi_cdc_comm_0 = UDI_CDC_COMM_DESC_0,
|
||||
.udi_cdc_data_0 = UDI_CDC_DATA_DESC_0_FS,
|
||||
#else
|
||||
# define UDI_CDC_DESC_FS(index, unused) \
|
||||
.udi_cdc_iad_##index = UDI_CDC_IAD_DESC_##index,\
|
||||
.udi_cdc_comm_##index = UDI_CDC_COMM_DESC_##index,\
|
||||
.udi_cdc_data_##index = UDI_CDC_DATA_DESC_##index##_FS,
|
||||
MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_DESC_FS, ~)
|
||||
# undef UDI_CDC_DESC_FS
|
||||
#endif
|
||||
};
|
||||
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE udc_desc_t udc_desc_hs = {
|
||||
.conf.bLength = sizeof(usb_conf_desc_t),
|
||||
.conf.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.conf.wTotalLength = LE16(sizeof(udc_desc_t)),
|
||||
.conf.bNumInterfaces = USB_DEVICE_NB_INTERFACE,
|
||||
.conf.bConfigurationValue = 1,
|
||||
.conf.iConfiguration = 0,
|
||||
.conf.bmAttributes = USB_CONFIG_ATTR_MUST_SET | USB_DEVICE_ATTR,
|
||||
.conf.bMaxPower = USB_CONFIG_MAX_POWER(USB_DEVICE_POWER),
|
||||
#if UDI_CDC_PORT_NB == 1
|
||||
.udi_cdc_comm_0 = UDI_CDC_COMM_DESC_0,
|
||||
.udi_cdc_data_0 = UDI_CDC_DATA_DESC_0_HS,
|
||||
#else
|
||||
# define UDI_CDC_DESC_HS(index, unused) \
|
||||
.udi_cdc_iad_##index = UDI_CDC_IAD_DESC_##index, \
|
||||
.udi_cdc_comm_##index = UDI_CDC_COMM_DESC_##index, \
|
||||
.udi_cdc_data_##index = UDI_CDC_DATA_DESC_##index##_HS,
|
||||
MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_DESC_HS, ~)
|
||||
# undef UDI_CDC_DESC_HS
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \name UDC structures which content all USB Device definitions
|
||||
*/
|
||||
//@{
|
||||
|
||||
//! Associate an UDI for each USB interface
|
||||
UDC_DESC_STORAGE udi_api_t *udi_apis[USB_DEVICE_NB_INTERFACE] = {
|
||||
# define UDI_CDC_API(index, unused) \
|
||||
&udi_api_cdc_comm, \
|
||||
&udi_api_cdc_data,
|
||||
MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_API, ~)
|
||||
# undef UDI_CDC_API
|
||||
};
|
||||
|
||||
//! Add UDI with USB Descriptors FS & HS
|
||||
UDC_DESC_STORAGE udc_config_speed_t udc_config_fs[1] = { {
|
||||
.desc = (usb_conf_desc_t UDC_DESC_STORAGE*)&udc_desc_fs,
|
||||
.udi_apis = udi_apis,
|
||||
}};
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
UDC_DESC_STORAGE udc_config_speed_t udc_config_hs[1] = { {
|
||||
.desc = (usb_conf_desc_t UDC_DESC_STORAGE*)&udc_desc_hs,
|
||||
.udi_apis = udi_apis,
|
||||
}};
|
||||
#endif
|
||||
|
||||
//! Add all information about USB Device in global structure for UDC
|
||||
UDC_DESC_STORAGE udc_config_t udc_config = {
|
||||
.confdev_lsfs = &udc_device_desc,
|
||||
.conf_lsfs = udc_config_fs,
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
.confdev_hs = &udc_device_desc,
|
||||
.qualifier = &udc_device_qual,
|
||||
.conf_hs = udc_config_hs,
|
||||
#endif
|
||||
#ifdef USB_DEVICE_LPM_SUPPORT
|
||||
.conf_bos = &udc_device_lpm.bos,
|
||||
#else
|
||||
.conf_bos = NULL,
|
||||
#endif
|
||||
};
|
||||
|
||||
//@}
|
||||
//@}
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
192
Marlin/src/HAL/DUE/usb/udi_composite_desc.c
Normal file
192
Marlin/src/HAL/DUE/usb/udi_composite_desc.c
Normal file
@ -0,0 +1,192 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Descriptors for an USB Composite Device
|
||||
*
|
||||
* Copyright (c) 2009-2016 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "udd.h"
|
||||
#include "udc_desc.h"
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
/**
|
||||
* \defgroup udi_group_desc Descriptors for a USB Device
|
||||
* composite
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**INDENT-OFF**/
|
||||
|
||||
//! USB Device Descriptor
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = {
|
||||
.bLength = sizeof(usb_dev_desc_t),
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = LE16(USB_V2_0),
|
||||
.bDeviceClass = CDC_CLASS_MULTI,
|
||||
.bDeviceSubClass = CDC_SUBCLASS_ACM,
|
||||
.bDeviceProtocol = CDC_PROTOCOL_V25TER,
|
||||
.bMaxPacketSize0 = USB_DEVICE_EP_CTRL_SIZE,
|
||||
.idVendor = LE16(USB_DEVICE_VENDOR_ID),
|
||||
.idProduct = LE16(USB_DEVICE_PRODUCT_ID),
|
||||
.bcdDevice = LE16((USB_DEVICE_MAJOR_VERSION << 8)
|
||||
| USB_DEVICE_MINOR_VERSION),
|
||||
#ifdef USB_DEVICE_MANUFACTURE_NAME
|
||||
.iManufacturer = 1,
|
||||
#else
|
||||
.iManufacturer = 0, // No manufacture string
|
||||
#endif
|
||||
#ifdef USB_DEVICE_PRODUCT_NAME
|
||||
.iProduct = 2,
|
||||
#else
|
||||
.iProduct = 0, // No product string
|
||||
#endif
|
||||
#if (defined USB_DEVICE_SERIAL_NAME || defined USB_DEVICE_GET_SERIAL_NAME_POINTER)
|
||||
.iSerialNumber = 3,
|
||||
#else
|
||||
.iSerialNumber = 0, // No serial string
|
||||
#endif
|
||||
.bNumConfigurations = 1
|
||||
};
|
||||
|
||||
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
//! USB Device Qualifier Descriptor for HS
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE usb_dev_qual_desc_t udc_device_qual = {
|
||||
.bLength = sizeof(usb_dev_qual_desc_t),
|
||||
.bDescriptorType = USB_DT_DEVICE_QUALIFIER,
|
||||
.bcdUSB = LE16(USB_V2_0),
|
||||
.bDeviceClass = CDC_CLASS_MULTI,
|
||||
.bDeviceSubClass = CDC_SUBCLASS_ACM,
|
||||
.bDeviceProtocol = CDC_PROTOCOL_V25TER,
|
||||
.bMaxPacketSize0 = USB_DEVICE_EP_CTRL_SIZE,
|
||||
.bNumConfigurations = 1
|
||||
};
|
||||
#endif
|
||||
|
||||
//! Structure for USB Device Configuration Descriptor
|
||||
COMPILER_PACK_SET(1)
|
||||
typedef struct {
|
||||
usb_conf_desc_t conf;
|
||||
UDI_COMPOSITE_DESC_T;
|
||||
} udc_desc_t;
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
//! USB Device Configuration Descriptor filled for FS
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE udc_desc_t udc_desc_fs = {
|
||||
.conf.bLength = sizeof(usb_conf_desc_t),
|
||||
.conf.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.conf.wTotalLength = LE16(sizeof(udc_desc_t)),
|
||||
.conf.bNumInterfaces = USB_DEVICE_NB_INTERFACE,
|
||||
.conf.bConfigurationValue = 1,
|
||||
.conf.iConfiguration = 0,
|
||||
.conf.bmAttributes = USB_CONFIG_ATTR_MUST_SET | USB_DEVICE_ATTR,
|
||||
.conf.bMaxPower = USB_CONFIG_MAX_POWER(USB_DEVICE_POWER),
|
||||
UDI_COMPOSITE_DESC_FS
|
||||
};
|
||||
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
//! USB Device Configuration Descriptor filled for HS
|
||||
COMPILER_WORD_ALIGNED
|
||||
UDC_DESC_STORAGE udc_desc_t udc_desc_hs = {
|
||||
.conf.bLength = sizeof(usb_conf_desc_t),
|
||||
.conf.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.conf.wTotalLength = LE16(sizeof(udc_desc_t)),
|
||||
.conf.bNumInterfaces = USB_DEVICE_NB_INTERFACE,
|
||||
.conf.bConfigurationValue = 1,
|
||||
.conf.iConfiguration = 0,
|
||||
.conf.bmAttributes = USB_CONFIG_ATTR_MUST_SET | USB_DEVICE_ATTR,
|
||||
.conf.bMaxPower = USB_CONFIG_MAX_POWER(USB_DEVICE_POWER),
|
||||
UDI_COMPOSITE_DESC_HS
|
||||
};
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* \name UDC structures which contains all USB Device definitions
|
||||
*/
|
||||
//@{
|
||||
|
||||
//! Associate an UDI for each USB interface
|
||||
UDC_DESC_STORAGE udi_api_t *udi_apis[USB_DEVICE_NB_INTERFACE] = {
|
||||
UDI_COMPOSITE_API
|
||||
};
|
||||
|
||||
//! Add UDI with USB Descriptors FS
|
||||
UDC_DESC_STORAGE udc_config_speed_t udc_config_lsfs[1] = {{
|
||||
.desc = (usb_conf_desc_t UDC_DESC_STORAGE*)&udc_desc_fs,
|
||||
.udi_apis = udi_apis,
|
||||
}};
|
||||
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
//! Add UDI with USB Descriptors HS
|
||||
UDC_DESC_STORAGE udc_config_speed_t udc_config_hs[1] = {{
|
||||
.desc = (usb_conf_desc_t UDC_DESC_STORAGE*)&udc_desc_hs,
|
||||
.udi_apis = udi_apis,
|
||||
}};
|
||||
#endif
|
||||
|
||||
//! Add all information about USB Device in global structure for UDC
|
||||
UDC_DESC_STORAGE udc_config_t udc_config = {
|
||||
.confdev_lsfs = &udc_device_desc,
|
||||
.conf_lsfs = udc_config_lsfs,
|
||||
#ifdef USB_DEVICE_HS_SUPPORT
|
||||
.confdev_hs = &udc_device_desc,
|
||||
.qualifier = &udc_device_qual,
|
||||
.conf_hs = udc_config_hs,
|
||||
#endif
|
||||
};
|
||||
|
||||
//@}
|
||||
/**INDENT-ON**/
|
||||
//@}
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
||||
|
||||
#endif // SDSUPPORT
|
1132
Marlin/src/HAL/DUE/usb/udi_msc.c
Normal file
1132
Marlin/src/HAL/DUE/usb/udi_msc.c
Normal file
File diff suppressed because it is too large
Load Diff
376
Marlin/src/HAL/DUE/usb/udi_msc.h
Normal file
376
Marlin/src/HAL/DUE/usb/udi_msc.h
Normal file
@ -0,0 +1,376 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB Device Mass Storage Class (MSC) interface definitions.
|
||||
*
|
||||
* Copyright (c) 2009-2016 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _UDI_MSC_H_
|
||||
#define _UDI_MSC_H_
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "usb_protocol.h"
|
||||
#include "usb_protocol_msc.h"
|
||||
#include "udd.h"
|
||||
#include "udc_desc.h"
|
||||
#include "udi.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \addtogroup udi_msc_group_udc
|
||||
* @{
|
||||
*/
|
||||
//! Global structure which contains standard UDI interface for UDC
|
||||
extern UDC_DESC_STORAGE udi_api_t udi_api_msc;
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \ingroup udi_msc_group
|
||||
* \defgroup udi_msc_group USB interface descriptors
|
||||
*
|
||||
* The following structures provide predefined USB interface descriptors.
|
||||
* It must be used to define the final USB descriptors.
|
||||
*/
|
||||
//@{
|
||||
|
||||
//! Interface descriptor structure for MSC
|
||||
typedef struct {
|
||||
usb_iface_desc_t iface;
|
||||
usb_ep_desc_t ep_in;
|
||||
usb_ep_desc_t ep_out;
|
||||
} udi_msc_desc_t;
|
||||
|
||||
//! By default no string associated to this interface
|
||||
#ifndef UDI_MSC_STRING_ID
|
||||
#define UDI_MSC_STRING_ID 0
|
||||
#endif
|
||||
|
||||
//! MSC endpoints size for full speed
|
||||
#define UDI_MSC_EPS_SIZE_FS 64
|
||||
//! MSC endpoints size for high speed
|
||||
#define UDI_MSC_EPS_SIZE_HS 512
|
||||
|
||||
//! Content of MSC interface descriptor for all speeds
|
||||
#define UDI_MSC_DESC \
|
||||
.iface.bLength = sizeof(usb_iface_desc_t),\
|
||||
.iface.bDescriptorType = USB_DT_INTERFACE,\
|
||||
.iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\
|
||||
.iface.bAlternateSetting = 0,\
|
||||
.iface.bNumEndpoints = 2,\
|
||||
.iface.bInterfaceClass = MSC_CLASS,\
|
||||
.iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\
|
||||
.iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\
|
||||
.iface.iInterface = UDI_MSC_STRING_ID,\
|
||||
.ep_in.bLength = sizeof(usb_ep_desc_t),\
|
||||
.ep_in.bDescriptorType = USB_DT_ENDPOINT,\
|
||||
.ep_in.bEndpointAddress = UDI_MSC_EP_IN,\
|
||||
.ep_in.bmAttributes = USB_EP_TYPE_BULK,\
|
||||
.ep_in.bInterval = 0,\
|
||||
.ep_out.bLength = sizeof(usb_ep_desc_t),\
|
||||
.ep_out.bDescriptorType = USB_DT_ENDPOINT,\
|
||||
.ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\
|
||||
.ep_out.bmAttributes = USB_EP_TYPE_BULK,\
|
||||
.ep_out.bInterval = 0,
|
||||
|
||||
//! Content of MSC interface descriptor for full speed only
|
||||
#define UDI_MSC_DESC_FS {\
|
||||
UDI_MSC_DESC \
|
||||
.ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\
|
||||
.ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\
|
||||
}
|
||||
|
||||
//! Content of MSC interface descriptor for high speed only
|
||||
#define UDI_MSC_DESC_HS {\
|
||||
UDI_MSC_DESC \
|
||||
.ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_HS),\
|
||||
.ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_HS),\
|
||||
}
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* \ingroup udi_group
|
||||
* \defgroup udi_msc_group USB Device Interface (UDI) for Mass Storage Class (MSC)
|
||||
*
|
||||
* Common APIs used by high level application to use this USB class.
|
||||
*
|
||||
* These routines are used by memory to transfer its data
|
||||
* to/from USB MSC endpoints.
|
||||
*
|
||||
* See \ref udi_msc_quickstart.
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief Process the background read/write commands
|
||||
*
|
||||
* Routine called by the main loop
|
||||
*/
|
||||
bool udi_msc_process_trans(void);
|
||||
|
||||
/**
|
||||
* \brief Transfers data to/from USB MSC endpoints
|
||||
*
|
||||
*
|
||||
* \param b_read Memory to USB, if true
|
||||
* \param block Buffer on Internal RAM to send or fill
|
||||
* \param block_size Buffer size to send or fill
|
||||
* \param callback Function to call at the end of transfer.
|
||||
* If NULL then the routine exit when transfer is finish.
|
||||
*
|
||||
* \return \c 1 if function was successfully done, otherwise \c 0.
|
||||
*/
|
||||
bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
|
||||
void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep));
|
||||
//@}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC)
|
||||
*
|
||||
* This is the quick start guide for the \ref udi_msc_group
|
||||
* "USB device interface MSC module (UDI MSC)" with step-by-step instructions on
|
||||
* how to configure and use the modules in a selection of use cases.
|
||||
*
|
||||
* The use cases contain several code fragments. The code fragments in the
|
||||
* steps for setup can be copied into a custom initialization function, while
|
||||
* the steps for usage can be copied into, e.g., the main application function.
|
||||
*
|
||||
* \section udi_msc_basic_use_case Basic use case
|
||||
* In this basic use case, the "USB MSC (Single Interface Device)" module is used.
|
||||
* The "USB MSC (Composite Device)" module usage is described in \ref udi_msc_use_cases
|
||||
* "Advanced use cases".
|
||||
*
|
||||
* \section udi_msc_basic_use_case_setup Setup steps
|
||||
* \subsection udi_msc_basic_use_case_setup_prereq Prerequisites
|
||||
* \copydetails udc_basic_use_case_setup_prereq
|
||||
* \subsection udi_msc_basic_use_case_setup_code Example code
|
||||
* \copydetails udc_basic_use_case_setup_code
|
||||
* \subsection udi_msc_basic_use_case_setup_flow Workflow
|
||||
* \copydetails udc_basic_use_case_setup_flow
|
||||
*
|
||||
* \section udi_msc_basic_use_case_usage Usage steps
|
||||
*
|
||||
* \subsection udi_msc_basic_use_case_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC
|
||||
#define UDI_MSC_GLOBAL_VENDOR_ID \
|
||||
'A', 'T', 'M', 'E', 'L', ' ', ' ', ' '
|
||||
#define UDI_MSC_GLOBAL_PRODUCT_VERSION \
|
||||
'1', '.', '0', '0'
|
||||
#define UDI_MSC_ENABLE_EXT() my_callback_msc_enable()
|
||||
extern bool my_callback_msc_enable(void);
|
||||
#define UDI_MSC_DISABLE_EXT() my_callback_msc_disable()
|
||||
extern void my_callback_msc_disable(void);
|
||||
#include "udi_msc_conf.h" // At the end of conf_usb.h file
|
||||
\endcode
|
||||
*
|
||||
* Add to application C-file:
|
||||
* \code
|
||||
static bool my_flag_autorize_msc_transfert = false;
|
||||
bool my_callback_msc_enable(void)
|
||||
{
|
||||
my_flag_autorize_msc_transfert = true;
|
||||
return true;
|
||||
}
|
||||
void my_callback_msc_disable(void)
|
||||
{
|
||||
my_flag_autorize_msc_transfert = false;
|
||||
}
|
||||
|
||||
void task(void)
|
||||
{
|
||||
udi_msc_process_trans();
|
||||
}
|
||||
\endcode
|
||||
*
|
||||
* \subsection udi_msc_basic_use_case_setup_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following configuration,
|
||||
* which is the USB device MSC configuration:
|
||||
* - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC \endcode
|
||||
* \note The USB serial number is mandatory when a MSC interface is used.
|
||||
* - \code //! Vendor name and Product version of MSC interface
|
||||
#define UDI_MSC_GLOBAL_VENDOR_ID \
|
||||
'A', 'T', 'M', 'E', 'L', ' ', ' ', ' '
|
||||
#define UDI_MSC_GLOBAL_PRODUCT_VERSION \
|
||||
'1', '.', '0', '0' \endcode
|
||||
* \note The USB MSC interface requires a vendor ID (8 ASCII characters)
|
||||
* and a product version (4 ASCII characters).
|
||||
* - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable()
|
||||
extern bool my_callback_msc_enable(void); \endcode
|
||||
* \note After the device enumeration (detecting and identifying USB devices),
|
||||
* the USB host starts the device configuration. When the USB MSC interface
|
||||
* from the device is accepted by the host, the USB host enables this interface and the
|
||||
* UDI_MSC_ENABLE_EXT() callback function is called and return true.
|
||||
* Thus, when this event is received, the tasks which call
|
||||
* udi_msc_process_trans() must be enabled.
|
||||
* - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable()
|
||||
extern void my_callback_msc_disable(void); \endcode
|
||||
* \note When the USB device is unplugged or is reset by the USB host, the USB
|
||||
* interface is disabled and the UDI_MSC_DISABLE_EXT() callback function
|
||||
* is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans().
|
||||
* -# The MSC is automatically linked with memory control access component
|
||||
* which provides the memories interfaces. However, the memory data transfers
|
||||
* must be done outside USB interrupt routine. This is done in the MSC process
|
||||
* ("udi_msc_process_trans()") called by main loop:
|
||||
* - \code * void task(void) {
|
||||
udi_msc_process_trans();
|
||||
} \endcode
|
||||
* -# The MSC speed depends on task periodicity. To get the best speed
|
||||
* the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup
|
||||
* this task (Example, through a mutex):
|
||||
* - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans()
|
||||
void msc_notify_trans(void) {
|
||||
wakeup_my_task();
|
||||
} \endcode
|
||||
*
|
||||
* \section udi_msc_use_cases Advanced use cases
|
||||
* For more advanced use of the UDI MSC module, see the following use cases:
|
||||
* - \subpage udi_msc_use_case_composite
|
||||
* - \subpage udc_use_case_1
|
||||
* - \subpage udc_use_case_2
|
||||
* - \subpage udc_use_case_3
|
||||
* - \subpage udc_use_case_5
|
||||
* - \subpage udc_use_case_6
|
||||
*/
|
||||
|
||||
/**
|
||||
* \page udi_msc_use_case_composite MSC in a composite device
|
||||
*
|
||||
* A USB Composite Device is a USB Device which uses more than one USB class.
|
||||
* In this use case, the "USB MSC (Composite Device)" module is used to
|
||||
* create a USB composite device. Thus, this USB module can be associated with
|
||||
* another "Composite Device" module, like "USB HID Mouse (Composite Device)".
|
||||
*
|
||||
* Also, you can refer to application note
|
||||
* <A href="http://www.atmel.com/dyn/resources/prod_documents/doc8445.pdf">
|
||||
* AVR4902 ASF - USB Composite Device</A>.
|
||||
*
|
||||
* \section udi_msc_use_case_composite_setup Setup steps
|
||||
* For the setup code of this use case to work, the
|
||||
* \ref udi_msc_basic_use_case "basic use case" must be followed.
|
||||
*
|
||||
* \section udi_msc_use_case_composite_usage Usage steps
|
||||
*
|
||||
* \subsection udi_msc_use_case_composite_usage_code Example code
|
||||
* Content of conf_usb.h:
|
||||
* \code
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
#define USB_DEVICE_NB_INTERFACE (X+1)
|
||||
#define USB_DEVICE_MAX_EP (X+2)
|
||||
|
||||
#define UDI_MSC_EP_IN (X | USB_EP_DIR_IN)
|
||||
#define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT)
|
||||
#define UDI_MSC_IFACE_NUMBER X
|
||||
|
||||
#define UDI_COMPOSITE_DESC_T \
|
||||
udi_msc_desc_t udi_msc; \
|
||||
...
|
||||
#define UDI_COMPOSITE_DESC_FS \
|
||||
.udi_msc = UDI_MSC_DESC, \
|
||||
...
|
||||
#define UDI_COMPOSITE_DESC_HS \
|
||||
.udi_msc = UDI_MSC_DESC, \
|
||||
...
|
||||
#define UDI_COMPOSITE_API \
|
||||
&udi_api_msc, \
|
||||
...
|
||||
\endcode
|
||||
*
|
||||
* \subsection udi_msc_use_case_composite_usage_flow Workflow
|
||||
* -# Ensure that conf_usb.h is available and contains the following parameters
|
||||
* required for a USB composite device configuration:
|
||||
* - \code // Endpoint control size, This must be:
|
||||
// - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM)
|
||||
// - 64 for a high speed device
|
||||
#define USB_DEVICE_EP_CTRL_SIZE 64
|
||||
// Total Number of interfaces on this USB device.
|
||||
// Add 1 for MSC.
|
||||
#define USB_DEVICE_NB_INTERFACE (X+1)
|
||||
// Total number of endpoints on this USB device.
|
||||
// This must include each endpoint for each interface.
|
||||
// Add 2 for MSC.
|
||||
#define USB_DEVICE_MAX_EP (X+2) \endcode
|
||||
* -# Ensure that conf_usb.h contains the description of
|
||||
* composite device:
|
||||
* - \code // The endpoint numbers chosen by you for the MSC.
|
||||
// The endpoint numbers starting from 1.
|
||||
#define UDI_MSC_EP_IN (X | USB_EP_DIR_IN)
|
||||
#define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT)
|
||||
// The interface index of an interface starting from 0
|
||||
#define UDI_MSC_IFACE_NUMBER X \endcode
|
||||
* -# Ensure that conf_usb.h contains the following parameters
|
||||
* required for a USB composite device configuration:
|
||||
* - \code // USB Interfaces descriptor structure
|
||||
#define UDI_COMPOSITE_DESC_T \
|
||||
...
|
||||
udi_msc_desc_t udi_msc; \
|
||||
...
|
||||
// USB Interfaces descriptor value for Full Speed
|
||||
#define UDI_COMPOSITE_DESC_FS \
|
||||
...
|
||||
.udi_msc = UDI_MSC_DESC_FS, \
|
||||
...
|
||||
// USB Interfaces descriptor value for High Speed
|
||||
#define UDI_COMPOSITE_DESC_HS \
|
||||
...
|
||||
.udi_msc = UDI_MSC_DESC_HS, \
|
||||
...
|
||||
// USB Interface APIs
|
||||
#define UDI_COMPOSITE_API \
|
||||
...
|
||||
&udi_api_msc, \
|
||||
... \endcode
|
||||
* - \note The descriptors order given in the four lists above must be the
|
||||
* same as the order defined by all interface indexes. The interface index
|
||||
* orders are defined through UDI_X_IFACE_NUMBER defines.
|
||||
*/
|
||||
|
||||
#endif // _UDI_MSC_H_
|
2074
Marlin/src/HAL/DUE/usb/uotghs_device_due.c
Normal file
2074
Marlin/src/HAL/DUE/usb/uotghs_device_due.c
Normal file
File diff suppressed because it is too large
Load Diff
664
Marlin/src/HAL/DUE/usb/uotghs_device_due.h
Normal file
664
Marlin/src/HAL/DUE/usb/uotghs_device_due.h
Normal file
@ -0,0 +1,664 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB Device Driver for UOTGHS. Compliant with common UDD driver.
|
||||
*
|
||||
* Copyright (c) 2014-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef UOTGHS_DEVICE_DUE_H_INCLUDED
|
||||
#define UOTGHS_DEVICE_DUE_H_INCLUDED
|
||||
|
||||
//#include "compiler.h"
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
//! \ingroup udd_group
|
||||
//! \defgroup udd_udphs_group USB On-The-Go High-Speed Port for device mode (UOTGHS)
|
||||
//! UOTGHS low-level driver for USB device mode
|
||||
//!
|
||||
//! @{
|
||||
|
||||
#ifndef UOTGHS_DEVEPTCFG_EPDIR_Pos
|
||||
// Bit pos is not defined in SAM header file but we need it.
|
||||
# define UOTGHS_DEVEPTCFG_EPDIR_Pos 8
|
||||
#endif
|
||||
|
||||
//! @name UOTGHS Device IP properties
|
||||
//! These macros give access to IP properties
|
||||
//! @{
|
||||
//! Get maximal number of endpoints
|
||||
#define udd_get_endpoint_max_nbr() (9)
|
||||
#define UDD_MAX_PEP_NB (udd_get_endpoint_max_nbr() + 1)
|
||||
//! Get maximal number of banks of endpoints
|
||||
#define udd_get_endpoint_bank_max_nbr(ep) ((ep == 0) ? 1 : (( ep <= 2) ? 3 : 2))
|
||||
//! Get maximal size of endpoint (3X, 1024/64)
|
||||
#define udd_get_endpoint_size_max(ep) (((ep) == 0) ? 64 : 1024)
|
||||
//! Get DMA support of endpoints
|
||||
#define Is_udd_endpoint_dma_supported(ep) ((((ep) >= 1) && ((ep) <= 6)) ? true : false)
|
||||
//! Get High Band Width support of endpoints
|
||||
#define Is_udd_endpoint_high_bw_supported(ep) (((ep) >= 2) ? true : false)
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device speeds management
|
||||
//! @{
|
||||
//! Enable/disable device low-speed mode
|
||||
#define udd_low_speed_enable() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_LS))
|
||||
#define udd_low_speed_disable() (Clr_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_LS))
|
||||
//! Test if device low-speed mode is forced
|
||||
#define Is_udd_low_speed_enable() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_LS))
|
||||
|
||||
#ifdef UOTGHS_DEVCTRL_SPDCONF_HIGH_SPEED
|
||||
//! Enable high speed mode
|
||||
# define udd_high_speed_enable() (Wr_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_SPDCONF_Msk, 0))
|
||||
//! Disable high speed mode
|
||||
# define udd_high_speed_disable() (Wr_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_SPDCONF_Msk, 3))
|
||||
//! Test if controller is in full speed mode
|
||||
# define Is_udd_full_speed_mode() (Rd_bitfield(UOTGHS->UOTGHS_SR, UOTGHS_SR_SPEED_Msk) == UOTGHS_SR_SPEED_FULL_SPEED)
|
||||
#else
|
||||
# define udd_high_speed_enable() do { } while (0)
|
||||
# define udd_high_speed_disable() do { } while (0)
|
||||
# define Is_udd_full_speed_mode() true
|
||||
#endif
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device HS test mode management
|
||||
//! @{
|
||||
#ifdef UOTGHS_DEVCTRL_SPDCONF_HIGH_SPEED
|
||||
//! Enable high speed test mode
|
||||
# define udd_enable_hs_test_mode() (Wr_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_SPDCONF_Msk, 2))
|
||||
# define udd_enable_hs_test_mode_j() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_TSTJ))
|
||||
# define udd_enable_hs_test_mode_k() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_TSTK))
|
||||
# define udd_enable_hs_test_mode_packet() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_TSTPCKT))
|
||||
#endif
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device vbus management
|
||||
//! @{
|
||||
#define udd_enable_vbus_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define udd_disable_vbus_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define Is_udd_vbus_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define Is_udd_vbus_high() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUS))
|
||||
#define Is_udd_vbus_low() (!Is_udd_vbus_high())
|
||||
#define udd_ack_vbus_transition() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_VBUSTIC)
|
||||
#define udd_raise_vbus_transition() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_VBUSTIS)
|
||||
#define Is_udd_vbus_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUSTI))
|
||||
//! @}
|
||||
|
||||
|
||||
//! @name UOTGHS device attach control
|
||||
//! These macros manage the UOTGHS Device attach.
|
||||
//! @{
|
||||
//! Detaches from USB bus
|
||||
#define udd_detach_device() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH))
|
||||
//! Attaches to USB bus
|
||||
#define udd_attach_device() (Clr_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH))
|
||||
//! Test if the device is detached
|
||||
#define Is_udd_detached() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH))
|
||||
//! @}
|
||||
|
||||
|
||||
//! @name UOTGHS device bus events control
|
||||
//! These macros manage the UOTGHS Device bus events.
|
||||
//! @{
|
||||
|
||||
//! Initiates a remote wake-up event
|
||||
//! @{
|
||||
#define udd_initiate_remote_wake_up() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_RMWKUP))
|
||||
#define Is_udd_pending_remote_wake_up() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_RMWKUP))
|
||||
//! @}
|
||||
|
||||
//! Manage upstream resume event (=remote wakeup)
|
||||
//! The USB driver sends a resume signal called "Upstream Resume"
|
||||
//! @{
|
||||
#define udd_enable_remote_wake_up_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_UPRSMES)
|
||||
#define udd_disable_remote_wake_up_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_UPRSMEC)
|
||||
#define Is_udd_remote_wake_up_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_UPRSME))
|
||||
#define udd_ack_remote_wake_up_start() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_UPRSMC)
|
||||
#define udd_raise_remote_wake_up_start() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_UPRSMS)
|
||||
#define Is_udd_remote_wake_up_start() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_UPRSM))
|
||||
//! @}
|
||||
|
||||
//! Manage downstream resume event (=remote wakeup from host)
|
||||
//! The USB controller detects a valid "End of Resume" signal initiated by the host
|
||||
//! @{
|
||||
#define udd_enable_resume_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_EORSMES)
|
||||
#define udd_disable_resume_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_EORSMEC)
|
||||
#define Is_udd_resume_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_EORSME))
|
||||
#define udd_ack_resume() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_EORSMC)
|
||||
#define udd_raise_resume() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_EORSMS)
|
||||
#define Is_udd_resume() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_EORSM))
|
||||
//! @}
|
||||
|
||||
//! Manage wake-up event (=usb line activity)
|
||||
//! The USB controller is reactivated by a filtered non-idle signal from the lines
|
||||
//! @{
|
||||
#define udd_enable_wake_up_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_WAKEUPES)
|
||||
#define udd_disable_wake_up_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_WAKEUPEC)
|
||||
#define Is_udd_wake_up_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_WAKEUPE))
|
||||
#define udd_ack_wake_up() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_WAKEUPC)
|
||||
#define udd_raise_wake_up() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_WAKEUPS)
|
||||
#define Is_udd_wake_up() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_WAKEUP))
|
||||
//! @}
|
||||
|
||||
//! Manage reset event
|
||||
//! Set when a USB "End of Reset" has been detected
|
||||
//! @{
|
||||
#define udd_enable_reset_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_EORSTES)
|
||||
#define udd_disable_reset_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_EORSTEC)
|
||||
#define Is_udd_reset_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_EORSTE))
|
||||
#define udd_ack_reset() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_EORSTC)
|
||||
#define udd_raise_reset() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_EORSTS)
|
||||
#define Is_udd_reset() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_EORST))
|
||||
//! @}
|
||||
|
||||
//! Manage start of frame event
|
||||
//! @{
|
||||
#define udd_enable_sof_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_SOFES)
|
||||
#define udd_disable_sof_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_SOFEC)
|
||||
#define Is_udd_sof_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_SOFE))
|
||||
#define udd_ack_sof() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_SOFC)
|
||||
#define udd_raise_sof() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_SOFS)
|
||||
#define Is_udd_sof() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_SOF))
|
||||
#define udd_frame_number() (Rd_bitfield(UOTGHS->UOTGHS_DEVFNUM, UOTGHS_DEVFNUM_FNUM_Msk))
|
||||
#define Is_udd_frame_number_crc_error() (Tst_bits(UOTGHS->UOTGHS_DEVFNUM, UOTGHS_DEVFNUM_FNCERR))
|
||||
//! @}
|
||||
|
||||
//! Manage Micro start of frame event (High Speed Only)
|
||||
//! @{
|
||||
#define udd_enable_msof_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_MSOFES)
|
||||
#define udd_disable_msof_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_MSOFEC)
|
||||
#define Is_udd_msof_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_MSOFE))
|
||||
#define udd_ack_msof() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVIMR_MSOFE)
|
||||
#define udd_raise_msof() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_MSOFS)
|
||||
#define Is_udd_msof() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_MSOF))
|
||||
#define udd_micro_frame_number() \
|
||||
(Rd_bitfield(UOTGHS->UOTGHS_DEVFNUM, (UOTGHS_DEVFNUM_FNUM_Msk|UOTGHS_DEVFNUM_MFNUM_Msk)))
|
||||
//! @}
|
||||
|
||||
//! Manage suspend event
|
||||
//! @{
|
||||
#define udd_enable_suspend_interrupt() (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_SUSPES)
|
||||
#define udd_disable_suspend_interrupt() (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_SUSPEC)
|
||||
#define Is_udd_suspend_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_SUSPE))
|
||||
#define udd_ack_suspend() (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_SUSPC)
|
||||
#define udd_raise_suspend() (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_SUSPS)
|
||||
#define Is_udd_suspend() (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_SUSP))
|
||||
//! @}
|
||||
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS device address control
|
||||
//! These macros manage the UOTGHS Device address.
|
||||
//! @{
|
||||
//! enables USB device address
|
||||
#define udd_enable_address() (Set_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_ADDEN))
|
||||
//! disables USB device address
|
||||
#define udd_disable_address() (Clr_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_ADDEN))
|
||||
#define Is_udd_address_enabled() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_ADDEN))
|
||||
//! configures the USB device address
|
||||
#define udd_configure_address(addr) (Wr_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_UADD_Msk, addr))
|
||||
//! gets the currently configured USB device address
|
||||
#define udd_get_configured_address() (Rd_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_UADD_Msk))
|
||||
//! @}
|
||||
|
||||
|
||||
//! @name UOTGHS Device endpoint drivers
|
||||
//! These macros manage the common features of the endpoints.
|
||||
//! @{
|
||||
|
||||
//! Generic macro for UOTGHS registers that can be arrayed
|
||||
//! @{
|
||||
#define UOTGHS_ARRAY(reg,index) ((&(UOTGHS->reg))[(index)])
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device endpoint configuration
|
||||
//! @{
|
||||
//! enables the selected endpoint
|
||||
#define udd_enable_endpoint(ep) (Set_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPEN0 << (ep)))
|
||||
//! disables the selected endpoint
|
||||
#define udd_disable_endpoint(ep) (Clr_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPEN0 << (ep)))
|
||||
//! tests if the selected endpoint is enabled
|
||||
#define Is_udd_endpoint_enabled(ep) (Tst_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPEN0 << (ep)))
|
||||
//! resets the selected endpoint
|
||||
#define udd_reset_endpoint(ep) \
|
||||
do { \
|
||||
Set_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPRST0 << (ep)); \
|
||||
Clr_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPRST0 << (ep)); \
|
||||
} while (0)
|
||||
//! Tests if the selected endpoint is being reset
|
||||
#define Is_udd_resetting_endpoint(ep) (Tst_bits(UOTGHS->UOTGHS_DEVEPT, UOTGHS_DEVEPT_EPRST0 << (ep)))
|
||||
|
||||
//! Configures the selected endpoint type
|
||||
#define udd_configure_endpoint_type(ep, type) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPTYPE_Msk, type))
|
||||
//! Gets the configured selected endpoint type
|
||||
#define udd_get_endpoint_type(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPTYPE_Msk))
|
||||
//! Enables the bank autoswitch for the selected endpoint
|
||||
#define udd_enable_endpoint_bank_autoswitch(ep) (Set_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_AUTOSW))
|
||||
//! Disables the bank autoswitch for the selected endpoint
|
||||
#define udd_disable_endpoint_bank_autoswitch(ep) (Clr_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_AUTOSW))
|
||||
#define Is_udd_endpoint_bank_autoswitch_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_AUTOSW))
|
||||
//! Configures the selected endpoint direction
|
||||
#define udd_configure_endpoint_direction(ep, dir) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPDIR, dir))
|
||||
//! Gets the configured selected endpoint direction
|
||||
#define udd_get_endpoint_direction(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPDIR))
|
||||
#define Is_udd_endpoint_in(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPDIR))
|
||||
//! Bounds given integer size to allowed range and rounds it up to the nearest
|
||||
//! available greater size, then applies register format of UOTGHS controller
|
||||
//! for endpoint size bit-field.
|
||||
#undef udd_format_endpoint_size
|
||||
#define udd_format_endpoint_size(size) (32 - clz(((uint32_t)min(max(size, 8), 1024) << 1) - 1) - 1 - 3)
|
||||
//! Configures the selected endpoint size
|
||||
#define udd_configure_endpoint_size(ep, size) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk, udd_format_endpoint_size(size)))
|
||||
//! Gets the configured selected endpoint size
|
||||
#define udd_get_endpoint_size(ep) (8 << Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk))
|
||||
//! Configures the selected endpoint number of banks
|
||||
#define udd_configure_endpoint_bank(ep, bank) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPBK_Msk, bank))
|
||||
//! Gets the configured selected endpoint number of banks
|
||||
#define udd_get_endpoint_bank(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPBK_Msk)+1)
|
||||
//! Allocates the configuration selected endpoint in DPRAM memory
|
||||
#define udd_allocate_memory(ep) (Set_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_ALLOC))
|
||||
//! un-allocates the configuration selected endpoint in DPRAM memory
|
||||
#define udd_unallocate_memory(ep) (Clr_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_ALLOC))
|
||||
#define Is_udd_memory_allocated(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_ALLOC))
|
||||
|
||||
//! Configures selected endpoint in one step
|
||||
#define udd_configure_endpoint(ep, type, dir, size, bank) (\
|
||||
Wr_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPTYPE_Msk |\
|
||||
UOTGHS_DEVEPTCFG_EPDIR |\
|
||||
UOTGHS_DEVEPTCFG_EPSIZE_Msk |\
|
||||
UOTGHS_DEVEPTCFG_EPBK_Msk , \
|
||||
(((uint32_t)(type) << UOTGHS_DEVEPTCFG_EPTYPE_Pos) & UOTGHS_DEVEPTCFG_EPTYPE_Msk) |\
|
||||
(((uint32_t)(dir ) << UOTGHS_DEVEPTCFG_EPDIR_Pos ) & UOTGHS_DEVEPTCFG_EPDIR) |\
|
||||
( (uint32_t)udd_format_endpoint_size(size) << UOTGHS_DEVEPTCFG_EPSIZE_Pos) |\
|
||||
(((uint32_t)(bank) << UOTGHS_DEVEPTCFG_EPBK_Pos) & UOTGHS_DEVEPTCFG_EPBK_Msk))\
|
||||
)
|
||||
//! Tests if current endpoint is configured
|
||||
#define Is_udd_endpoint_configured(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_CFGOK))
|
||||
//! Returns the control direction
|
||||
#define udd_control_direction() (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], EP_CONTROL), UOTGHS_DEVEPTISR_CTRLDIR))
|
||||
|
||||
//! Resets the data toggle sequence
|
||||
#define udd_reset_data_toggle(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_RSTDTS)
|
||||
//! Tests if the data toggle sequence is being reset
|
||||
#define Is_udd_data_toggle_reset(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_RSTDT))
|
||||
//! Returns data toggle
|
||||
#define udd_data_toggle(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_DTSEQ_Msk))
|
||||
//! @}
|
||||
|
||||
|
||||
//! @name UOTGHS Device control endpoint
|
||||
//! These macros control the endpoints.
|
||||
//! @{
|
||||
|
||||
//! @name UOTGHS Device control endpoint interrupts
|
||||
//! These macros control the endpoints interrupts.
|
||||
//! @{
|
||||
//! Enables the selected endpoint interrupt
|
||||
#define udd_enable_endpoint_interrupt(ep) (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << (ep))
|
||||
//! Disables the selected endpoint interrupt
|
||||
#define udd_disable_endpoint_interrupt(ep) (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_PEP_0 << (ep))
|
||||
//! Tests if the selected endpoint interrupt is enabled
|
||||
#define Is_udd_endpoint_interrupt_enabled(ep) (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_PEP_0 << (ep)))
|
||||
//! Tests if an interrupt is triggered by the selected endpoint
|
||||
#define Is_udd_endpoint_interrupt(ep) (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_PEP_0 << (ep)))
|
||||
//! Returns the lowest endpoint number generating an endpoint interrupt or MAX_PEP_NB if none
|
||||
#define udd_get_interrupt_endpoint_number() (ctz(((UOTGHS->UOTGHS_DEVISR >> UOTGHS_DEVISR_PEP_Pos) & \
|
||||
(UOTGHS->UOTGHS_DEVIMR >> UOTGHS_DEVIMR_PEP_Pos)) | \
|
||||
(1 << MAX_PEP_NB)))
|
||||
#define UOTGHS_DEVISR_PEP_Pos 12
|
||||
#define UOTGHS_DEVIMR_PEP_Pos 12
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device control endpoint errors
|
||||
//! These macros control the endpoint errors.
|
||||
//! @{
|
||||
//! Enables the STALL handshake
|
||||
#define udd_enable_stall_handshake(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_STALLRQS)
|
||||
//! Disables the STALL handshake
|
||||
#define udd_disable_stall_handshake(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_STALLRQC)
|
||||
//! Tests if STALL handshake request is running
|
||||
#define Is_udd_endpoint_stall_requested(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_STALLRQ))
|
||||
//! Tests if STALL sent
|
||||
#define Is_udd_stall(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_STALLEDI))
|
||||
//! ACKs STALL sent
|
||||
#define udd_ack_stall(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_STALLEDIC)
|
||||
//! Raises STALL sent
|
||||
#define udd_raise_stall(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_STALLEDIS)
|
||||
//! Enables STALL sent interrupt
|
||||
#define udd_enable_stall_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_STALLEDES)
|
||||
//! Disables STALL sent interrupt
|
||||
#define udd_disable_stall_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_STALLEDEC)
|
||||
//! Tests if STALL sent interrupt is enabled
|
||||
#define Is_udd_stall_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_STALLEDE))
|
||||
|
||||
//! Tests if NAK OUT received
|
||||
#define Is_udd_nak_out(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_NAKOUTI))
|
||||
//! ACKs NAK OUT received
|
||||
#define udd_ack_nak_out(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_NAKOUTIC)
|
||||
//! Raises NAK OUT received
|
||||
#define udd_raise_nak_out(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_NAKOUTIS)
|
||||
//! Enables NAK OUT interrupt
|
||||
#define udd_enable_nak_out_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_NAKOUTES)
|
||||
//! Disables NAK OUT interrupt
|
||||
#define udd_disable_nak_out_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_NAKOUTEC)
|
||||
//! Tests if NAK OUT interrupt is enabled
|
||||
#define Is_udd_nak_out_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_NAKOUTE))
|
||||
|
||||
//! Tests if NAK IN received
|
||||
#define Is_udd_nak_in(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_NAKINI))
|
||||
//! ACKs NAK IN received
|
||||
#define udd_ack_nak_in(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_NAKINIC)
|
||||
//! Raises NAK IN received
|
||||
#define udd_raise_nak_in(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_NAKINIS)
|
||||
//! Enables NAK IN interrupt
|
||||
#define udd_enable_nak_in_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_NAKINES)
|
||||
//! Disables NAK IN interrupt
|
||||
#define udd_disable_nak_in_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_NAKINEC)
|
||||
//! Tests if NAK IN interrupt is enabled
|
||||
#define Is_udd_nak_in_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_NAKINE))
|
||||
|
||||
//! ACKs endpoint isochronous overflow interrupt
|
||||
#define udd_ack_overflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_OVERFIC)
|
||||
//! Raises endpoint isochronous overflow interrupt
|
||||
#define udd_raise_overflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_OVERFIS)
|
||||
//! Tests if an overflow occurs
|
||||
#define Is_udd_overflow(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_OVERFI))
|
||||
//! Enables overflow interrupt
|
||||
#define udd_enable_overflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_OVERFES)
|
||||
//! Disables overflow interrupt
|
||||
#define udd_disable_overflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_OVERFEC)
|
||||
//! Tests if overflow interrupt is enabled
|
||||
#define Is_udd_overflow_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_OVERFE))
|
||||
|
||||
//! ACKs endpoint isochronous underflow interrupt
|
||||
#define udd_ack_underflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_UNDERFIC)
|
||||
//! Raises endpoint isochronous underflow interrupt
|
||||
#define udd_raise_underflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_UNDERFIS)
|
||||
//! Tests if an underflow occurs
|
||||
#define Is_udd_underflow(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_UNDERFI))
|
||||
//! Enables underflow interrupt
|
||||
#define udd_enable_underflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_UNDERFES)
|
||||
//! Disables underflow interrupt
|
||||
#define udd_disable_underflow_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_UNDERFEC)
|
||||
//! Tests if underflow interrupt is enabled
|
||||
#define Is_udd_underflow_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_UNDERFE))
|
||||
|
||||
//! Tests if CRC ERROR ISO OUT detected
|
||||
#define Is_udd_crc_error(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_CRCERRI))
|
||||
//! ACKs CRC ERROR ISO OUT detected
|
||||
#define udd_ack_crc_error(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_CRCERRIC)
|
||||
//! Raises CRC ERROR ISO OUT detected
|
||||
#define udd_raise_crc_error(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_CRCERRIS)
|
||||
//! Enables CRC ERROR ISO OUT detected interrupt
|
||||
#define udd_enable_crc_error_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_CRCERRES)
|
||||
//! Disables CRC ERROR ISO OUT detected interrupt
|
||||
#define udd_disable_crc_error_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_CRCERREC)
|
||||
//! Tests if CRC ERROR ISO OUT detected interrupt is enabled
|
||||
#define Is_udd_crc_error_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_CRCERRE))
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS Device control endpoint transfer
|
||||
//! These macros control the endpoint transfer.
|
||||
//! @{
|
||||
|
||||
//! Tests if endpoint read allowed
|
||||
#define Is_udd_read_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_RWALL))
|
||||
//! Tests if endpoint write allowed
|
||||
#define Is_udd_write_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_RWALL))
|
||||
|
||||
//! Returns the byte count
|
||||
#define udd_byte_count(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_BYCT_Msk))
|
||||
//! Clears FIFOCON bit
|
||||
#define udd_ack_fifocon(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_FIFOCONC)
|
||||
//! Tests if FIFOCON bit set
|
||||
#define Is_udd_fifocon(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_FIFOCON))
|
||||
|
||||
//! Returns the number of busy banks
|
||||
#define udd_nb_busy_bank(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_NBUSYBK_Msk))
|
||||
//! Returns the number of the current bank
|
||||
#define udd_current_bank(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_CURRBK_Msk))
|
||||
//! Kills last bank
|
||||
#define udd_kill_last_in_bank(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_KILLBKS)
|
||||
#define Is_udd_kill_last(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_KILLBK))
|
||||
//! Tests if last bank killed
|
||||
#define Is_udd_last_in_bank_killed(ep) (!Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_KILLBK))
|
||||
//! Forces all banks full (OUT) or free (IN) interrupt
|
||||
#define udd_force_bank_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_NBUSYBKS)
|
||||
//! Unforces all banks full (OUT) or free (IN) interrupt
|
||||
#define udd_unforce_bank_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_NBUSYBKS)
|
||||
//! Enables all banks full (OUT) or free (IN) interrupt
|
||||
#define udd_enable_bank_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_NBUSYBKES)
|
||||
//! Disables all banks full (OUT) or free (IN) interrupt
|
||||
#define udd_disable_bank_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_NBUSYBKEC)
|
||||
//! Tests if all banks full (OUT) or free (IN) interrupt enabled
|
||||
#define Is_udd_bank_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_NBUSYBKE))
|
||||
|
||||
//! Tests if SHORT PACKET received
|
||||
#define Is_udd_short_packet(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_SHORTPACKET))
|
||||
//! ACKs SHORT PACKET received
|
||||
#define udd_ack_short_packet(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_SHORTPACKETC)
|
||||
//! Raises SHORT PACKET received
|
||||
#define udd_raise_short_packet(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_SHORTPACKETS)
|
||||
//! Enables SHORT PACKET received interrupt
|
||||
#define udd_enable_short_packet_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_SHORTPACKETES)
|
||||
//! Disables SHORT PACKET received interrupt
|
||||
#define udd_disable_short_packet_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_SHORTPACKETEC)
|
||||
//! Tests if SHORT PACKET received interrupt is enabled
|
||||
#define Is_udd_short_packet_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_SHORTPACKETE))
|
||||
|
||||
//! Tests if SETUP received
|
||||
#define Is_udd_setup_received(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_RXSTPI))
|
||||
//! ACKs SETUP received
|
||||
#define udd_ack_setup_received(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_RXSTPIC)
|
||||
//! Raises SETUP received
|
||||
#define udd_raise_setup_received(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_RXSTPIS)
|
||||
//! Enables SETUP received interrupt
|
||||
#define udd_enable_setup_received_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_RXSTPES)
|
||||
//! Disables SETUP received interrupt
|
||||
#define udd_disable_setup_received_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_RXSTPEC)
|
||||
//! Tests if SETUP received interrupt is enabled
|
||||
#define Is_udd_setup_received_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_RXSTPE))
|
||||
|
||||
//! Tests if OUT received
|
||||
#define Is_udd_out_received(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_RXOUTI))
|
||||
//! ACKs OUT received
|
||||
#define udd_ack_out_received(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_RXOUTIC)
|
||||
//! Raises OUT received
|
||||
#define udd_raise_out_received(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_RXOUTIS)
|
||||
//! Enables OUT received interrupt
|
||||
#define udd_enable_out_received_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_RXOUTES)
|
||||
//! Disables OUT received interrupt
|
||||
#define udd_disable_out_received_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_RXOUTEC)
|
||||
//! Tests if OUT received interrupt is enabled
|
||||
#define Is_udd_out_received_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_RXOUTE))
|
||||
|
||||
//! Tests if IN sending
|
||||
#define Is_udd_in_send(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_TXINI))
|
||||
//! ACKs IN sending
|
||||
#define udd_ack_in_send(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTICR[0], ep) = UOTGHS_DEVEPTICR_TXINIC)
|
||||
//! Raises IN sending
|
||||
#define udd_raise_in_send(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIFR[0], ep) = UOTGHS_DEVEPTIFR_TXINIS)
|
||||
//! Enables IN sending interrupt
|
||||
#define udd_enable_in_send_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0], ep) = UOTGHS_DEVEPTIER_TXINES)
|
||||
//! Disables IN sending interrupt
|
||||
#define udd_disable_in_send_interrupt(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0], ep) = UOTGHS_DEVEPTIDR_TXINEC)
|
||||
//! Tests if IN sending interrupt is enabled
|
||||
#define Is_udd_in_send_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_TXINE))
|
||||
|
||||
|
||||
//! Get 64-, 32-, 16- or 8-bit access to FIFO data register of selected endpoint.
|
||||
//! @param ep Endpoint of which to access FIFO data register
|
||||
//! @param scale Data scale in bits: 64, 32, 16 or 8
|
||||
//! @return Volatile 64-, 32-, 16- or 8-bit data pointer to FIFO data register
|
||||
//! @warning It is up to the user of this macro to make sure that all accesses
|
||||
//! are aligned with their natural boundaries except 64-bit accesses which
|
||||
//! require only 32-bit alignment.
|
||||
//! @warning It is up to the user of this macro to make sure that used HSB
|
||||
//! addresses are identical to the DPRAM internal pointer modulo 32 bits.
|
||||
#define udd_get_endpoint_fifo_access(ep, scale) \
|
||||
(((volatile TPASTE2(U, scale) (*)[0x8000 / ((scale) / 8)])UOTGHS_RAM_ADDR)[(ep)])
|
||||
|
||||
//! @name UOTGHS endpoint DMA drivers
|
||||
//! These macros manage the common features of the endpoint DMA channels.
|
||||
//! @{
|
||||
|
||||
//! Maximum transfer size on USB DMA
|
||||
#define UDD_ENDPOINT_MAX_TRANS 0x10000
|
||||
//! Enables the disabling of HDMA requests by endpoint interrupts
|
||||
#define udd_enable_endpoint_int_dis_hdma_req(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIER[0](ep) = UOTGHS_DEVEPTIER_EPDISHDMAS)
|
||||
//! Disables the disabling of HDMA requests by endpoint interrupts
|
||||
#define udd_disable_endpoint_int_dis_hdma_req(ep) (UOTGHS_ARRAY(UOTGHS_DEVEPTIDR[0](ep) = UOTGHS_DEVEPTIDR_EPDISHDMAC)
|
||||
//! Tests if the disabling of HDMA requests by endpoint interrupts is enabled
|
||||
#define Is_udd_endpoint_int_dis_hdma_req_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0](ep), UOTGHS_DEVEPTIMR_EPDISHDMA))
|
||||
|
||||
//! Raises the selected endpoint DMA channel interrupt
|
||||
#define udd_raise_endpoint_dma_interrupt(ep) (UOTGHS->UOTGHS_DEVIFR = UOTGHS_DEVIFR_DMA_1 << ((ep) - 1))
|
||||
//! Raises the selected endpoint DMA channel interrupt
|
||||
#define udd_clear_endpoint_dma_interrupt(ep) (UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVISR_DMA_1 << ((ep) - 1))
|
||||
//! Tests if an interrupt is triggered by the selected endpoint DMA channel
|
||||
#define Is_udd_endpoint_dma_interrupt(ep) (Tst_bits(UOTGHS->UOTGHS_DEVISR, UOTGHS_DEVISR_DMA_1 << ((ep) - 1)))
|
||||
//! Enables the selected endpoint DMA channel interrupt
|
||||
#define udd_enable_endpoint_dma_interrupt(ep) (UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_DMA_1 << ((ep) - 1))
|
||||
//! Disables the selected endpoint DMA channel interrupt
|
||||
#define udd_disable_endpoint_dma_interrupt(ep) (UOTGHS->UOTGHS_DEVIDR = UOTGHS_DEVIDR_DMA_1 << ((ep) - 1))
|
||||
//! Tests if the selected endpoint DMA channel interrupt is enabled
|
||||
#define Is_udd_endpoint_dma_interrupt_enabled(ep) (Tst_bits(UOTGHS->UOTGHS_DEVIMR, UOTGHS_DEVIMR_DMA_1 << ((ep) - 1)))
|
||||
|
||||
//! Access points to the UOTGHS device DMA memory map with arrayed registers
|
||||
//! @{
|
||||
//! Structure for DMA next descriptor register
|
||||
typedef struct {
|
||||
uint32_t *NXT_DSC_ADD;
|
||||
} uotghs_dma_nextdesc_t;
|
||||
//! Structure for DMA control register
|
||||
typedef struct {
|
||||
uint32_t CHANN_ENB:1,
|
||||
LDNXT_DSC:1,
|
||||
END_TR_EN:1,
|
||||
END_B_EN:1,
|
||||
END_TR_IT:1,
|
||||
END_BUFFIT:1,
|
||||
DESC_LD_IT:1,
|
||||
BUST_LCK:1,
|
||||
reserved:8,
|
||||
BUFF_LENGTH:16;
|
||||
} uotghs_dma_control_t;
|
||||
//! Structure for DMA status register
|
||||
typedef struct {
|
||||
uint32_t CHANN_ENB:1,
|
||||
CHANN_ACT:1,
|
||||
reserved0:2,
|
||||
END_TR_ST:1,
|
||||
END_BF_ST:1,
|
||||
DESC_LDST:1,
|
||||
reserved1:9,
|
||||
BUFF_COUNT:16;
|
||||
} uotghs_dma_status_t;
|
||||
//! Structure for DMA descriptor
|
||||
typedef struct {
|
||||
union {
|
||||
uint32_t nextdesc;
|
||||
uotghs_dma_nextdesc_t NEXTDESC;
|
||||
};
|
||||
uint32_t addr;
|
||||
union {
|
||||
uint32_t control;
|
||||
uotghs_dma_control_t CONTROL;
|
||||
};
|
||||
uint32_t reserved;
|
||||
} sam_uotghs_dmadesc_t, uotghs_dmadesc_t;
|
||||
//! Structure for DMA registers in a channel
|
||||
typedef struct {
|
||||
union {
|
||||
uint32_t nextdesc;
|
||||
uotghs_dma_nextdesc_t NEXTDESC;
|
||||
};
|
||||
uint32_t addr;
|
||||
union {
|
||||
uint32_t control;
|
||||
uotghs_dma_control_t CONTROL;
|
||||
};
|
||||
union {
|
||||
unsigned long status;
|
||||
uotghs_dma_status_t STATUS;
|
||||
};
|
||||
} sam_uotghs_dmach_t, uotghs_dmach_t;
|
||||
//! DMA channel control command
|
||||
#define UDD_ENDPOINT_DMA_STOP_NOW (0)
|
||||
#define UDD_ENDPOINT_DMA_RUN_AND_STOP (UOTGHS_DEVDMACONTROL_CHANN_ENB)
|
||||
#define UDD_ENDPOINT_DMA_LOAD_NEXT_DESC (UOTGHS_DEVDMACONTROL_LDNXT_DSC)
|
||||
#define UDD_ENDPOINT_DMA_RUN_AND_LINK (UOTGHS_DEVDMACONTROL_CHANN_ENB|UOTGHS_DEVDMACONTROL_LDNXT_DSC)
|
||||
//! Structure for DMA registers
|
||||
#define UOTGHS_UDDMA_ARRAY(ep) (((volatile uotghs_dmach_t *)UOTGHS->UOTGHS_DEVDMA)[(ep) - 1])
|
||||
|
||||
//! Set control desc to selected endpoint DMA channel
|
||||
#define udd_endpoint_dma_set_control(ep,desc) (UOTGHS_UDDMA_ARRAY(ep).control = desc)
|
||||
//! Get control desc to selected endpoint DMA channel
|
||||
#define udd_endpoint_dma_get_control(ep) (UOTGHS_UDDMA_ARRAY(ep).control)
|
||||
//! Set RAM address to selected endpoint DMA channel
|
||||
#define udd_endpoint_dma_set_addr(ep,add) (UOTGHS_UDDMA_ARRAY(ep).addr = add)
|
||||
//! Get status to selected endpoint DMA channel
|
||||
#define udd_endpoint_dma_get_status(ep) (UOTGHS_UDDMA_ARRAY(ep).status)
|
||||
//! @}
|
||||
//! @}
|
||||
|
||||
//! @}
|
||||
//! @}
|
||||
//! @}
|
||||
//! @}
|
||||
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
/**INDENT-ON**/
|
||||
/// @endcond
|
||||
|
||||
#endif /* UOTGHS_DEVICE_H_INCLUDED */
|
241
Marlin/src/HAL/DUE/usb/uotghs_otg.h
Normal file
241
Marlin/src/HAL/DUE/usb/uotghs_otg.h
Normal file
@ -0,0 +1,241 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB OTG Driver for UOTGHS.
|
||||
*
|
||||
* Copyright (c) 2012-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef UOTGHS_OTG_H_INCLUDED
|
||||
#define UOTGHS_OTG_H_INCLUDED
|
||||
|
||||
#include "compiler.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
//! \ingroup usb_group
|
||||
//! \defgroup otg_group UOTGHS OTG Driver
|
||||
//! UOTGHS low-level driver for OTG features
|
||||
//!
|
||||
//! @{
|
||||
|
||||
/**
|
||||
* \brief Initialize the dual role
|
||||
* This function is implemented in uotghs_host.c file.
|
||||
*
|
||||
* \return \c true if the ID pin management has been started, otherwise \c false.
|
||||
*/
|
||||
bool otg_dual_enable(void);
|
||||
|
||||
/**
|
||||
* \brief Uninitialize the dual role
|
||||
* This function is implemented in uotghs_host.c file.
|
||||
*/
|
||||
void otg_dual_disable(void);
|
||||
|
||||
|
||||
//! @name UOTGHS OTG ID pin management
|
||||
//! The ID pin come from the USB OTG connector (A and B receptable) and
|
||||
//! allows to select the USB mode host or device.
|
||||
//! The UOTGHS hardware can manage it automatically. This feature is optional.
|
||||
//! When USB_ID_GPIO is defined (in board.h), this feature is enabled.
|
||||
//!
|
||||
//! @{
|
||||
//! Enable external OTG_ID pin (listened to by USB)
|
||||
#define otg_enable_id_pin() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIDE))
|
||||
//! Disable external OTG_ID pin (ignored by USB)
|
||||
#define otg_disable_id_pin() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIDE))
|
||||
//! Test if external OTG_ID pin enabled (listened to by USB)
|
||||
#define Is_otg_id_pin_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIDE))
|
||||
//! Disable external OTG_ID pin and force device mode
|
||||
#define otg_force_device_mode() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIMOD), otg_disable_id_pin())
|
||||
//! Test if device mode is forced
|
||||
#define Is_otg_device_mode_forced() (!Is_otg_id_pin_enabled() && Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIMOD))
|
||||
//! Disable external OTG_ID pin and force host mode
|
||||
#define otg_force_host_mode() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIMOD), otg_disable_id_pin())
|
||||
//! Test if host mode is forced
|
||||
#define Is_otg_host_mode_forced() (!Is_otg_id_pin_enabled() && !Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UIMOD))
|
||||
|
||||
//! @name UOTGHS OTG ID pin interrupt management
|
||||
//! These macros manage the ID pin interrupt
|
||||
//! @{
|
||||
#define otg_enable_id_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_IDTE))
|
||||
#define otg_disable_id_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_IDTE))
|
||||
#define Is_otg_id_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_IDTE))
|
||||
#define Is_otg_id_device() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_ID))
|
||||
#define Is_otg_id_host() (!Is_otg_id_device())
|
||||
#define otg_ack_id_transition() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_IDTIC)
|
||||
#define otg_raise_id_transition() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_IDTIS)
|
||||
#define Is_otg_id_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_IDTI))
|
||||
//! @}
|
||||
//! @}
|
||||
|
||||
//! @name OTG Vbus management
|
||||
//! @{
|
||||
#define otg_enable_vbus_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define otg_disable_vbus_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define Is_otg_vbus_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_VBUSTE))
|
||||
#define Is_otg_vbus_high() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUS))
|
||||
#define Is_otg_vbus_low() (!Is_otg_vbus_high())
|
||||
#define otg_ack_vbus_transition() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_VBUSTIC)
|
||||
#define otg_raise_vbus_transition() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_VBUSTIS)
|
||||
#define Is_otg_vbus_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUSTI))
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS OTG main management
|
||||
//! These macros allows to enable/disable pad and UOTGHS hardware
|
||||
//! @{
|
||||
//! Reset USB macro
|
||||
#define otg_reset() \
|
||||
do { \
|
||||
UOTGHS->UOTGHS_CTRL = 0; \
|
||||
while( UOTGHS->UOTGHS_SR & 0x3FFF) {\
|
||||
UOTGHS->UOTGHS_SCR = 0xFFFFFFFF;\
|
||||
} \
|
||||
} while (0)
|
||||
//! Enable USB macro
|
||||
#define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE))
|
||||
//! Disable USB macro
|
||||
#define otg_disable() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE))
|
||||
#define Is_otg_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE))
|
||||
|
||||
//! Enable OTG pad
|
||||
#define otg_enable_pad() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE))
|
||||
//! Disable OTG pad
|
||||
#define otg_disable_pad() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE))
|
||||
#define Is_otg_pad_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE))
|
||||
|
||||
//! Check Clock Usable
|
||||
//! For parts with HS feature, this one corresponding at UTMI clock
|
||||
#define Is_otg_clock_usable() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_CLKUSABLE))
|
||||
|
||||
//! Stop (freeze) internal USB clock
|
||||
#define otg_freeze_clock() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_FRZCLK))
|
||||
#define otg_unfreeze_clock() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_FRZCLK))
|
||||
#define Is_otg_clock_frozen() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_FRZCLK))
|
||||
|
||||
//! Configure time-out of specified OTG timer
|
||||
#define otg_configure_timeout(timer, timeout) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\
|
||||
Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\
|
||||
Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\
|
||||
Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK))
|
||||
//! Get configured time-out of specified OTG timer
|
||||
#define otg_get_timeout(timer) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\
|
||||
Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\
|
||||
Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\
|
||||
Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk))
|
||||
|
||||
|
||||
//! Get the dual-role device state of the internal USB finite state machine of the UOTGHS controller
|
||||
#define otg_get_fsm_drd_state() (Rd_bitfield(UOTGHS->UOTGHS_FSM, UOTGHS_FSM_DRDSTATE_Msk))
|
||||
#define Is_otg_a_suspend() (4==otg_get_fsm_drd_state())
|
||||
#define Is_otg_a_wait_vrise() (1==otg_get_fsm_drd_state())
|
||||
//! @}
|
||||
|
||||
//! @name UOTGHS OTG hardware protocol
|
||||
//! These macros manages the hardware OTG protocol
|
||||
//! @{
|
||||
//! Initiates a Host negotiation Protocol
|
||||
#define otg_device_initiate_hnp() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPREQ))
|
||||
//! Accepts a Host negotiation Protocol
|
||||
#define otg_host_accept_hnp() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPREQ))
|
||||
//! Rejects a Host negotiation Protocol
|
||||
#define otg_host_reject_hnp() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPREQ))
|
||||
//! initiates a Session Request Protocol
|
||||
#define otg_device_initiate_srp() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPREQ))
|
||||
//! Selects VBus as SRP method
|
||||
#define otg_select_vbus_srp_method() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPSEL))
|
||||
#define Is_otg_vbus_srp_method_selected() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPSEL))
|
||||
//! Selects data line as SRP method
|
||||
#define otg_select_data_srp_method() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPSEL))
|
||||
#define Is_otg_data_srp_method_selected() (!Is_otg_vbus_srp_method_selected())
|
||||
//! Tests if a HNP occurs
|
||||
#define Is_otg_hnp() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPREQ))
|
||||
//! Tests if a SRP from device occurs
|
||||
#define Is_otg_device_srp() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPREQ))
|
||||
|
||||
//! Enables HNP error interrupt
|
||||
#define otg_enable_hnp_error_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPERRE))
|
||||
//! Disables HNP error interrupt
|
||||
#define otg_disable_hnp_error_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPERRE))
|
||||
#define Is_otg_hnp_error_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_HNPERRE))
|
||||
//! ACKs HNP error interrupt
|
||||
#define otg_ack_hnp_error_interrupt() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_HNPERRIC)
|
||||
//! Raises HNP error interrupt
|
||||
#define otg_raise_hnp_error_interrupt() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_HNPERRIS)
|
||||
//! Tests if a HNP error occurs
|
||||
#define Is_otg_hnp_error_interrupt() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_HNPERRI))
|
||||
|
||||
//! Enables role exchange interrupt
|
||||
#define otg_enable_role_exchange_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_ROLEEXE))
|
||||
//! Disables role exchange interrupt
|
||||
#define otg_disable_role_exchange_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_ROLEEXE))
|
||||
#define Is_otg_role_exchange_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_ROLEEXE))
|
||||
//! ACKs role exchange interrupt
|
||||
#define otg_ack_role_exchange_interrupt() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_ROLEEXIC)
|
||||
//! Raises role exchange interrupt
|
||||
#define otg_raise_role_exchange_interrupt() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_ROLEEXIS)
|
||||
//! Tests if a role exchange occurs
|
||||
#define Is_otg_role_exchange_interrupt() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_ROLEEXI))
|
||||
|
||||
//! Enables SRP interrupt
|
||||
#define otg_enable_srp_interrupt() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPE))
|
||||
//! Disables SRP interrupt
|
||||
#define otg_disable_srp_interrupt() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPE))
|
||||
#define Is_otg_srp_interrupt_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_SRPE))
|
||||
//! ACKs SRP interrupt
|
||||
#define otg_ack_srp_interrupt() (UOTGHS->UOTGHS_SCR = UOTGHS_SCR_SRPIC)
|
||||
//! Raises SRP interrupt
|
||||
#define otg_raise_srp_interrupt() (UOTGHS->UOTGHS_SFR = UOTGHS_SFR_SRPIS)
|
||||
//! Tests if a SRP occurs
|
||||
#define Is_otg_srp_interrupt() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_SRPI))
|
||||
//! @}
|
||||
|
||||
//! @}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* UOTGHS_OTG_H_INCLUDED */
|
496
Marlin/src/HAL/DUE/usb/usb_protocol.h
Normal file
496
Marlin/src/HAL/DUE/usb/usb_protocol.h
Normal file
@ -0,0 +1,496 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB protocol definitions.
|
||||
*
|
||||
* This file contains the USB definitions and data structures provided by the
|
||||
* USB 2.0 specification.
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _USB_PROTOCOL_H_
|
||||
#define _USB_PROTOCOL_H_
|
||||
|
||||
/**
|
||||
* \ingroup usb_group
|
||||
* \defgroup usb_protocol_group USB Protocol Definitions
|
||||
*
|
||||
* This module defines constants and data structures provided by the USB
|
||||
* 2.0 specification.
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
//! Value for field bcdUSB
|
||||
#define USB_V2_0 0x0200 //!< USB Specification version 2.00
|
||||
#define USB_V2_1 0x0201 //!< USB Specification version 2.01
|
||||
|
||||
/*! \name Generic definitions (Class, subclass and protocol)
|
||||
*/
|
||||
//! @{
|
||||
#define NO_CLASS 0x00
|
||||
#define CLASS_VENDOR_SPECIFIC 0xFF
|
||||
#define NO_SUBCLASS 0x00
|
||||
#define NO_PROTOCOL 0x00
|
||||
//! @}
|
||||
|
||||
//! \name IAD (Interface Association Descriptor) constants
|
||||
//! @{
|
||||
#define CLASS_IAD 0xEF
|
||||
#define SUB_CLASS_IAD 0x02
|
||||
#define PROTOCOL_IAD 0x01
|
||||
//! @}
|
||||
|
||||
/**
|
||||
* \brief USB request data transfer direction (bmRequestType)
|
||||
*/
|
||||
#define USB_REQ_DIR_OUT (0<<7) //!< Host to device
|
||||
#define USB_REQ_DIR_IN (1<<7) //!< Device to host
|
||||
#define USB_REQ_DIR_MASK (1<<7) //!< Mask
|
||||
|
||||
/**
|
||||
* \brief USB request types (bmRequestType)
|
||||
*/
|
||||
#define USB_REQ_TYPE_STANDARD (0<<5) //!< Standard request
|
||||
#define USB_REQ_TYPE_CLASS (1<<5) //!< Class-specific request
|
||||
#define USB_REQ_TYPE_VENDOR (2<<5) //!< Vendor-specific request
|
||||
#define USB_REQ_TYPE_MASK (3<<5) //!< Mask
|
||||
|
||||
/**
|
||||
* \brief USB recipient codes (bmRequestType)
|
||||
*/
|
||||
#define USB_REQ_RECIP_DEVICE (0<<0) //!< Recipient device
|
||||
#define USB_REQ_RECIP_INTERFACE (1<<0) //!< Recipient interface
|
||||
#define USB_REQ_RECIP_ENDPOINT (2<<0) //!< Recipient endpoint
|
||||
#define USB_REQ_RECIP_OTHER (3<<0) //!< Recipient other
|
||||
#define USB_REQ_RECIP_MASK (0x1F) //!< Mask
|
||||
|
||||
/**
|
||||
* \brief Standard USB requests (bRequest)
|
||||
*/
|
||||
enum usb_reqid {
|
||||
USB_REQ_GET_STATUS = 0,
|
||||
USB_REQ_CLEAR_FEATURE = 1,
|
||||
USB_REQ_SET_FEATURE = 3,
|
||||
USB_REQ_SET_ADDRESS = 5,
|
||||
USB_REQ_GET_DESCRIPTOR = 6,
|
||||
USB_REQ_SET_DESCRIPTOR = 7,
|
||||
USB_REQ_GET_CONFIGURATION = 8,
|
||||
USB_REQ_SET_CONFIGURATION = 9,
|
||||
USB_REQ_GET_INTERFACE = 10,
|
||||
USB_REQ_SET_INTERFACE = 11,
|
||||
USB_REQ_SYNCH_FRAME = 12,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB device status flags
|
||||
*
|
||||
*/
|
||||
enum usb_device_status {
|
||||
USB_DEV_STATUS_BUS_POWERED = 0,
|
||||
USB_DEV_STATUS_SELF_POWERED = 1,
|
||||
USB_DEV_STATUS_REMOTEWAKEUP = 2
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB Interface status flags
|
||||
*
|
||||
*/
|
||||
enum usb_interface_status {
|
||||
USB_IFACE_STATUS_RESERVED = 0
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB endpoint status flags
|
||||
*
|
||||
*/
|
||||
enum usb_endpoint_status {
|
||||
USB_EP_STATUS_HALTED = 1,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB device feature flags
|
||||
*
|
||||
* \note valid for SetFeature request.
|
||||
*/
|
||||
enum usb_device_feature {
|
||||
USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled
|
||||
USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode
|
||||
USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3,
|
||||
USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4,
|
||||
USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Test Mode possible on HS USB device
|
||||
*
|
||||
* \note valid for USB_DEV_FEATURE_TEST_MODE request.
|
||||
*/
|
||||
enum usb_device_hs_test_mode {
|
||||
USB_DEV_TEST_MODE_J = 1,
|
||||
USB_DEV_TEST_MODE_K = 2,
|
||||
USB_DEV_TEST_MODE_SE0_NAK = 3,
|
||||
USB_DEV_TEST_MODE_PACKET = 4,
|
||||
USB_DEV_TEST_MODE_FORCE_ENABLE = 5,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB endpoint feature/status flags
|
||||
*/
|
||||
enum usb_endpoint_feature {
|
||||
USB_EP_FEATURE_HALT = 0,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB Test Mode Selectors
|
||||
*/
|
||||
enum usb_test_mode_selector {
|
||||
USB_TEST_J = 0x01,
|
||||
USB_TEST_K = 0x02,
|
||||
USB_TEST_SE0_NAK = 0x03,
|
||||
USB_TEST_PACKET = 0x04,
|
||||
USB_TEST_FORCE_ENABLE = 0x05,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB descriptor types
|
||||
*/
|
||||
enum usb_descriptor_type {
|
||||
USB_DT_DEVICE = 1,
|
||||
USB_DT_CONFIGURATION = 2,
|
||||
USB_DT_STRING = 3,
|
||||
USB_DT_INTERFACE = 4,
|
||||
USB_DT_ENDPOINT = 5,
|
||||
USB_DT_DEVICE_QUALIFIER = 6,
|
||||
USB_DT_OTHER_SPEED_CONFIGURATION = 7,
|
||||
USB_DT_INTERFACE_POWER = 8,
|
||||
USB_DT_OTG = 9,
|
||||
USB_DT_IAD = 0x0B,
|
||||
USB_DT_BOS = 0x0F,
|
||||
USB_DT_DEVICE_CAPABILITY = 0x10,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief USB Device Capability types
|
||||
*/
|
||||
enum usb_capability_type {
|
||||
USB_DC_USB20_EXTENSION = 0x02,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief USB Device Capability - USB 2.0 Extension
|
||||
* To fill bmAttributes field of usb_capa_ext_desc_t structure.
|
||||
*/
|
||||
enum usb_capability_extension_attr {
|
||||
USB_DC_EXT_LPM = 0x00000002,
|
||||
};
|
||||
|
||||
#define HIRD_50_US 0
|
||||
#define HIRD_125_US 1
|
||||
#define HIRD_200_US 2
|
||||
#define HIRD_275_US 3
|
||||
#define HIRD_350_US 4
|
||||
#define HIRD_425_US 5
|
||||
#define HIRD_500_US 6
|
||||
#define HIRD_575_US 7
|
||||
#define HIRD_650_US 8
|
||||
#define HIRD_725_US 9
|
||||
#define HIRD_800_US 10
|
||||
#define HIRD_875_US 11
|
||||
#define HIRD_950_US 12
|
||||
#define HIRD_1025_US 13
|
||||
#define HIRD_1100_US 14
|
||||
#define HIRD_1175_US 15
|
||||
|
||||
/** Fields definition from a LPM TOKEN */
|
||||
#define USB_LPM_ATTRIBUT_BLINKSTATE_MASK (0xF << 0)
|
||||
#define USB_LPM_ATTRIBUT_FIRD_MASK (0xF << 4)
|
||||
#define USB_LPM_ATTRIBUT_REMOTEWAKE_MASK (1 << 8)
|
||||
#define USB_LPM_ATTRIBUT_BLINKSTATE(value) ((value & 0xF) << 0)
|
||||
#define USB_LPM_ATTRIBUT_FIRD(value) ((value & 0xF) << 4)
|
||||
#define USB_LPM_ATTRIBUT_REMOTEWAKE(value) ((value & 1) << 8)
|
||||
#define USB_LPM_ATTRIBUT_BLINKSTATE_L1 USB_LPM_ATTRIBUT_BLINKSTATE(1)
|
||||
|
||||
/**
|
||||
* \brief Standard USB endpoint transfer types
|
||||
*/
|
||||
enum usb_ep_type {
|
||||
USB_EP_TYPE_CONTROL = 0x00,
|
||||
USB_EP_TYPE_ISOCHRONOUS = 0x01,
|
||||
USB_EP_TYPE_BULK = 0x02,
|
||||
USB_EP_TYPE_INTERRUPT = 0x03,
|
||||
USB_EP_TYPE_MASK = 0x03,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Standard USB language IDs for string descriptors
|
||||
*/
|
||||
enum usb_langid {
|
||||
USB_LANGID_EN_US = 0x0409, //!< English (United States)
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief Mask selecting the index part of an endpoint address
|
||||
*/
|
||||
#define USB_EP_ADDR_MASK 0x0F
|
||||
|
||||
//! \brief USB address identifier
|
||||
typedef uint8_t usb_add_t;
|
||||
|
||||
/**
|
||||
* \brief Endpoint transfer direction is IN
|
||||
*/
|
||||
#define USB_EP_DIR_IN 0x80
|
||||
|
||||
/**
|
||||
* \brief Endpoint transfer direction is OUT
|
||||
*/
|
||||
#define USB_EP_DIR_OUT 0x00
|
||||
|
||||
//! \brief Endpoint identifier
|
||||
typedef uint8_t usb_ep_t;
|
||||
|
||||
/**
|
||||
* \brief Maximum length in bytes of a USB descriptor
|
||||
*
|
||||
* The maximum length of a USB descriptor is limited by the 8-bit
|
||||
* bLength field.
|
||||
*/
|
||||
#define USB_MAX_DESC_LEN 255
|
||||
|
||||
/*
|
||||
* 2-byte alignment requested for all USB structures.
|
||||
*/
|
||||
COMPILER_PACK_SET(1)
|
||||
|
||||
/**
|
||||
* \brief A USB Device SETUP request
|
||||
*
|
||||
* The data payload of SETUP packets always follows this structure.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bmRequestType;
|
||||
uint8_t bRequest;
|
||||
le16_t wValue;
|
||||
le16_t wIndex;
|
||||
le16_t wLength;
|
||||
} usb_setup_req_t;
|
||||
|
||||
/**
|
||||
* \brief Standard USB device descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
le16_t bcdUSB;
|
||||
uint8_t bDeviceClass;
|
||||
uint8_t bDeviceSubClass;
|
||||
uint8_t bDeviceProtocol;
|
||||
uint8_t bMaxPacketSize0;
|
||||
le16_t idVendor;
|
||||
le16_t idProduct;
|
||||
le16_t bcdDevice;
|
||||
uint8_t iManufacturer;
|
||||
uint8_t iProduct;
|
||||
uint8_t iSerialNumber;
|
||||
uint8_t bNumConfigurations;
|
||||
} usb_dev_desc_t;
|
||||
|
||||
/**
|
||||
* \brief Standard USB device qualifier descriptor structure
|
||||
*
|
||||
* This descriptor contains information about the device when running at
|
||||
* the "other" speed (i.e. if the device is currently operating at high
|
||||
* speed, this descriptor can be used to determine what would change if
|
||||
* the device was operating at full speed.)
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
le16_t bcdUSB;
|
||||
uint8_t bDeviceClass;
|
||||
uint8_t bDeviceSubClass;
|
||||
uint8_t bDeviceProtocol;
|
||||
uint8_t bMaxPacketSize0;
|
||||
uint8_t bNumConfigurations;
|
||||
uint8_t bReserved;
|
||||
} usb_dev_qual_desc_t;
|
||||
|
||||
/**
|
||||
* \brief USB Device BOS descriptor structure
|
||||
*
|
||||
* The BOS descriptor (Binary device Object Store) defines a root
|
||||
* descriptor that is similar to the configuration descriptor, and is
|
||||
* the base descriptor for accessing a family of related descriptors.
|
||||
* A host can read a BOS descriptor and learn from the wTotalLength field
|
||||
* the entire size of the device-level descriptor set, or it can read in
|
||||
* the entire BOS descriptor set of device capabilities.
|
||||
* The host accesses this descriptor using the GetDescriptor() request.
|
||||
* The descriptor type in the GetDescriptor() request is set to BOS.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
le16_t wTotalLength;
|
||||
uint8_t bNumDeviceCaps;
|
||||
} usb_dev_bos_desc_t;
|
||||
|
||||
|
||||
/**
|
||||
* \brief USB Device Capabilities - USB 2.0 Extension Descriptor structure
|
||||
*
|
||||
* Defines the set of USB 1.1-specific device level capabilities.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDevCapabilityType;
|
||||
le32_t bmAttributes;
|
||||
} usb_dev_capa_ext_desc_t;
|
||||
|
||||
/**
|
||||
* \brief USB Device LPM Descriptor structure
|
||||
*
|
||||
* The BOS descriptor and capabilities descriptors for LPM.
|
||||
*/
|
||||
typedef struct {
|
||||
usb_dev_bos_desc_t bos;
|
||||
usb_dev_capa_ext_desc_t capa_ext;
|
||||
} usb_dev_lpm_desc_t;
|
||||
|
||||
/**
|
||||
* \brief Standard USB Interface Association Descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength; //!< size of this descriptor in bytes
|
||||
uint8_t bDescriptorType; //!< INTERFACE descriptor type
|
||||
uint8_t bFirstInterface; //!< Number of interface
|
||||
uint8_t bInterfaceCount; //!< value to select alternate setting
|
||||
uint8_t bFunctionClass; //!< Class code assigned by the USB
|
||||
uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB
|
||||
uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB
|
||||
uint8_t iFunction; //!< Index of string descriptor
|
||||
} usb_association_desc_t;
|
||||
|
||||
|
||||
/**
|
||||
* \brief Standard USB configuration descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
le16_t wTotalLength;
|
||||
uint8_t bNumInterfaces;
|
||||
uint8_t bConfigurationValue;
|
||||
uint8_t iConfiguration;
|
||||
uint8_t bmAttributes;
|
||||
uint8_t bMaxPower;
|
||||
} usb_conf_desc_t;
|
||||
|
||||
|
||||
#define USB_CONFIG_ATTR_MUST_SET (1 << 7) //!< Must always be set
|
||||
#define USB_CONFIG_ATTR_BUS_POWERED (0 << 6) //!< Bus-powered
|
||||
#define USB_CONFIG_ATTR_SELF_POWERED (1 << 6) //!< Self-powered
|
||||
#define USB_CONFIG_ATTR_REMOTE_WAKEUP (1 << 5) //!< remote wakeup supported
|
||||
|
||||
#define USB_CONFIG_MAX_POWER(ma) (((ma) + 1) / 2) //!< Max power in mA
|
||||
|
||||
/**
|
||||
* \brief Standard USB association descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength; //!< Size of this descriptor in bytes
|
||||
uint8_t bDescriptorType; //!< Interface descriptor type
|
||||
uint8_t bFirstInterface; //!< Number of interface
|
||||
uint8_t bInterfaceCount; //!< value to select alternate setting
|
||||
uint8_t bFunctionClass; //!< Class code assigned by the USB
|
||||
uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB
|
||||
uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB
|
||||
uint8_t iFunction; //!< Index of string descriptor
|
||||
} usb_iad_desc_t;
|
||||
|
||||
/**
|
||||
* \brief Standard USB interface descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bInterfaceNumber;
|
||||
uint8_t bAlternateSetting;
|
||||
uint8_t bNumEndpoints;
|
||||
uint8_t bInterfaceClass;
|
||||
uint8_t bInterfaceSubClass;
|
||||
uint8_t bInterfaceProtocol;
|
||||
uint8_t iInterface;
|
||||
} usb_iface_desc_t;
|
||||
|
||||
/**
|
||||
* \brief Standard USB endpoint descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bEndpointAddress;
|
||||
uint8_t bmAttributes;
|
||||
le16_t wMaxPacketSize;
|
||||
uint8_t bInterval;
|
||||
} usb_ep_desc_t;
|
||||
|
||||
|
||||
/**
|
||||
* \brief A standard USB string descriptor structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
} usb_str_desc_t;
|
||||
|
||||
typedef struct {
|
||||
usb_str_desc_t desc;
|
||||
le16_t string[1];
|
||||
} usb_str_lgid_desc_t;
|
||||
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
//! @}
|
||||
|
||||
#endif /* _USB_PROTOCOL_H_ */
|
320
Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h
Normal file
320
Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h
Normal file
@ -0,0 +1,320 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB Communication Device Class (CDC) protocol definitions
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
#ifndef _USB_PROTOCOL_CDC_H_
|
||||
#define _USB_PROTOCOL_CDC_H_
|
||||
|
||||
#include "compiler.h"
|
||||
|
||||
/**
|
||||
* \ingroup usb_protocol_group
|
||||
* \defgroup cdc_protocol_group Communication Device Class Definitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \name Possible values of class
|
||||
*/
|
||||
//@{
|
||||
#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class
|
||||
#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface
|
||||
#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface
|
||||
#define CDC_CLASS_MULTI 0xEF //!< CDC Multi-interface Function
|
||||
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Subclass IDs
|
||||
//@{
|
||||
#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model
|
||||
#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model
|
||||
#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model
|
||||
#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model
|
||||
#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model
|
||||
#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model
|
||||
#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Communication Interface Protocol IDs
|
||||
//@{
|
||||
#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Data Interface Protocol IDs
|
||||
//@{
|
||||
#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI
|
||||
#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC
|
||||
#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent
|
||||
#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol
|
||||
#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol
|
||||
#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor
|
||||
#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures
|
||||
#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control
|
||||
#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN
|
||||
#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands
|
||||
#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver
|
||||
/**
|
||||
* \brief Describes the Protocol Unit Functional Descriptors [sic]
|
||||
* on Communication Class Interface
|
||||
*/
|
||||
#define CDC_PROTOCOL_PUFD 0xFE
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Functional Descriptor Types
|
||||
//@{
|
||||
#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor
|
||||
#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Functional Descriptor Subtypes
|
||||
//@{
|
||||
#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor
|
||||
#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management
|
||||
#define CDC_SCS_ACM 0x02 //!< Abstract Control Management
|
||||
#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor
|
||||
//@}
|
||||
|
||||
//! \name USB CDC Request IDs
|
||||
//@{
|
||||
#define USB_REQ_CDC_SEND_ENCAPSULATED_COMMAND 0x00
|
||||
#define USB_REQ_CDC_GET_ENCAPSULATED_RESPONSE 0x01
|
||||
#define USB_REQ_CDC_SET_COMM_FEATURE 0x02
|
||||
#define USB_REQ_CDC_GET_COMM_FEATURE 0x03
|
||||
#define USB_REQ_CDC_CLEAR_COMM_FEATURE 0x04
|
||||
#define USB_REQ_CDC_SET_AUX_LINE_STATE 0x10
|
||||
#define USB_REQ_CDC_SET_HOOK_STATE 0x11
|
||||
#define USB_REQ_CDC_PULSE_SETUP 0x12
|
||||
#define USB_REQ_CDC_SEND_PULSE 0x13
|
||||
#define USB_REQ_CDC_SET_PULSE_TIME 0x14
|
||||
#define USB_REQ_CDC_RING_AUX_JACK 0x15
|
||||
#define USB_REQ_CDC_SET_LINE_CODING 0x20
|
||||
#define USB_REQ_CDC_GET_LINE_CODING 0x21
|
||||
#define USB_REQ_CDC_SET_CONTROL_LINE_STATE 0x22
|
||||
#define USB_REQ_CDC_SEND_BREAK 0x23
|
||||
#define USB_REQ_CDC_SET_RINGER_PARMS 0x30
|
||||
#define USB_REQ_CDC_GET_RINGER_PARMS 0x31
|
||||
#define USB_REQ_CDC_SET_OPERATION_PARMS 0x32
|
||||
#define USB_REQ_CDC_GET_OPERATION_PARMS 0x33
|
||||
#define USB_REQ_CDC_SET_LINE_PARMS 0x34
|
||||
#define USB_REQ_CDC_GET_LINE_PARMS 0x35
|
||||
#define USB_REQ_CDC_DIAL_DIGITS 0x36
|
||||
#define USB_REQ_CDC_SET_UNIT_PARAMETER 0x37
|
||||
#define USB_REQ_CDC_GET_UNIT_PARAMETER 0x38
|
||||
#define USB_REQ_CDC_CLEAR_UNIT_PARAMETER 0x39
|
||||
#define USB_REQ_CDC_GET_PROFILE 0x3A
|
||||
#define USB_REQ_CDC_SET_ETHERNET_MULTICAST_FILTERS 0x40
|
||||
#define USB_REQ_CDC_SET_ETHERNET_POWER_MANAGEMENT_PATTERNFILTER 0x41
|
||||
#define USB_REQ_CDC_GET_ETHERNET_POWER_MANAGEMENT_PATTERNFILTER 0x42
|
||||
#define USB_REQ_CDC_SET_ETHERNET_PACKET_FILTER 0x43
|
||||
#define USB_REQ_CDC_GET_ETHERNET_STATISTIC 0x44
|
||||
#define USB_REQ_CDC_SET_ATM_DATA_FORMAT 0x50
|
||||
#define USB_REQ_CDC_GET_ATM_DEVICE_STATISTICS 0x51
|
||||
#define USB_REQ_CDC_SET_ATM_DEFAULT_VC 0x52
|
||||
#define USB_REQ_CDC_GET_ATM_VC_STATISTICS 0x53
|
||||
// Added bNotification codes according cdc spec 1.1 chapter 6.3
|
||||
#define USB_REQ_CDC_NOTIFY_RING_DETECT 0x09
|
||||
#define USB_REQ_CDC_NOTIFY_SERIAL_STATE 0x20
|
||||
#define USB_REQ_CDC_NOTIFY_CALL_STATE_CHANGE 0x28
|
||||
#define USB_REQ_CDC_NOTIFY_LINE_STATE_CHANGE 0x29
|
||||
//@}
|
||||
|
||||
/*
|
||||
* Need to pack structures tightly, or the compiler might insert padding
|
||||
* and violate the spec-mandated layout.
|
||||
*/
|
||||
COMPILER_PACK_SET(1)
|
||||
|
||||
//! \name USB CDC Descriptors
|
||||
//@{
|
||||
|
||||
|
||||
//! CDC Header Functional Descriptor
|
||||
typedef struct {
|
||||
uint8_t bFunctionLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubtype;
|
||||
le16_t bcdCDC;
|
||||
} usb_cdc_hdr_desc_t;
|
||||
|
||||
//! CDC Call Management Functional Descriptor
|
||||
typedef struct {
|
||||
uint8_t bFunctionLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubtype;
|
||||
uint8_t bmCapabilities;
|
||||
uint8_t bDataInterface;
|
||||
} usb_cdc_call_mgmt_desc_t;
|
||||
|
||||
//! CDC ACM Functional Descriptor
|
||||
typedef struct {
|
||||
uint8_t bFunctionLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubtype;
|
||||
uint8_t bmCapabilities;
|
||||
} usb_cdc_acm_desc_t;
|
||||
|
||||
//! CDC Union Functional Descriptor
|
||||
typedef struct {
|
||||
uint8_t bFunctionLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubtype;
|
||||
uint8_t bMasterInterface;
|
||||
uint8_t bSlaveInterface0;
|
||||
} usb_cdc_union_desc_t;
|
||||
|
||||
|
||||
//! \name USB CDC Call Management Capabilities
|
||||
//@{
|
||||
//! Device handles call management itself
|
||||
#define CDC_CALL_MGMT_SUPPORTED (1 << 0)
|
||||
//! Device can send/receive call management info over a Data Class interface
|
||||
#define CDC_CALL_MGMT_OVER_DCI (1 << 1)
|
||||
//@}
|
||||
|
||||
//! \name USB CDC ACM Capabilities
|
||||
//@{
|
||||
//! Device supports the request combination of
|
||||
//! Set_Comm_Feature, Clear_Comm_Feature, and Get_Comm_Feature.
|
||||
#define CDC_ACM_SUPPORT_FEATURE_REQUESTS (1 << 0)
|
||||
//! Device supports the request combination of
|
||||
//! Set_Line_Coding, Set_Control_Line_State, Get_Line_Coding,
|
||||
//! and the notification Serial_State.
|
||||
#define CDC_ACM_SUPPORT_LINE_REQUESTS (1 << 1)
|
||||
//! Device supports the request Send_Break
|
||||
#define CDC_ACM_SUPPORT_SENDBREAK_REQUESTS (1 << 2)
|
||||
//! Device supports the notification Network_Connection.
|
||||
#define CDC_ACM_SUPPORT_NOTIFY_REQUESTS (1 << 3)
|
||||
//@}
|
||||
//@}
|
||||
|
||||
//! \name USB CDC line control
|
||||
//@{
|
||||
|
||||
//! \name USB CDC line coding
|
||||
//@{
|
||||
//! Line Coding structure
|
||||
typedef struct {
|
||||
le32_t dwDTERate;
|
||||
uint8_t bCharFormat;
|
||||
uint8_t bParityType;
|
||||
uint8_t bDataBits;
|
||||
} usb_cdc_line_coding_t;
|
||||
//! Possible values of bCharFormat
|
||||
enum cdc_char_format {
|
||||
CDC_STOP_BITS_1 = 0, //!< 1 stop bit
|
||||
CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits
|
||||
CDC_STOP_BITS_2 = 2, //!< 2 stop bits
|
||||
};
|
||||
//! Possible values of bParityType
|
||||
enum cdc_parity {
|
||||
CDC_PAR_NONE = 0, //!< No parity
|
||||
CDC_PAR_ODD = 1, //!< Odd parity
|
||||
CDC_PAR_EVEN = 2, //!< Even parity
|
||||
CDC_PAR_MARK = 3, //!< Parity forced to 0 (space)
|
||||
CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark)
|
||||
};
|
||||
//@}
|
||||
|
||||
//! \name USB CDC control signals
|
||||
//! spec 1.1 chapter 6.2.14
|
||||
//@{
|
||||
|
||||
//! Control signal structure
|
||||
typedef struct {
|
||||
uint16_t value;
|
||||
} usb_cdc_control_signal_t;
|
||||
|
||||
//! \name Possible values in usb_cdc_control_signal_t
|
||||
//@{
|
||||
//! Carrier control for half duplex modems.
|
||||
//! This signal corresponds to V.24 signal 105 and RS-232 signal RTS.
|
||||
//! The device ignores the value of this bit
|
||||
//! when operating in full duplex mode.
|
||||
#define CDC_CTRL_SIGNAL_ACTIVATE_CARRIER (1 << 1)
|
||||
//! Indicates to DCE if DTE is present or not.
|
||||
//! This signal corresponds to V.24 signal 108/2 and RS-232 signal DTR.
|
||||
#define CDC_CTRL_SIGNAL_DTE_PRESENT (1 << 0)
|
||||
//@}
|
||||
//@}
|
||||
|
||||
|
||||
//! \name USB CDC notification message
|
||||
//@{
|
||||
|
||||
typedef struct {
|
||||
uint8_t bmRequestType;
|
||||
uint8_t bNotification;
|
||||
le16_t wValue;
|
||||
le16_t wIndex;
|
||||
le16_t wLength;
|
||||
} usb_cdc_notify_msg_t;
|
||||
|
||||
//! \name USB CDC serial state
|
||||
//@{*
|
||||
|
||||
//! Hardware handshake support (cdc spec 1.1 chapter 6.3.5)
|
||||
typedef struct {
|
||||
usb_cdc_notify_msg_t header;
|
||||
le16_t value;
|
||||
} usb_cdc_notify_serial_state_t;
|
||||
|
||||
//! \name Possible values in usb_cdc_notify_serial_state_t
|
||||
//@{
|
||||
#define CDC_SERIAL_STATE_DCD CPU_TO_LE16((1<<0))
|
||||
#define CDC_SERIAL_STATE_DSR CPU_TO_LE16((1<<1))
|
||||
#define CDC_SERIAL_STATE_BREAK CPU_TO_LE16((1<<2))
|
||||
#define CDC_SERIAL_STATE_RING CPU_TO_LE16((1<<3))
|
||||
#define CDC_SERIAL_STATE_FRAMING CPU_TO_LE16((1<<4))
|
||||
#define CDC_SERIAL_STATE_PARITY CPU_TO_LE16((1<<5))
|
||||
#define CDC_SERIAL_STATE_OVERRUN CPU_TO_LE16((1<<6))
|
||||
//@}
|
||||
//! @}
|
||||
|
||||
//! @}
|
||||
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
//! @}
|
||||
|
||||
#endif // _USB_PROTOCOL_CDC_H_
|
147
Marlin/src/HAL/DUE/usb/usb_protocol_msc.h
Normal file
147
Marlin/src/HAL/DUE/usb/usb_protocol_msc.h
Normal file
@ -0,0 +1,147 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief USB Mass Storage Class (MSC) protocol definitions.
|
||||
*
|
||||
* Copyright (c) 2009-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _USB_PROTOCOL_MSC_H_
|
||||
#define _USB_PROTOCOL_MSC_H_
|
||||
|
||||
|
||||
/**
|
||||
* \ingroup usb_protocol_group
|
||||
* \defgroup usb_msc_protocol USB Mass Storage Class (MSC) protocol definitions
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \name Possible Class value
|
||||
*/
|
||||
//@{
|
||||
#define MSC_CLASS 0x08
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \name Possible SubClass value
|
||||
* \note In practise, most devices should use
|
||||
* #MSC_SUBCLASS_TRANSPARENT and specify the actual command set in
|
||||
* the standard INQUIRY data block, even if the MSC spec indicates
|
||||
* otherwise. In particular, RBC is not supported by certain major
|
||||
* operating systems like Windows XP.
|
||||
*/
|
||||
//@{
|
||||
#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands
|
||||
#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices
|
||||
#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices
|
||||
#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives
|
||||
#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives
|
||||
#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY
|
||||
//@}
|
||||
|
||||
/**
|
||||
* \name Possible protocol value
|
||||
* \note Only the BULK protocol should be used in new designs.
|
||||
*/
|
||||
//@{
|
||||
#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt
|
||||
#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion
|
||||
#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* \brief MSC USB requests (bRequest)
|
||||
*/
|
||||
enum usb_reqid_msc {
|
||||
USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset
|
||||
USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN
|
||||
};
|
||||
|
||||
|
||||
COMPILER_PACK_SET(1)
|
||||
|
||||
/**
|
||||
* \name A Command Block Wrapper (CBW).
|
||||
*/
|
||||
//@{
|
||||
struct usb_msc_cbw {
|
||||
le32_t dCBWSignature; //!< Must contain 'USBC'
|
||||
le32_t dCBWTag; //!< Unique command ID
|
||||
le32_t dCBWDataTransferLength; //!< Number of bytes to transfer
|
||||
uint8_t bmCBWFlags; //!< Direction in bit 7
|
||||
uint8_t bCBWLUN; //!< Logical Unit Number
|
||||
uint8_t bCBWCBLength; //!< Number of valid CDB bytes
|
||||
uint8_t CDB[16]; //!< SCSI Command Descriptor Block
|
||||
};
|
||||
|
||||
#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value
|
||||
#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host
|
||||
#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device
|
||||
#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN
|
||||
#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength
|
||||
//@}
|
||||
|
||||
|
||||
/**
|
||||
* \name A Command Status Wrapper (CSW).
|
||||
*/
|
||||
//@{
|
||||
struct usb_msc_csw {
|
||||
le32_t dCSWSignature; //!< Must contain 'USBS'
|
||||
le32_t dCSWTag; //!< Same as dCBWTag
|
||||
le32_t dCSWDataResidue; //!< Number of bytes not transfered
|
||||
uint8_t bCSWStatus; //!< Status code
|
||||
};
|
||||
|
||||
#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value
|
||||
#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed
|
||||
#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed
|
||||
#define USB_CSW_STATUS_PE 0x02 //!< Phase Error
|
||||
//@}
|
||||
|
||||
COMPILER_PACK_RESET()
|
||||
|
||||
//@}
|
||||
|
||||
#endif // _USB_PROTOCOL_MSC_H_
|
341
Marlin/src/HAL/DUE/usb/usb_task.c
Normal file
341
Marlin/src/HAL/DUE/usb/usb_task.c
Normal file
@ -0,0 +1,341 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Main functions for USB composite example
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
|
||||
// Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <Reset.h>
|
||||
|
||||
#include "conf_usb.h"
|
||||
#include "udc.h"
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
static volatile bool main_b_msc_enable = false;
|
||||
#endif
|
||||
static volatile bool main_b_cdc_enable = false;
|
||||
static volatile bool main_b_dtr_active = false;
|
||||
|
||||
void usb_task_idle(void) {
|
||||
#if ENABLED(SDSUPPORT)
|
||||
// Attend SD card access from the USB MSD -- Prioritize access to improve speed
|
||||
int delay = 2;
|
||||
while (main_b_msc_enable && --delay > 0) {
|
||||
if (udi_msc_process_trans()) delay = 10000;
|
||||
|
||||
// Reset the watchdog, just to be sure
|
||||
REG_WDT_CR = WDT_CR_WDRSTT | WDT_CR_KEY(0xA5);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
bool usb_task_msc_enable(void) { return ((main_b_msc_enable = true)); }
|
||||
void usb_task_msc_disable(void) { main_b_msc_enable = false; }
|
||||
bool usb_task_msc_isenabled(void) { return main_b_msc_enable; }
|
||||
#endif
|
||||
|
||||
bool usb_task_cdc_enable(const uint8_t port) { UNUSED(port); return ((main_b_cdc_enable = true)); }
|
||||
void usb_task_cdc_disable(const uint8_t port) { UNUSED(port); main_b_cdc_enable = false; main_b_dtr_active = false; }
|
||||
bool usb_task_cdc_isenabled(void) { return main_b_cdc_enable; }
|
||||
|
||||
/*! \brief Called by CDC interface
|
||||
* Callback running when CDC device have received data
|
||||
*/
|
||||
void usb_task_cdc_rx_notify(const uint8_t port) { UNUSED(port); }
|
||||
|
||||
/*! \brief Configures communication line
|
||||
*
|
||||
* \param cfg line configuration
|
||||
*/
|
||||
static uint16_t dwDTERate = 0;
|
||||
void usb_task_cdc_config(const uint8_t port, usb_cdc_line_coding_t *cfg) {
|
||||
UNUSED(port);
|
||||
// Store last DTE rate
|
||||
dwDTERate = cfg->dwDTERate;
|
||||
}
|
||||
|
||||
void usb_task_cdc_set_dtr(const uint8_t port, const bool b_enable) {
|
||||
UNUSED(port);
|
||||
// Keep DTR status
|
||||
main_b_dtr_active = b_enable;
|
||||
|
||||
// Implement Arduino-Compatible kludge to enter programming mode from
|
||||
// the native port:
|
||||
// "Auto-reset into the bootloader is triggered when the port, already
|
||||
// open at 1200 bps, is closed."
|
||||
|
||||
if (1200 == dwDTERate) {
|
||||
// We check DTR state to determine if host port is open (bit 0 of lineState).
|
||||
if (!b_enable) {
|
||||
|
||||
// Set RST pin to go low for 65535 clock cycles on reset
|
||||
// This helps restarting when firmware flash ends
|
||||
RSTC->RSTC_MR = 0xA5000F01;
|
||||
|
||||
// Schedule delayed reset
|
||||
initiateReset(250);
|
||||
}
|
||||
else
|
||||
cancelReset();
|
||||
}
|
||||
}
|
||||
|
||||
bool usb_task_cdc_dtr_active(void) { return main_b_dtr_active; }
|
||||
|
||||
/// Microsoft WCID descriptor
|
||||
typedef struct USB_MicrosoftCompatibleDescriptor_Interface {
|
||||
uint8_t bFirstInterfaceNumber;
|
||||
uint8_t reserved1;
|
||||
uint8_t compatibleID[8];
|
||||
uint8_t subCompatibleID[8];
|
||||
uint8_t reserved2[6];
|
||||
} __attribute__((packed)) USB_MicrosoftCompatibleDescriptor_Interface;
|
||||
|
||||
typedef struct USB_MicrosoftCompatibleDescriptor {
|
||||
uint32_t dwLength;
|
||||
uint16_t bcdVersion;
|
||||
uint16_t wIndex;
|
||||
uint8_t bCount;
|
||||
uint8_t reserved[7];
|
||||
USB_MicrosoftCompatibleDescriptor_Interface interfaces[];
|
||||
} __attribute__((packed)) USB_MicrosoftCompatibleDescriptor;
|
||||
|
||||
// 3D Printer compatible descriptor
|
||||
static USB_MicrosoftCompatibleDescriptor microsoft_compatible_id_descriptor = {
|
||||
.dwLength = sizeof(USB_MicrosoftCompatibleDescriptor) +
|
||||
1*sizeof(USB_MicrosoftCompatibleDescriptor_Interface),
|
||||
.bcdVersion = 0x0100,
|
||||
.wIndex = 0x0004,
|
||||
.bCount = 1,
|
||||
.reserved = {0, 0, 0, 0, 0, 0, 0},
|
||||
.interfaces = {
|
||||
{
|
||||
.bFirstInterfaceNumber = 0,
|
||||
.reserved1 = 1,
|
||||
.compatibleID = "3DPRINT",
|
||||
.subCompatibleID = {0, 0, 0, 0, 0, 0, 0, 0},
|
||||
.reserved2 = {0, 0, 0, 0, 0, 0},
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
#define xstr(s) str(s)
|
||||
#define str(s) #s
|
||||
|
||||
#define MS3DPRINT_CONFIG u"MS3DPrintConfig"
|
||||
#define MS3DPRINT_CONFIG_DATA \
|
||||
u"Base=SD\0"\
|
||||
u"Job3DOutputAreaWidth=" xstr(X_BED_SIZE) "000\0"\
|
||||
u"Job3DOutputAreaDepth=" xstr(Y_BED_SIZE) "000\0"\
|
||||
u"Job3DOutputAreaHeight=" xstr(Z_MAX_POS) "000\0"\
|
||||
u"filamentdiameter=1750\0"
|
||||
|
||||
typedef struct USB_MicrosoftExtendedPropertiesDescriptor {
|
||||
uint32_t dwLength;
|
||||
uint16_t bcdVersion;
|
||||
uint16_t wIndex;
|
||||
uint16_t bCount;
|
||||
uint32_t dwPropertySize;
|
||||
uint32_t dwPropertyDataType;
|
||||
uint16_t wPropertyNameLength;
|
||||
uint16_t PropertyName[sizeof(MS3DPRINT_CONFIG)/sizeof(uint16_t)];
|
||||
uint32_t dwPropertyDataLength;
|
||||
uint16_t PropertyData[sizeof(MS3DPRINT_CONFIG_DATA)/sizeof(uint16_t)];
|
||||
} __attribute__((packed)) USB_MicrosoftExtendedPropertiesDescriptor;
|
||||
|
||||
static USB_MicrosoftExtendedPropertiesDescriptor microsoft_extended_properties_descriptor = {
|
||||
.dwLength = sizeof(USB_MicrosoftExtendedPropertiesDescriptor),
|
||||
.bcdVersion = 0x0100,
|
||||
.wIndex = 0x0005,
|
||||
.bCount = 1,
|
||||
|
||||
.dwPropertySize = 4 + 4 + 2 + 4 + sizeof(MS3DPRINT_CONFIG) + sizeof(MS3DPRINT_CONFIG_DATA),
|
||||
.dwPropertyDataType = 7, // (1=REG_SZ, 4=REG_DWORD, 7=REG_MULTI_SZ)
|
||||
.wPropertyNameLength = sizeof(MS3DPRINT_CONFIG),
|
||||
.PropertyName = MS3DPRINT_CONFIG,
|
||||
.dwPropertyDataLength = sizeof(MS3DPRINT_CONFIG_DATA),
|
||||
.PropertyData = MS3DPRINT_CONFIG_DATA
|
||||
};
|
||||
|
||||
/**************************************************************************************************
|
||||
** WCID configuration information
|
||||
** Hooked into UDC via UDC_GET_EXTRA_STRING #define.
|
||||
*/
|
||||
bool usb_task_extra_string(void) {
|
||||
static uint8_t udi_msft_magic[] = "MSFT100\xEE";
|
||||
static uint8_t udi_cdc_name[] = "CDC interface";
|
||||
#if ENABLED(SDSUPPORT)
|
||||
static uint8_t udi_msc_name[] = "MSC interface";
|
||||
#endif
|
||||
|
||||
struct extra_strings_desc_t {
|
||||
usb_str_desc_t header;
|
||||
#if ENABLED(SDSUPPORT)
|
||||
le16_t string[Max(Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msc_name) - 1), sizeof(udi_msft_magic) - 1)];
|
||||
#else
|
||||
le16_t string[Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msft_magic) - 1)];
|
||||
#endif
|
||||
};
|
||||
static UDC_DESC_STORAGE struct extra_strings_desc_t extra_strings_desc = {
|
||||
.header.bDescriptorType = USB_DT_STRING
|
||||
};
|
||||
|
||||
uint8_t *str;
|
||||
uint8_t str_lgt = 0;
|
||||
|
||||
// Link payload pointer to the string corresponding at request
|
||||
switch (udd_g_ctrlreq.req.wValue & 0xFF) {
|
||||
case UDI_CDC_IAD_STRING_ID:
|
||||
str_lgt = sizeof(udi_cdc_name) - 1;
|
||||
str = udi_cdc_name;
|
||||
break;
|
||||
#if ENABLED(SDSUPPORT)
|
||||
case UDI_MSC_STRING_ID:
|
||||
str_lgt = sizeof(udi_msc_name) - 1;
|
||||
str = udi_msc_name;
|
||||
break;
|
||||
#endif
|
||||
case 0xEE:
|
||||
str_lgt = sizeof(udi_msft_magic) - 1;
|
||||
str = udi_msft_magic;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < str_lgt; i++)
|
||||
extra_strings_desc.string[i] = cpu_to_le16((le16_t)str[i]);
|
||||
|
||||
extra_strings_desc.header.bLength = 2 + str_lgt * 2;
|
||||
udd_g_ctrlreq.payload_size = extra_strings_desc.header.bLength;
|
||||
udd_g_ctrlreq.payload = (uint8_t*)&extra_strings_desc;
|
||||
|
||||
// if the string is larger than request length, then cut it
|
||||
if (udd_g_ctrlreq.payload_size > udd_g_ctrlreq.req.wLength) {
|
||||
udd_g_ctrlreq.payload_size = udd_g_ctrlreq.req.wLength;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/**************************************************************************************************
|
||||
** Handle device requests that the ASF stack doesn't
|
||||
*/
|
||||
bool usb_task_other_requests(void) {
|
||||
uint8_t* ptr = 0;
|
||||
uint16_t size = 0;
|
||||
|
||||
if (Udd_setup_type() == USB_REQ_TYPE_VENDOR) {
|
||||
//if (udd_g_ctrlreq.req.bRequest == 0x30)
|
||||
if (1) {
|
||||
if (udd_g_ctrlreq.req.wIndex == 0x04) {
|
||||
ptr = (uint8_t*)µsoft_compatible_id_descriptor;
|
||||
size = (udd_g_ctrlreq.req.wLength);
|
||||
if (size > microsoft_compatible_id_descriptor.dwLength)
|
||||
size = microsoft_compatible_id_descriptor.dwLength;
|
||||
}
|
||||
else if (udd_g_ctrlreq.req.wIndex == 0x05) {
|
||||
ptr = (uint8_t*)µsoft_extended_properties_descriptor;
|
||||
size = (udd_g_ctrlreq.req.wLength);
|
||||
if (size > microsoft_extended_properties_descriptor.dwLength)
|
||||
size = microsoft_extended_properties_descriptor.dwLength;
|
||||
}
|
||||
else
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
udd_g_ctrlreq.payload_size = size;
|
||||
if (size == 0) {
|
||||
udd_g_ctrlreq.callback = 0;
|
||||
udd_g_ctrlreq.over_under_run = 0;
|
||||
}
|
||||
else
|
||||
udd_g_ctrlreq.payload = ptr;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void usb_task_init(void) {
|
||||
|
||||
uint16_t *ptr;
|
||||
|
||||
// Disable USB peripheral so we start clean and avoid lockups
|
||||
otg_disable();
|
||||
udd_disable();
|
||||
|
||||
// Set the USB interrupt to our stack
|
||||
UDD_SetStack(&USBD_ISR);
|
||||
|
||||
// Start USB stack to authorize VBus monitoring
|
||||
udc_start();
|
||||
|
||||
// Patch in filament diameter - Be careful: String is in UNICODE (2bytes per char)
|
||||
ptr = µsoft_extended_properties_descriptor.PropertyData[0];
|
||||
while (ptr[0] || ptr[1]) { // Double 0 flags end of resource
|
||||
|
||||
// Found the filamentdiameter= unicode string
|
||||
if (ptr[0] == 'r' && ptr[1] == '=') {
|
||||
char diam[16];
|
||||
char *sptr;
|
||||
|
||||
// Patch in the filament diameter
|
||||
sprintf_P(diam, PSTR("%d"), (int)((DEFAULT_NOMINAL_FILAMENT_DIA) * 1000.0));
|
||||
|
||||
// And copy it to the proper place, expanding it to unicode
|
||||
sptr = &diam[0];
|
||||
ptr += 2;
|
||||
while (*sptr) *ptr++ = *sptr++;
|
||||
|
||||
// Done!
|
||||
break;
|
||||
}
|
||||
|
||||
// Go to the next character
|
||||
ptr++;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
134
Marlin/src/HAL/DUE/usb/usb_task.h
Normal file
134
Marlin/src/HAL/DUE/usb/usb_task.h
Normal file
@ -0,0 +1,134 @@
|
||||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Declaration of main function used by Composite example 4
|
||||
*
|
||||
* Copyright (c) 2011-2015 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
|
||||
*/
|
||||
|
||||
#ifndef _USB_TASK_H_
|
||||
#define _USB_TASK_H_
|
||||
|
||||
#include "usb_protocol_cdc.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/*! \brief Called by MSC interface
|
||||
* Callback running when USB Host enable MSC interface
|
||||
*
|
||||
* \retval true if MSC startup is ok
|
||||
*/
|
||||
bool usb_task_msc_enable(void);
|
||||
|
||||
/*! \brief Called by MSC interface
|
||||
* Callback running when USB Host disable MSC interface
|
||||
*/
|
||||
void usb_task_msc_disable(void);
|
||||
|
||||
/*! \brief Opens the communication port
|
||||
* This is called by CDC interface when USB Host enable it.
|
||||
*
|
||||
* \retval true if cdc startup is successfully done
|
||||
*/
|
||||
bool usb_task_cdc_enable(const uint8_t port);
|
||||
|
||||
/*! \brief Closes the communication port
|
||||
* This is called by CDC interface when USB Host disable it.
|
||||
*/
|
||||
void usb_task_cdc_disable(const uint8_t port);
|
||||
|
||||
/*! \brief Save new DTR state to change led behavior.
|
||||
* The DTR notify that the terminal have open or close the communication port.
|
||||
*/
|
||||
void usb_task_cdc_set_dtr(const uint8_t port, const bool b_enable);
|
||||
|
||||
/*! \brief Check if MSC is enumerated and configured on the PC side
|
||||
*/
|
||||
bool usb_task_msc_isenabled(void);
|
||||
|
||||
/*! \brief Check if CDC is enumerated and configured on the PC side
|
||||
*/
|
||||
bool usb_task_cdc_isenabled(void);
|
||||
|
||||
/*! \brief Check if CDC is actually OPEN by an application on the PC side
|
||||
* assuming DTR signal means a program is listening to messages
|
||||
*/
|
||||
bool usb_task_cdc_dtr_active(void);
|
||||
|
||||
/*! \brief Called by UDC when USB Host request a extra string different
|
||||
* of this specified in USB device descriptor
|
||||
*/
|
||||
bool usb_task_extra_string(void);
|
||||
|
||||
/*! \brief Called by UDC when USB Host performs unknown requests
|
||||
*/
|
||||
bool usb_task_other_requests(void);
|
||||
|
||||
/*! \brief Called by CDC interface
|
||||
* Callback running when CDC device have received data
|
||||
*/
|
||||
void usb_task_cdc_rx_notify(const uint8_t port);
|
||||
|
||||
/*! \brief Configures communication line
|
||||
*
|
||||
* \param cfg line configuration
|
||||
*/
|
||||
void usb_task_cdc_config(const uint8_t port, usb_cdc_line_coding_t *cfg);
|
||||
|
||||
/*! \brief The USB device interrupt
|
||||
*/
|
||||
void USBD_ISR(void);
|
||||
|
||||
/*! \brief USB task init
|
||||
*/
|
||||
void usb_task_init(void);
|
||||
|
||||
/*! \brief USB task idle
|
||||
*/
|
||||
void usb_task_idle(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // _USB_TASK_H_
|
115
Marlin/src/HAL/DUE/watchdog.cpp
Normal file
115
Marlin/src/HAL/DUE/watchdog.cpp
Normal file
@ -0,0 +1,115 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../../MarlinCore.h"
|
||||
#include "watchdog.h"
|
||||
|
||||
// Override Arduino runtime to either config or disable the watchdog
|
||||
//
|
||||
// We need to configure the watchdog as soon as possible in the boot
|
||||
// process, because watchdog initialization at hardware reset on SAM3X8E
|
||||
// is unreliable, and there is risk of unintended resets if we delay
|
||||
// that initialization to a later time.
|
||||
void watchdogSetup() {
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
// 4 seconds timeout
|
||||
uint32_t timeout = 4000;
|
||||
|
||||
// Calculate timeout value in WDT counter ticks: This assumes
|
||||
// the slow clock is running at 32.768 kHz watchdog
|
||||
// frequency is therefore 32768 / 128 = 256 Hz
|
||||
timeout = (timeout << 8) / 1000;
|
||||
if (timeout == 0)
|
||||
timeout = 1;
|
||||
else if (timeout > 0xFFF)
|
||||
timeout = 0xFFF;
|
||||
|
||||
// We want to enable the watchdog with the specified timeout
|
||||
uint32_t value =
|
||||
WDT_MR_WDV(timeout) | // With the specified timeout
|
||||
WDT_MR_WDD(timeout) | // and no invalid write window
|
||||
#if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
|
||||
WDT_MR_WDRPROC | // WDT fault resets processor only - We want
|
||||
// to keep PIO controller state
|
||||
#endif
|
||||
WDT_MR_WDDBGHLT | // WDT stops in debug state.
|
||||
WDT_MR_WDIDLEHLT; // WDT stops in idle state.
|
||||
|
||||
#if ENABLED(WATCHDOG_RESET_MANUAL)
|
||||
// We enable the watchdog timer, but only for the interrupt.
|
||||
|
||||
// Configure WDT to only trigger an interrupt
|
||||
value |= WDT_MR_WDFIEN; // Enable WDT fault 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();
|
||||
|
||||
// Initialize WDT with the given parameters
|
||||
WDT_Enable(WDT, value);
|
||||
|
||||
// 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
|
||||
|
||||
// a WDT fault triggers a reset
|
||||
value |= WDT_MR_WDRSTEN;
|
||||
|
||||
// Initialize WDT with the given parameters
|
||||
WDT_Enable(WDT, value);
|
||||
|
||||
#endif
|
||||
|
||||
// Reset the watchdog
|
||||
WDT_Restart(WDT);
|
||||
|
||||
#else
|
||||
|
||||
// Make sure to completely disable the Watchdog
|
||||
WDT_Disable(WDT);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
// Initialize watchdog - On SAM3X, Watchdog was already configured
|
||||
// and enabled or disabled at startup, so no need to reconfigure it
|
||||
// here.
|
||||
void watchdog_init() {
|
||||
// Reset watchdog to start clean
|
||||
WDT_Restart(WDT);
|
||||
}
|
||||
#endif // USE_WATCHDOG
|
||||
|
||||
#endif
|
33
Marlin/src/HAL/DUE/watchdog.h
Normal file
33
Marlin/src/HAL/DUE/watchdog.h
Normal file
@ -0,0 +1,33 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// Arduino Due core now has watchdog support
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
// Initialize watchdog with a 4 second interrupt time
|
||||
void watchdog_init();
|
||||
|
||||
// Reset watchdog. MUST be called at least every 4 seconds after the
|
||||
// first watchdog_init or AVR will go into emergency procedures.
|
||||
inline void HAL_watchdog_refresh() { watchdogReset(); }
|
Reference in New Issue
Block a user