Drop C-style 'void' argument

This commit is contained in:
Scott Lahteine 2019-09-16 20:31:08 -05:00
parent 7d8c38693f
commit f01f0d1956
174 changed files with 864 additions and 864 deletions

View File

@ -35,7 +35,7 @@
// Public functions // Public functions
// ------------------------ // ------------------------
void HAL_init(void) { void HAL_init() {
// Init Servo Pins // Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0 #if HAS_SERVO_0

View File

@ -105,19 +105,19 @@ typedef int8_t pin_t;
// Public functions // Public functions
// ------------------------ // ------------------------
void HAL_init(void); void HAL_init();
//void cli(void); //void cli();
//void _delay_ms(const int delay); //void _delay_ms(const int delay);
inline void HAL_clear_reset_source(void) { MCUSR = 0; } inline void HAL_clear_reset_source() { MCUSR = 0; }
inline uint8_t HAL_get_reset_source(void) { return MCUSR; } inline uint8_t HAL_get_reset_source() { return MCUSR; }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
extern "C" { extern "C" {
int freeMemory(void); int freeMemory();
} }
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
@ -199,9 +199,9 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t freque
/* 18 cycles maximum latency */ /* 18 cycles maximum latency */
#define HAL_STEP_TIMER_ISR() \ #define HAL_STEP_TIMER_ISR() \
extern "C" void TIMER1_COMPA_vect(void) __attribute__ ((signal, naked, used, externally_visible)); \ extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER1_COMPA_vect_bottom(void) asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \ extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER1_COMPA_vect(void) { \ void TIMER1_COMPA_vect() { \
__asm__ __volatile__ ( \ __asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \ A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \ A("in r16, __SREG__") /* 1 Get SREG */ \
@ -268,13 +268,13 @@ void TIMER1_COMPA_vect(void) { \
: \ : \
); \ ); \
} \ } \
void TIMER1_COMPA_vect_bottom(void) void TIMER1_COMPA_vect_bottom()
/* 14 cycles maximum latency */ /* 14 cycles maximum latency */
#define HAL_TEMP_TIMER_ISR() \ #define HAL_TEMP_TIMER_ISR() \
extern "C" void TIMER0_COMPB_vect(void) __attribute__ ((signal, naked, used, externally_visible)); \ extern "C" void TIMER0_COMPB_vect() __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER0_COMPB_vect_bottom(void) asm ("TIMER0_COMPB_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \ extern "C" void TIMER0_COMPB_vect_bottom() asm ("TIMER0_COMPB_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER0_COMPB_vect(void) { \ void TIMER0_COMPB_vect() { \
__asm__ __volatile__ ( \ __asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \ A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \ A("in r16, __SREG__") /* 1 Get SREG */ \
@ -334,7 +334,7 @@ void TIMER0_COMPB_vect(void) { \
: \ : \
); \ ); \
} \ } \
void TIMER0_COMPB_vect_bottom(void) void TIMER0_COMPB_vect_bottom()
// ADC // ADC
#ifdef DIDR2 #ifdef DIDR2
@ -343,7 +343,7 @@ void TIMER0_COMPB_vect_bottom(void)
#define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0) #define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
#endif #endif
inline void HAL_adc_init(void) { inline void HAL_adc_init() {
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0; DIDR0 = 0;
#ifdef DIDR2 #ifdef DIDR2

View File

@ -33,7 +33,7 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
void spiBegin(void) { void spiBegin() {
OUT_WRITE(SS_PIN, HIGH); OUT_WRITE(SS_PIN, HIGH);
SET_OUTPUT(SCK_PIN); SET_OUTPUT(SCK_PIN);
SET_INPUT(MISO_PIN); SET_INPUT(MISO_PIN);
@ -81,7 +81,7 @@ void spiBegin(void) {
} }
/** SPI receive a byte */ /** SPI receive a byte */
uint8_t spiRec(void) { uint8_t spiRec() {
SPDR = 0xFF; SPDR = 0xFF;
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
return SPDR; return SPDR;

View File

@ -271,7 +271,7 @@
// (called with TX irqs disabled) // (called with TX irqs disabled)
template<typename Cfg> template<typename Cfg>
FORCE_INLINE void MarlinSerial<Cfg>::_tx_udr_empty_irq(void) { FORCE_INLINE void MarlinSerial<Cfg>::_tx_udr_empty_irq() {
if (Cfg::TX_SIZE > 0) { if (Cfg::TX_SIZE > 0) {
// Read positions // Read positions
uint8_t t = tx_buffer.tail; uint8_t t = tx_buffer.tail;
@ -363,13 +363,13 @@
} }
template<typename Cfg> template<typename Cfg>
int MarlinSerial<Cfg>::peek(void) { int MarlinSerial<Cfg>::peek() {
const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
return h == t ? -1 : rx_buffer.buffer[t]; return h == t ? -1 : rx_buffer.buffer[t];
} }
template<typename Cfg> template<typename Cfg>
int MarlinSerial<Cfg>::read(void) { int MarlinSerial<Cfg>::read() {
const ring_buffer_pos_t h = atomic_read_rx_head(); const ring_buffer_pos_t h = atomic_read_rx_head();
// Read the tail. Main thread owns it, so it is safe to directly read it // Read the tail. Main thread owns it, so it is safe to directly read it
@ -412,13 +412,13 @@
} }
template<typename Cfg> template<typename Cfg>
typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::available(void) { typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::available() {
const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1); return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1);
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::flush(void) { void MarlinSerial<Cfg>::flush() {
// Set the tail to the head: // Set the tail to the head:
// - Read the RX head index in a safe way. (See atomic_read_rx_head.) // - Read the RX head index in a safe way. (See atomic_read_rx_head.)
@ -505,7 +505,7 @@
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::flushTX(void) { void MarlinSerial<Cfg>::flushTX() {
if (Cfg::TX_SIZE == 0) { if (Cfg::TX_SIZE == 0) {
// No bytes written, no need to flush. This special case is needed since there's // No bytes written, no need to flush. This special case is needed since there's
@ -595,7 +595,7 @@
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::println(void) { void MarlinSerial<Cfg>::println() {
print('\r'); print('\r');
print('\n'); print('\n');
} }

View File

@ -205,18 +205,18 @@
public: public:
FORCE_INLINE static void store_rxd_char(); FORCE_INLINE static void store_rxd_char();
FORCE_INLINE static void _tx_udr_empty_irq(void); FORCE_INLINE static void _tx_udr_empty_irq();
public: public:
MarlinSerial() {}; MarlinSerial() {};
static void begin(const long); static void begin(const long);
static void end(); static void end();
static int peek(void); static int peek();
static int read(void); static int read();
static void flush(void); static void flush();
static ring_buffer_pos_t available(void); static ring_buffer_pos_t available();
static void write(const uint8_t c); static void write(const uint8_t c);
static void flushTX(void); static void flushTX();
FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } 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 buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
@ -245,7 +245,7 @@
static void println(long, int = DEC); static void println(long, int = DEC);
static void println(unsigned long, int = DEC); static void println(unsigned long, int = DEC);
static void println(double, int = 2); static void println(double, int = 2);
static void println(void); static void println();
operator bool() { return true; } operator bool() { return true; }
private: private:

View File

@ -41,7 +41,7 @@
#include <stdint.h> #include <stdint.h>
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
/** /**
* Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h) * Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h)
@ -102,7 +102,7 @@ void pciSetup(const int8_t pin) {
ISR(PCINT3_vect, ISR_ALIASOF(PCINT0_vect)); ISR(PCINT3_vect, ISR_ALIASOF(PCINT0_vect));
#endif #endif
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#if HAS_X_MAX #if HAS_X_MAX
#if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) #if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT)

View File

@ -42,7 +42,7 @@
#define sw_barrier() __asm__ volatile("": : :"memory"); #define sw_barrier() __asm__ volatile("": : :"memory");
// (re)initialize UART0 as a monitor output to 250000,n,8,1 // (re)initialize UART0 as a monitor output to 250000,n,8,1
static void TXBegin(void) { static void TXBegin() {
// Disable UART interrupt in NVIC // Disable UART interrupt in NVIC
NVIC_DisableIRQ( UART_IRQn ); NVIC_DisableIRQ( UART_IRQn );
@ -235,7 +235,7 @@ void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause
for (;;) WDT_Restart(WDT); for (;;) WDT_Restart(WDT);
} }
__attribute__((naked)) void NMI_Handler(void) { __attribute__((naked)) void NMI_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -248,7 +248,7 @@ __attribute__((naked)) void NMI_Handler(void) {
); );
} }
__attribute__((naked)) void HardFault_Handler(void) { __attribute__((naked)) void HardFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -261,7 +261,7 @@ __attribute__((naked)) void HardFault_Handler(void) {
); );
} }
__attribute__((naked)) void MemManage_Handler(void) { __attribute__((naked)) void MemManage_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -274,7 +274,7 @@ __attribute__((naked)) void MemManage_Handler(void) {
); );
} }
__attribute__((naked)) void BusFault_Handler(void) { __attribute__((naked)) void BusFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -287,7 +287,7 @@ __attribute__((naked)) void BusFault_Handler(void) {
); );
} }
__attribute__((naked)) void UsageFault_Handler(void) { __attribute__((naked)) void UsageFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -300,7 +300,7 @@ __attribute__((naked)) void UsageFault_Handler(void) {
); );
} }
__attribute__((naked)) void DebugMon_Handler(void) { __attribute__((naked)) void DebugMon_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -314,7 +314,7 @@ __attribute__((naked)) void DebugMon_Handler(void) {
} }
/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */ /* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
__attribute__((naked)) void WDT_Handler(void) { __attribute__((naked)) void WDT_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -327,7 +327,7 @@ __attribute__((naked)) void WDT_Handler(void) {
); );
} }
__attribute__((naked)) void RSTC_Handler(void) { __attribute__((naked)) void RSTC_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")

View File

@ -993,7 +993,7 @@ void eeprom_read_block(void* __dst, const void* __src, size_t __n) {
} }
} }
void eeprom_flush(void) { void eeprom_flush() {
ee_Flush(); ee_Flush();
} }

View File

@ -42,7 +42,7 @@ uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// HAL initialization task // HAL initialization task
void HAL_init(void) { void HAL_init() {
// Initialize the USB stack // Initialize the USB stack
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
@ -51,20 +51,20 @@ void HAL_init(void) {
} }
// HAL idle task // HAL idle task
void HAL_idletask(void) { void HAL_idletask() {
// Perform USB stack housekeeping // Perform USB stack housekeeping
usb_task_idle(); usb_task_idle();
} }
// Disable interrupts // Disable interrupts
void cli(void) { noInterrupts(); } void cli() { noInterrupts(); }
// Enable interrupts // Enable interrupts
void sei(void) { interrupts(); } void sei() { interrupts(); }
void HAL_clear_reset_source(void) { } void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
switch ((RSTC->RSTC_SR >> 8) & 0x07) { switch ((RSTC->RSTC_SR >> 8) & 0x07) {
case 0: return RST_POWER_ON; case 0: return RST_POWER_ON;
case 1: return RST_BACKUP; case 1: return RST_BACKUP;
@ -98,7 +98,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = analogRead(adc_pin); HAL_adc_result = analogRead(adc_pin);
} }
uint16_t HAL_adc_get_result(void) { uint16_t HAL_adc_get_result() {
// nop // nop
return HAL_adc_result; return HAL_adc_result;
} }

View File

@ -88,11 +88,11 @@ typedef int8_t pin_t;
#define ENABLE_ISRS() __enable_irq() #define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq() #define DISABLE_ISRS() __disable_irq()
void cli(void); // Disable interrupts void cli(); // Disable interrupts
void sei(void); // Enable interrupts void sei(); // Enable interrupts
void HAL_clear_reset_source(void); // clear reset reason void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(void); // get reset reason uint8_t HAL_get_reset_source(); // get reset reason
// //
// EEPROM // EEPROM
@ -113,14 +113,14 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion
#define HAL_ANALOG_SELECT(pin) #define HAL_ANALOG_SELECT(pin)
inline void HAL_adc_init(void) {}//todo inline void HAL_adc_init() {}//todo
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true #define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
// //
// Pin Map // Pin Map
@ -138,8 +138,8 @@ void noTone(const pin_t _pin);
// Enable hooks into idle and setup for HAL // Enable hooks into idle and setup for HAL
#define HAL_IDLETASK 1 #define HAL_IDLETASK 1
void HAL_idletask(void); void HAL_idletask();
void HAL_init(void); void HAL_init();
// //
// Utility functions // Utility functions
@ -148,7 +148,7 @@ void _delay_ms(const int delay);
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory(void); int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
#ifdef __cplusplus #ifdef __cplusplus

View File

@ -48,7 +48,7 @@ static DeviceVectors ram_tab = { nullptr };
* If it is not, then it copies the ROM table to the SRAM and relocates the table * If it is not, then it copies the ROM table to the SRAM and relocates the table
* by reprogramming the NVIC registers * by reprogramming the NVIC registers
*/ */
static pfnISR_Handler* get_relocated_table_addr(void) { static pfnISR_Handler* get_relocated_table_addr() {
// Get the address of the interrupt/exception table // Get the address of the interrupt/exception table
uint32_t isrtab = SCB->VTOR; uint32_t isrtab = SCB->VTOR;

View File

@ -37,7 +37,7 @@
#ifdef ARDUINO_ARCH_SAM #ifdef ARDUINO_ARCH_SAM
// ISR handler type // ISR handler type
typedef void (*pfnISR_Handler)(void); typedef void (*pfnISR_Handler)();
// Install a new interrupt vector handler for the given irq, returning the old one // Install a new interrupt vector handler for the given irq, returning the old one
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler); pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler);

View File

@ -178,7 +178,7 @@ FORCE_INLINE void MarlinSerial<Cfg>::store_rxd_char() {
} }
template<typename Cfg> template<typename Cfg>
FORCE_INLINE void MarlinSerial<Cfg>::_tx_thr_empty_irq(void) { FORCE_INLINE void MarlinSerial<Cfg>::_tx_thr_empty_irq() {
if (Cfg::TX_SIZE > 0) { if (Cfg::TX_SIZE > 0) {
// Read positions // Read positions
uint8_t t = tx_buffer.tail; uint8_t t = tx_buffer.tail;
@ -221,7 +221,7 @@ FORCE_INLINE void MarlinSerial<Cfg>::_tx_thr_empty_irq(void) {
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::UART_ISR(void) { void MarlinSerial<Cfg>::UART_ISR() {
const uint32_t status = HWUART->UART_SR; const uint32_t status = HWUART->UART_SR;
// Data received? // Data received?
@ -308,13 +308,13 @@ void MarlinSerial<Cfg>::end() {
} }
template<typename Cfg> template<typename Cfg>
int MarlinSerial<Cfg>::peek(void) { int MarlinSerial<Cfg>::peek() {
const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail]; const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
return v; return v;
} }
template<typename Cfg> template<typename Cfg>
int MarlinSerial<Cfg>::read(void) { int MarlinSerial<Cfg>::read() {
const ring_buffer_pos_t h = rx_buffer.head; const ring_buffer_pos_t h = rx_buffer.head;
ring_buffer_pos_t t = rx_buffer.tail; ring_buffer_pos_t t = rx_buffer.tail;
@ -354,13 +354,13 @@ int MarlinSerial<Cfg>::read(void) {
} }
template<typename Cfg> template<typename Cfg>
typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::available(void) { typename MarlinSerial<Cfg>::ring_buffer_pos_t MarlinSerial<Cfg>::available() {
const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail; 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); return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1);
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::flush(void) { void MarlinSerial<Cfg>::flush() {
rx_buffer.tail = rx_buffer.head; rx_buffer.tail = rx_buffer.head;
if (Cfg::XONOFF) { if (Cfg::XONOFF) {
@ -431,7 +431,7 @@ void MarlinSerial<Cfg>::write(const uint8_t c) {
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::flushTX(void) { void MarlinSerial<Cfg>::flushTX() {
// TX // TX
if (Cfg::TX_SIZE == 0) { if (Cfg::TX_SIZE == 0) {
@ -520,7 +520,7 @@ void MarlinSerial<Cfg>::print(double n, int digits) {
} }
template<typename Cfg> template<typename Cfg>
void MarlinSerial<Cfg>::println(void) { void MarlinSerial<Cfg>::println() {
print('\r'); print('\r');
print('\n'); print('\n');
} }

View File

@ -108,19 +108,19 @@ protected:
static ring_buffer_pos_t rx_max_enqueued; static ring_buffer_pos_t rx_max_enqueued;
FORCE_INLINE static void store_rxd_char(); FORCE_INLINE static void store_rxd_char();
FORCE_INLINE static void _tx_thr_empty_irq(void); FORCE_INLINE static void _tx_thr_empty_irq();
static void UART_ISR(void); static void UART_ISR();
public: public:
MarlinSerial() {}; MarlinSerial() {};
static void begin(const long); static void begin(const long);
static void end(); static void end();
static int peek(void); static int peek();
static int read(void); static int read();
static void flush(void); static void flush();
static ring_buffer_pos_t available(void); static ring_buffer_pos_t available();
static void write(const uint8_t c); static void write(const uint8_t c);
static void flushTX(void); static void flushTX();
FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } 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 buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
@ -149,7 +149,7 @@ public:
static void println(long, int = DEC); static void println(long, int = DEC);
static void println(unsigned long, int = DEC); static void println(unsigned long, int = DEC);
static void println(double, int = 2); static void println(double, int = 2);
static void println(void); static void println();
operator bool() { return true; } operator bool() { return true; }
private: private:

View File

@ -39,11 +39,11 @@
// Imports from Atmel USB Stack/CDC implementation // Imports from Atmel USB Stack/CDC implementation
extern "C" { extern "C" {
bool usb_task_cdc_isenabled(void); bool usb_task_cdc_isenabled();
bool usb_task_cdc_dtr_active(void); bool usb_task_cdc_dtr_active();
bool udi_cdc_is_rx_ready(void); bool udi_cdc_is_rx_ready();
int udi_cdc_getc(void); int udi_cdc_getc();
bool udi_cdc_is_tx_ready(void); bool udi_cdc_is_tx_ready();
int udi_cdc_putc(int value); int udi_cdc_putc(int value);
}; };
@ -62,7 +62,7 @@ void MarlinSerialUSB::begin(const long baud_setting) {
void MarlinSerialUSB::end() { void MarlinSerialUSB::end() {
} }
int MarlinSerialUSB::peek(void) { int MarlinSerialUSB::peek() {
if (pending_char >= 0) if (pending_char >= 0)
return pending_char; return pending_char;
@ -83,7 +83,7 @@ int MarlinSerialUSB::peek(void) {
return pending_char; return pending_char;
} }
int MarlinSerialUSB::read(void) { int MarlinSerialUSB::read() {
if (pending_char >= 0) { if (pending_char >= 0) {
int ret = pending_char; int ret = pending_char;
pending_char = -1; pending_char = -1;
@ -107,7 +107,7 @@ int MarlinSerialUSB::read(void) {
return c; return c;
} }
bool MarlinSerialUSB::available(void) { bool MarlinSerialUSB::available() {
/* If Pending chars */ /* If Pending chars */
return pending_char >= 0 || return pending_char >= 0 ||
/* or USB CDC enumerated and configured on the PC side and some /* or USB CDC enumerated and configured on the PC side and some
@ -115,8 +115,8 @@ bool MarlinSerialUSB::available(void) {
(usb_task_cdc_isenabled() && udi_cdc_is_rx_ready()); (usb_task_cdc_isenabled() && udi_cdc_is_rx_ready());
} }
void MarlinSerialUSB::flush(void) { } void MarlinSerialUSB::flush() { }
void MarlinSerialUSB::flushTX(void) { } void MarlinSerialUSB::flushTX() { }
void MarlinSerialUSB::write(const uint8_t c) { void MarlinSerialUSB::write(const uint8_t c) {
@ -186,7 +186,7 @@ void MarlinSerialUSB::print(double n, int digits) {
printFloat(n, digits); printFloat(n, digits);
} }
void MarlinSerialUSB::println(void) { void MarlinSerialUSB::println() {
print('\r'); print('\r');
print('\n'); print('\n');
} }

View File

@ -43,11 +43,11 @@ public:
MarlinSerialUSB() {}; MarlinSerialUSB() {};
static void begin(const long); static void begin(const long);
static void end(); static void end();
static int peek(void); static int peek();
static int read(void); static int read();
static void flush(void); static void flush();
static void flushTX(void); static void flushTX();
static bool available(void); static bool available();
static void write(const uint8_t c); static void write(const uint8_t c);
#if ENABLED(SERIAL_STATS_DROPPED_RX) #if ENABLED(SERIAL_STATS_DROPPED_RX)
@ -80,7 +80,7 @@ public:
static void println(long, int = DEC); static void println(long, int = DEC);
static void println(unsigned long, int = DEC); static void println(unsigned long, int = DEC);
static void println(double, int = 2); static void println(double, int = 2);
static void println(void); static void println();
operator bool() { return true; } operator bool() { return true; }
private: private:

View File

@ -56,19 +56,19 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the s
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel); void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
#ifdef _useTimer1 #ifdef _useTimer1
void HANDLER_FOR_TIMER1(void) { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); } void HANDLER_FOR_TIMER1() { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); }
#endif #endif
#ifdef _useTimer2 #ifdef _useTimer2
void HANDLER_FOR_TIMER2(void) { Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); } void HANDLER_FOR_TIMER2() { Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); }
#endif #endif
#ifdef _useTimer3 #ifdef _useTimer3
void HANDLER_FOR_TIMER3(void) { Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); } void HANDLER_FOR_TIMER3() { Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); }
#endif #endif
#ifdef _useTimer4 #ifdef _useTimer4
void HANDLER_FOR_TIMER4(void) { Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); } void HANDLER_FOR_TIMER4() { Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); }
#endif #endif
#ifdef _useTimer5 #ifdef _useTimer5
void HANDLER_FOR_TIMER5(void) { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); } void HANDLER_FOR_TIMER5() { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); }
#endif #endif
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) { void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {

View File

@ -38,14 +38,14 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
/** /**
* Endstop interrupts for Due based targets. * Endstop interrupts for Due based targets.
* On Due, all pins support external interrupt capability. * On Due, all pins support external interrupt capability.
*/ */
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#if HAS_X_MAX #if HAS_X_MAX
_ATTACH(X_MAX_PIN); _ATTACH(X_MAX_PIN);

View File

@ -33,7 +33,7 @@
#define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp)
#endif #endif
extern void eeprom_flush(void); extern void eeprom_flush();
bool PersistentStore::access_start() { return true; } bool PersistentStore::access_start() { return true; }

View File

@ -216,7 +216,7 @@
} }
# endif # endif
#else #else
# define Assert(expr) ((void) 0) # define Assert(expr) (() 0)
#endif #endif
/* Define WEAK attribute */ /* Define WEAK attribute */
@ -796,7 +796,7 @@ typedef struct
* *
* \note It may be used as a long jump opcode in some special cases. * \note It may be used as a long jump opcode in some special cases.
*/ */
#define Long_call(addr) ((*(void (*)(void))(addr))()) #define Long_call(addr) ((*(void (*)())(addr))())
/*! \name MCU Endianism Handling /*! \name MCU Endianism Handling

View File

@ -174,11 +174,11 @@ static xSemaphoreHandle ctrl_access_semphr = NULL;
//! LUN descriptor table. //! LUN descriptor table.
static const struct static const struct
{ {
Ctrl_status (*test_unit_ready)(void); Ctrl_status (*test_unit_ready)();
Ctrl_status (*read_capacity)(U32 *); Ctrl_status (*read_capacity)(U32 *);
bool (*unload)(bool); bool (*unload)(bool);
bool (*wr_protect)(void); bool (*wr_protect)();
bool (*removal)(void); bool (*removal)();
#if ACCESS_USB == true #if ACCESS_USB == true
Ctrl_status (*usb_read_10)(U32, U16); Ctrl_status (*usb_read_10)(U32, U16);
Ctrl_status (*usb_write_10)(U32, U16); Ctrl_status (*usb_write_10)(U32, U16);
@ -255,7 +255,7 @@ bool g_wr_protect;
#ifdef FREERTOS_USED #ifdef FREERTOS_USED
bool ctrl_access_init(void) bool ctrl_access_init()
{ {
// If the handle to the protecting semaphore is not valid, // If the handle to the protecting semaphore is not valid,
if (!ctrl_access_semphr) if (!ctrl_access_semphr)
@ -275,7 +275,7 @@ bool ctrl_access_init(void)
* *
* \return \c true if the access was successfully locked, else \c false. * \return \c true if the access was successfully locked, else \c false.
*/ */
static bool ctrl_access_lock(void) static bool ctrl_access_lock()
{ {
// If the semaphore could not be created, there is no backup solution. // If the semaphore could not be created, there is no backup solution.
if (!ctrl_access_semphr) return false; if (!ctrl_access_semphr) return false;
@ -289,7 +289,7 @@ static bool ctrl_access_lock(void)
#endif // FREERTOS_USED #endif // FREERTOS_USED
U8 get_nb_lun(void) U8 get_nb_lun()
{ {
#if MEM_USB == ENABLE #if MEM_USB == ENABLE
# ifndef Lun_usb_get_lun # ifndef Lun_usb_get_lun
@ -310,7 +310,7 @@ U8 get_nb_lun(void)
} }
U8 get_cur_lun(void) U8 get_cur_lun()
{ {
return LUN_ID_0; return LUN_ID_0;
} }

View File

@ -191,7 +191,7 @@ extern bool g_wr_protect;
* *
* \return \c true if the locker was successfully initialized, else \c false. * \return \c true if the locker was successfully initialized, else \c false.
*/ */
extern bool ctrl_access_init(void); extern bool ctrl_access_init();
#endif // FREERTOS_USED #endif // FREERTOS_USED
@ -199,7 +199,7 @@ extern bool ctrl_access_init(void);
* *
* \return Number of LUNs in the system. * \return Number of LUNs in the system.
*/ */
extern U8 get_nb_lun(void); extern U8 get_nb_lun();
/*! \brief Returns the current LUN. /*! \brief Returns the current LUN.
* *
@ -207,7 +207,7 @@ extern U8 get_nb_lun(void);
* *
* \todo Implement. * \todo Implement.
*/ */
extern U8 get_cur_lun(void); extern U8 get_cur_lun();
/*! \brief Tests the memory state and initializes the memory if required. /*! \brief Tests the memory state and initializes the memory if required.
* *

View File

@ -15,10 +15,10 @@ extern "C" {
#define SD_MMC_BLOCK_SIZE 512 #define SD_MMC_BLOCK_SIZE 512
void sd_mmc_spi_mem_init(void) { void sd_mmc_spi_mem_init() {
} }
Ctrl_status sd_mmc_spi_test_unit_ready(void) { Ctrl_status sd_mmc_spi_test_unit_ready() {
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
return CTRL_NO_PRESENT; return CTRL_NO_PRESENT;
return CTRL_GOOD; return CTRL_GOOD;
@ -38,11 +38,11 @@ bool sd_mmc_spi_unload(bool unload) {
return true; return true;
} }
bool sd_mmc_spi_wr_protect(void) { bool sd_mmc_spi_wr_protect() {
return false; return false;
} }
bool sd_mmc_spi_removal(void) { bool sd_mmc_spi_removal() {
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
return true; return true;
return false; return false;

View File

@ -78,7 +78,7 @@
//! //!
//! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI.
//!/ //!/
extern void sd_mmc_spi_mem_init(void); extern void sd_mmc_spi_mem_init();
//! //!
//! @brief This function tests the state of the SD_MMC memory and sends it to the Host. //! @brief This function tests the state of the SD_MMC memory and sends it to the Host.
@ -91,7 +91,7 @@ extern void sd_mmc_spi_mem_init(void);
//! Media not present -> CTRL_NO_PRESENT //! Media not present -> CTRL_NO_PRESENT
//! Media has changed -> CTRL_BUSY //! Media has changed -> CTRL_BUSY
//!/ //!/
extern Ctrl_status sd_mmc_spi_test_unit_ready(void); extern Ctrl_status sd_mmc_spi_test_unit_ready();
//! //!
//! @brief This function gives the address of the last valid sector. //! @brief This function gives the address of the last valid sector.
@ -124,14 +124,14 @@ extern bool sd_mmc_spi_unload(bool unload);
//! //!
//! @return false -> the memory is not write-protected (always) //! @return false -> the memory is not write-protected (always)
//!/ //!/
extern bool sd_mmc_spi_wr_protect(void); extern bool sd_mmc_spi_wr_protect();
//! //!
//! @brief This function tells if the memory has been removed or not. //! @brief This function tells if the memory has been removed or not.
//! //!
//! @return false -> The memory isn't removed //! @return false -> The memory isn't removed
//! //!
extern bool sd_mmc_spi_removal(void); extern bool sd_mmc_spi_removal();
//---- ACCESS DATA FONCTIONS ---- //---- ACCESS DATA FONCTIONS ----

View File

@ -71,7 +71,7 @@ extern "C" {
* \param pll_id Source of the USB clock. * \param pll_id Source of the USB clock.
* \param div Actual clock divisor. Must be superior to 0. * \param div Actual clock divisor. Must be superior to 0.
*/ */
void sysclk_enable_usb(void) void sysclk_enable_usb()
{ {
Assert(CONFIG_USBCLK_DIV > 0); Assert(CONFIG_USBCLK_DIV > 0);
@ -103,7 +103,7 @@ void sysclk_enable_usb(void)
* *
* \note This implementation does not switch off the PLL, it just turns off the USB clock. * \note This implementation does not switch off the PLL, it just turns off the USB clock.
*/ */
void sysclk_disable_usb(void) void sysclk_disable_usb()
{ {
pmc_disable_udpck(); pmc_disable_udpck();
} }

View File

@ -213,8 +213,8 @@ extern "C" {
#endif #endif
extern void sysclk_enable_usb(void); extern void sysclk_enable_usb();
extern void sysclk_disable_usb(void); extern void sysclk_disable_usb();
//! @} //! @}

View File

@ -132,14 +132,14 @@ static uint8_t udc_string_product_name[] = USB_DEVICE_PRODUCT_NAME;
* define USB_DEVICE_GET_SERIAL_NAME_LENGTH. * define USB_DEVICE_GET_SERIAL_NAME_LENGTH.
*/ */
#if defined USB_DEVICE_GET_SERIAL_NAME_POINTER #if defined USB_DEVICE_GET_SERIAL_NAME_POINTER
static const uint8_t *udc_get_string_serial_name(void) static const uint8_t *udc_get_string_serial_name()
{ {
return (const uint8_t *)USB_DEVICE_GET_SERIAL_NAME_POINTER; return (const uint8_t *)USB_DEVICE_GET_SERIAL_NAME_POINTER;
} }
# define USB_DEVICE_SERIAL_NAME_SIZE \ # define USB_DEVICE_SERIAL_NAME_SIZE \
USB_DEVICE_GET_SERIAL_NAME_LENGTH USB_DEVICE_GET_SERIAL_NAME_LENGTH
#elif defined USB_DEVICE_SERIAL_NAME #elif defined USB_DEVICE_SERIAL_NAME
static const uint8_t *udc_get_string_serial_name(void) static const uint8_t *udc_get_string_serial_name()
{ {
return (const uint8_t *)USB_DEVICE_SERIAL_NAME; return (const uint8_t *)USB_DEVICE_SERIAL_NAME;
} }
@ -164,7 +164,7 @@ static UDC_DESC_STORAGE struct udc_string_desc_t udc_string_desc = {
}; };
//! @} //! @}
usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void) usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc()
{ {
return udc_ptr_iface; return udc_ptr_iface;
} }
@ -174,7 +174,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void)
* *
* \return address after the last byte of USB Configuration descriptor * \return address after the last byte of USB Configuration descriptor
*/ */
static usb_conf_desc_t UDC_DESC_STORAGE *udc_get_eof_conf(void) static usb_conf_desc_t UDC_DESC_STORAGE *udc_get_eof_conf()
{ {
return (UDC_DESC_STORAGE usb_conf_desc_t *) ((uint8_t *) return (UDC_DESC_STORAGE usb_conf_desc_t *) ((uint8_t *)
udc_ptr_conf->desc + udc_ptr_conf->desc +
@ -360,14 +360,14 @@ static bool udc_iface_enable(uint8_t iface_num, uint8_t setting_num)
/*! \brief Start the USB Device stack /*! \brief Start the USB Device stack
*/ */
void udc_start(void) void udc_start()
{ {
udd_enable(); udd_enable();
} }
/*! \brief Stop the USB Device stack /*! \brief Stop the USB Device stack
*/ */
void udc_stop(void) void udc_stop()
{ {
udd_disable(); udd_disable();
udc_reset(); udc_reset();
@ -377,7 +377,7 @@ void udc_stop(void)
* \brief Reset the current configuration of the USB device, * \brief Reset the current configuration of the USB device,
* This routines can be called by UDD when a RESET on the USB line occurs. * This routines can be called by UDD when a RESET on the USB line occurs.
*/ */
void udc_reset(void) void udc_reset()
{ {
uint8_t iface_num; uint8_t iface_num;
@ -404,7 +404,7 @@ void udc_reset(void)
#endif #endif
} }
void udc_sof_notify(void) void udc_sof_notify()
{ {
uint8_t iface_num; uint8_t iface_num;
@ -424,7 +424,7 @@ void udc_sof_notify(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_get_status(void) static bool udc_req_std_dev_get_status()
{ {
if (udd_g_ctrlreq.req.wLength != sizeof(udc_device_status)) { if (udd_g_ctrlreq.req.wLength != sizeof(udc_device_status)) {
return false; return false;
@ -441,7 +441,7 @@ static bool udc_req_std_dev_get_status(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_ep_get_status(void) static bool udc_req_std_ep_get_status()
{ {
static le16_t udc_ep_status; static le16_t udc_ep_status;
@ -463,7 +463,7 @@ static bool udc_req_std_ep_get_status(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_clear_feature(void) static bool udc_req_std_dev_clear_feature()
{ {
if (udd_g_ctrlreq.req.wLength) { if (udd_g_ctrlreq.req.wLength) {
return false; return false;
@ -486,7 +486,7 @@ static bool udc_req_std_dev_clear_feature(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_ep_clear_feature(void) static bool udc_req_std_ep_clear_feature()
{ {
if (udd_g_ctrlreq.req.wLength) { if (udd_g_ctrlreq.req.wLength) {
return false; return false;
@ -504,7 +504,7 @@ static bool udc_req_std_ep_clear_feature(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_set_feature(void) static bool udc_req_std_dev_set_feature()
{ {
if (udd_g_ctrlreq.req.wLength) { if (udd_g_ctrlreq.req.wLength) {
return false; return false;
@ -567,7 +567,7 @@ static bool udc_req_std_dev_set_feature(void)
* \return true if success * \return true if success
*/ */
#if (0!=USB_DEVICE_MAX_EP) #if (0!=USB_DEVICE_MAX_EP)
static bool udc_req_std_ep_set_feature(void) static bool udc_req_std_ep_set_feature()
{ {
if (udd_g_ctrlreq.req.wLength) { if (udd_g_ctrlreq.req.wLength) {
return false; return false;
@ -584,7 +584,7 @@ static bool udc_req_std_ep_set_feature(void)
* \brief Change the address of device * \brief Change the address of device
* Callback called at the end of request set address * Callback called at the end of request set address
*/ */
static void udc_valid_address(void) static void udc_valid_address()
{ {
udd_set_address(udd_g_ctrlreq.req.wValue & 0x7F); udd_set_address(udd_g_ctrlreq.req.wValue & 0x7F);
} }
@ -594,7 +594,7 @@ static void udc_valid_address(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_set_address(void) static bool udc_req_std_dev_set_address()
{ {
if (udd_g_ctrlreq.req.wLength) { if (udd_g_ctrlreq.req.wLength) {
return false; return false;
@ -611,7 +611,7 @@ static bool udc_req_std_dev_set_address(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_get_str_desc(void) static bool udc_req_std_dev_get_str_desc()
{ {
uint8_t i; uint8_t i;
const uint8_t *str; const uint8_t *str;
@ -670,7 +670,7 @@ static bool udc_req_std_dev_get_str_desc(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_get_descriptor(void) static bool udc_req_std_dev_get_descriptor()
{ {
uint8_t conf_num; uint8_t conf_num;
@ -787,7 +787,7 @@ static bool udc_req_std_dev_get_descriptor(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_get_configuration(void) static bool udc_req_std_dev_get_configuration()
{ {
if (udd_g_ctrlreq.req.wLength != 1) { if (udd_g_ctrlreq.req.wLength != 1) {
return false; return false;
@ -802,7 +802,7 @@ static bool udc_req_std_dev_get_configuration(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_dev_set_configuration(void) static bool udc_req_std_dev_set_configuration()
{ {
uint8_t iface_num; uint8_t iface_num;
@ -867,7 +867,7 @@ static bool udc_req_std_dev_set_configuration(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_iface_get_setting(void) static bool udc_req_std_iface_get_setting()
{ {
uint8_t iface_num; uint8_t iface_num;
udi_api_t UDC_DESC_STORAGE *udi_api; udi_api_t UDC_DESC_STORAGE *udi_api;
@ -905,7 +905,7 @@ static bool udc_req_std_iface_get_setting(void)
* *
* \return true if success * \return true if success
*/ */
static bool udc_req_std_iface_set_setting(void) static bool udc_req_std_iface_set_setting()
{ {
uint8_t iface_num, setting_num; uint8_t iface_num, setting_num;
@ -933,7 +933,7 @@ static bool udc_req_std_iface_set_setting(void)
* *
* \return true if the request is supported * \return true if the request is supported
*/ */
static bool udc_reqstd(void) static bool udc_reqstd()
{ {
if (Udd_setup_is_in()) { if (Udd_setup_is_in()) {
// GET Standard Requests // GET Standard Requests
@ -1027,7 +1027,7 @@ static bool udc_reqstd(void)
* *
* \return true if the request is supported * \return true if the request is supported
*/ */
static bool udc_req_iface(void) static bool udc_req_iface()
{ {
uint8_t iface_num; uint8_t iface_num;
udi_api_t UDC_DESC_STORAGE *udi_api; udi_api_t UDC_DESC_STORAGE *udi_api;
@ -1062,7 +1062,7 @@ static bool udc_req_iface(void)
* *
* \return true if the request is supported * \return true if the request is supported
*/ */
static bool udc_req_ep(void) static bool udc_req_ep()
{ {
uint8_t iface_num; uint8_t iface_num;
udi_api_t UDC_DESC_STORAGE *udi_api; udi_api_t UDC_DESC_STORAGE *udi_api;
@ -1101,7 +1101,7 @@ static bool udc_req_ep(void)
* *
* \return true if the request is supported, else the request is stalled by UDD * \return true if the request is supported, else the request is stalled by UDD
*/ */
bool udc_process_setup(void) bool udc_process_setup()
{ {
// By default no data (receive/send) and no callbacks registered // By default no data (receive/send) and no callbacks registered
udd_g_ctrlreq.payload_size = 0; udd_g_ctrlreq.payload_size = 0;

View File

@ -172,18 +172,18 @@ extern "C" {
} }
\endcode \endcode
*/ */
static inline bool udc_include_vbus_monitoring(void) static inline bool udc_include_vbus_monitoring()
{ {
return udd_include_vbus_monitoring(); return udd_include_vbus_monitoring();
} }
/*! \brief Start the USB Device stack /*! \brief Start the USB Device stack
*/ */
void udc_start(void); void udc_start();
/*! \brief Stop the USB Device stack /*! \brief Stop the USB Device stack
*/ */
void udc_stop(void); void udc_stop();
/** /**
* \brief Attach device to the bus when possible * \brief Attach device to the bus when possible
@ -192,7 +192,7 @@ void udc_stop(void);
* then it will attach device when an acceptable Vbus * then it will attach device when an acceptable Vbus
* level from the host is detected. * level from the host is detected.
*/ */
static inline void udc_attach(void) static inline void udc_attach()
{ {
udd_attach(); udd_attach();
} }
@ -203,7 +203,7 @@ static inline void udc_attach(void)
* *
* The driver must remove pull-up on USB line D- or D+. * The driver must remove pull-up on USB line D- or D+.
*/ */
static inline void udc_detach(void) static inline void udc_detach()
{ {
udd_detach(); udd_detach();
} }
@ -212,7 +212,7 @@ static inline void udc_detach(void)
/*! \brief The USB driver sends a resume signal called \e "Upstream Resume" /*! \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. * This is authorized only when the remote wakeup feature is enabled by host.
*/ */
static inline void udc_remotewakeup(void) static inline void udc_remotewakeup()
{ {
udd_send_remotewakeup(); udd_send_remotewakeup();
} }
@ -223,7 +223,7 @@ static inline void udc_remotewakeup(void)
* *
* \return 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); usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc();
//@} //@}
@ -334,7 +334,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
* *
* Add to application C-file: * Add to application C-file:
* \code * \code
void usb_init(void) void usb_init()
{ {
udc_start(); udc_start();
} }
@ -551,23 +551,23 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
#define USB_DEVICE_ATTR \ #define USB_DEVICE_ATTR \
(USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED)
#define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable()
extern void my_callback_remotewakeup_enable(void); extern void my_callback_remotewakeup_enable();
#define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable()
extern void my_callback_remotewakeup_disable(void); extern void my_callback_remotewakeup_disable();
\endcode \endcode
* *
* Add to application C-file: * Add to application C-file:
* \code * \code
void my_callback_remotewakeup_enable(void) void my_callback_remotewakeup_enable()
{ {
// Enable application wakeup events (e.g. enable GPIO interrupt) // Enable application wakeup events (e.g. enable GPIO interrupt)
} }
void my_callback_remotewakeup_disable(void) void my_callback_remotewakeup_disable()
{ {
// Disable application wakeup events (e.g. disable GPIO interrupt) // Disable application wakeup events (e.g. disable GPIO interrupt)
} }
void my_interrupt_event(void) void my_interrupt_event()
{ {
udc_remotewakeup(); udc_remotewakeup();
} }
@ -580,10 +580,10 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode #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 * - \code // Define callback called when the host enables the remotewakeup feature
#define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable()
extern void my_callback_remotewakeup_enable(void); \endcode extern void my_callback_remotewakeup_enable(); \endcode
* - \code // Define callback called when the host disables the remotewakeup feature * - \code // Define callback called when the host disables the remotewakeup feature
#define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable()
extern void my_callback_remotewakeup_disable(void); \endcode extern void my_callback_remotewakeup_disable(); \endcode
* -# Send a remote wakeup (USB upstream): * -# Send a remote wakeup (USB upstream):
* - \code udc_remotewakeup(); \endcode * - \code udc_remotewakeup(); \endcode
*/ */
@ -605,18 +605,18 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
* \code * \code
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED)
#define UDC_SUSPEND_EVENT() user_callback_suspend_action() #define UDC_SUSPEND_EVENT() user_callback_suspend_action()
extern void user_callback_suspend_action(void) extern void user_callback_suspend_action()
#define UDC_RESUME_EVENT() user_callback_resume_action() #define UDC_RESUME_EVENT() user_callback_resume_action()
extern void user_callback_resume_action(void) extern void user_callback_resume_action()
\endcode \endcode
* *
* Add to application C-file: * Add to application C-file:
* \code * \code
void user_callback_suspend_action(void) void user_callback_suspend_action()
{ {
// Disable hardware component to reduce power consumption // Disable hardware component to reduce power consumption
} }
void user_callback_resume_action(void) void user_callback_resume_action()
{ {
// Re-enable hardware component // Re-enable hardware component
} }
@ -628,12 +628,12 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
#define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode
* - \code // Define callback called when the host suspend the USB line * - \code // Define callback called when the host suspend the USB line
#define UDC_SUSPEND_EVENT() user_callback_suspend_action() #define UDC_SUSPEND_EVENT() user_callback_suspend_action()
extern void user_callback_suspend_action(void); \endcode extern void user_callback_suspend_action(); \endcode
* - \code // Define callback called when the host or device resume the USB line * - \code // Define callback called when the host or device resume the USB line
#define UDC_RESUME_EVENT() user_callback_resume_action() #define UDC_RESUME_EVENT() user_callback_resume_action()
extern void user_callback_resume_action(void); \endcode extern void user_callback_resume_action(); \endcode
* -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus): * -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus):
* - \code void user_callback_suspend_action(void) * - \code void user_callback_suspend_action()
{ {
turn_off_components(); turn_off_components();
} \endcode } \endcode
@ -664,7 +664,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
* \code * \code
uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH];
void init_build_usb_serial_number(void) void init_build_usb_serial_number()
{ {
serial_number[0] = 'A'; serial_number[0] = 'A';
serial_number[1] = 'B'; serial_number[1] = 'B';
@ -683,7 +683,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
* - \code * - \code
uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH];
void init_build_usb_serial_number(void) void init_build_usb_serial_number()
{ {
serial_number[0] = 'A'; serial_number[0] = 'A';
serial_number[1] = 'B'; serial_number[1] = 'B';

View File

@ -94,11 +94,11 @@ typedef struct {
uint16_t payload_size; uint16_t payload_size;
//! Callback called after reception of ZLP from setup request //! Callback called after reception of ZLP from setup request
void (*callback)(void); void (*callback)();
//! Callback called when the buffer given (.payload) is full or empty. //! 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. //! This one return false to abort data transfer, or true with a new buffer in .payload.
bool (*over_under_run)(void); bool (*over_under_run)();
} udd_ctrl_request_t; } udd_ctrl_request_t;
extern udd_ctrl_request_t udd_g_ctrlreq; extern udd_ctrl_request_t udd_g_ctrlreq;
@ -123,7 +123,7 @@ extern udd_ctrl_request_t udd_g_ctrlreq;
* Registered by routine udd_ep_wait_stall_clear() * Registered by routine udd_ep_wait_stall_clear()
* Callback called when endpoint stall is cleared. * Callback called when endpoint stall is cleared.
*/ */
typedef void (*udd_callback_halt_cleared_t)(void); typedef void (*udd_callback_halt_cleared_t)();
/** /**
* \brief End of transfer callback function type. * \brief End of transfer callback function type.
@ -142,17 +142,17 @@ typedef void (*udd_callback_trans_t) (udd_ep_status_t status,
* *
* \return true, if the VBUS monitoring is possible. * \return true, if the VBUS monitoring is possible.
*/ */
bool udd_include_vbus_monitoring(void); bool udd_include_vbus_monitoring();
/** /**
* \brief Enables the USB Device mode * \brief Enables the USB Device mode
*/ */
void udd_enable(void); void udd_enable();
/** /**
* \brief Disables the USB Device mode * \brief Disables the USB Device mode
*/ */
void udd_disable(void); void udd_disable();
/** /**
* \brief Attach device to the bus when possible * \brief Attach device to the bus when possible
@ -161,14 +161,14 @@ void udd_disable(void);
* then it will attach device when an acceptable Vbus * then it will attach device when an acceptable Vbus
* level from the host is detected. * level from the host is detected.
*/ */
void udd_attach(void); void udd_attach();
/** /**
* \brief Detaches the device from the bus * \brief Detaches the device from the bus
* *
* The driver must remove pull-up on USB line D- or D+. * The driver must remove pull-up on USB line D- or D+.
*/ */
void udd_detach(void); void udd_detach();
/** /**
* \brief Test whether the USB Device Controller is running at high * \brief Test whether the USB Device Controller is running at high
@ -176,7 +176,7 @@ void udd_detach(void);
* *
* \return \c true if the Device is running at high speed mode, otherwise \c false. * \return \c true if the Device is running at high speed mode, otherwise \c false.
*/ */
bool udd_is_high_speed(void); bool udd_is_high_speed();
/** /**
* \brief Changes the USB address of device * \brief Changes the USB address of device
@ -190,25 +190,25 @@ void udd_set_address(uint8_t address);
* *
* \return USB address * \return USB address
*/ */
uint8_t udd_getaddress(void); uint8_t udd_getaddress();
/** /**
* \brief Returns the current start of frame number * \brief Returns the current start of frame number
* *
* \return current start of frame number. * \return current start of frame number.
*/ */
uint16_t udd_get_frame_number(void); uint16_t udd_get_frame_number();
/** /**
* \brief Returns the current micro start of frame number * \brief Returns the current micro start of frame number
* *
* \return current micro start of frame number required in high speed mode. * \return current micro start of frame number required in high speed mode.
*/ */
uint16_t udd_get_micro_frame_number(void); uint16_t udd_get_micro_frame_number();
/*! \brief The USB driver sends a resume signal called Upstream Resume /*! \brief The USB driver sends a resume signal called Upstream Resume
*/ */
void udd_send_remotewakeup(void); void udd_send_remotewakeup();
/** /**
* \brief Load setup payload * \brief Load setup payload
@ -346,10 +346,10 @@ void udd_ep_abort(udd_ep_id_t ep);
* The following functions allow the device to jump to a specific test mode required in high speed mode. * 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_j();
void udd_test_mode_k(void); void udd_test_mode_k();
void udd_test_mode_se0_nak(void); void udd_test_mode_se0_nak();
void udd_test_mode_packet(void); void udd_test_mode_packet();
//@} //@}
@ -370,21 +370,21 @@ void udd_test_mode_packet(void);
* *
* \return \c 1 if the request is accepted, otherwise \c 0. * \return \c 1 if the request is accepted, otherwise \c 0.
*/ */
extern bool udc_process_setup(void); extern bool udc_process_setup();
/** /**
* \brief Reset the UDC * \brief Reset the UDC
* *
* The UDC must reset all configuration. * The UDC must reset all configuration.
*/ */
extern void udc_reset(void); extern void udc_reset();
/** /**
* \brief To signal that a SOF is occurred * \brief To signal that a SOF is occurred
* *
* The UDC must send the signal to all UDIs enabled * The UDC must send the signal to all UDIs enabled
*/ */
extern void udc_sof_notify(void); extern void udc_sof_notify();
//@} //@}

View File

@ -82,7 +82,7 @@ typedef struct {
* *
* \return \c 1 if function was successfully done, otherwise \c 0. * \return \c 1 if function was successfully done, otherwise \c 0.
*/ */
bool (*enable)(void); bool (*enable)();
/** /**
* \brief Disable the interface. * \brief Disable the interface.
@ -95,7 +95,7 @@ typedef struct {
* - the device is detached from the host (i.e. Vbus is no * - the device is detached from the host (i.e. Vbus is no
* longer present) * longer present)
*/ */
void (*disable)(void); void (*disable)();
/** /**
* \brief Handle a control request directed at an interface. * \brief Handle a control request directed at an interface.
@ -108,7 +108,7 @@ typedef struct {
* *
* \return \c 1 if this interface supports the SETUP request, otherwise \c 0. * \return \c 1 if this interface supports the SETUP request, otherwise \c 0.
*/ */
bool (*setup)(void); bool (*setup)();
/** /**
* \brief Returns the current setting of the selected interface. * \brief Returns the current setting of the selected interface.
@ -117,12 +117,12 @@ typedef struct {
* *
* \return alternate setting of selected interface * \return alternate setting of selected interface
*/ */
uint8_t (*getsetting)(void); uint8_t (*getsetting)();
/** /**
* \brief To signal that a SOF is occurred * \brief To signal that a SOF is occurred
*/ */
void (*sof_notify)(void); void (*sof_notify)();
} udi_api_t; } udi_api_t;
//@} //@}

View File

@ -84,14 +84,14 @@
* *
* @{ * @{
*/ */
bool udi_cdc_comm_enable(void); bool udi_cdc_comm_enable();
void udi_cdc_comm_disable(void); void udi_cdc_comm_disable();
bool udi_cdc_comm_setup(void); bool udi_cdc_comm_setup();
bool udi_cdc_data_enable(void); bool udi_cdc_data_enable();
void udi_cdc_data_disable(void); void udi_cdc_data_disable();
bool udi_cdc_data_setup(void); bool udi_cdc_data_setup();
uint8_t udi_cdc_getsetting(void); uint8_t udi_cdc_getsetting();
void udi_cdc_data_sof_notify(void); void udi_cdc_data_sof_notify();
UDC_DESC_STORAGE udi_api_t udi_api_cdc_comm = { UDC_DESC_STORAGE udi_api_t udi_api_cdc_comm = {
.enable = udi_cdc_comm_enable, .enable = udi_cdc_comm_enable,
.disable = udi_cdc_comm_disable, .disable = udi_cdc_comm_disable,
@ -130,14 +130,14 @@ UDC_DESC_STORAGE udi_api_t udi_api_cdc_data = {
* *
* \return port number * \return port number
*/ */
static uint8_t udi_cdc_setup_to_port(void); static uint8_t udi_cdc_setup_to_port();
/** /**
* \brief Sends line coding to application * \brief Sends line coding to application
* *
* Called after SETUP request when line coding data is received. * Called after SETUP request when line coding data is received.
*/ */
static void udi_cdc_line_coding_received(void); static void udi_cdc_line_coding_received();
/** /**
* \brief Records new state * \brief Records new state
@ -267,7 +267,7 @@ static volatile bool udi_cdc_tx_both_buf_to_send[UDI_CDC_PORT_NB];
//@} //@}
bool udi_cdc_comm_enable(void) bool udi_cdc_comm_enable()
{ {
uint8_t port; uint8_t port;
uint8_t iface_comm_num; uint8_t iface_comm_num;
@ -321,7 +321,7 @@ bool udi_cdc_comm_enable(void)
return true; return true;
} }
bool udi_cdc_data_enable(void) bool udi_cdc_data_enable()
{ {
uint8_t port; uint8_t port;
@ -360,13 +360,13 @@ bool udi_cdc_data_enable(void)
return true; return true;
} }
void udi_cdc_comm_disable(void) void udi_cdc_comm_disable()
{ {
Assert(udi_cdc_nb_comm_enabled != 0); Assert(udi_cdc_nb_comm_enabled != 0);
udi_cdc_nb_comm_enabled--; udi_cdc_nb_comm_enabled--;
} }
void udi_cdc_data_disable(void) void udi_cdc_data_disable()
{ {
uint8_t port; uint8_t port;
@ -377,7 +377,7 @@ void udi_cdc_data_disable(void)
udi_cdc_data_running = false; udi_cdc_data_running = false;
} }
bool udi_cdc_comm_setup(void) bool udi_cdc_comm_setup()
{ {
uint8_t port = udi_cdc_setup_to_port(); uint8_t port = udi_cdc_setup_to_port();
@ -433,17 +433,17 @@ bool udi_cdc_comm_setup(void)
return false; // request Not supported return false; // request Not supported
} }
bool udi_cdc_data_setup(void) bool udi_cdc_data_setup()
{ {
return false; // request Not supported return false; // request Not supported
} }
uint8_t udi_cdc_getsetting(void) uint8_t udi_cdc_getsetting()
{ {
return 0; // CDC don't have multiple alternate setting return 0; // CDC don't have multiple alternate setting
} }
void udi_cdc_data_sof_notify(void) void udi_cdc_data_sof_notify()
{ {
static uint8_t port_notify = 0; static uint8_t port_notify = 0;
@ -461,7 +461,7 @@ void udi_cdc_data_sof_notify(void)
// ------------------------ // ------------------------
//------- Internal routines to control serial line //------- Internal routines to control serial line
static uint8_t udi_cdc_setup_to_port(void) static uint8_t udi_cdc_setup_to_port()
{ {
uint8_t port; uint8_t port;
@ -479,7 +479,7 @@ static uint8_t udi_cdc_setup_to_port(void)
return port; return port;
} }
static void udi_cdc_line_coding_received(void) static void udi_cdc_line_coding_received()
{ {
uint8_t port = udi_cdc_setup_to_port(); uint8_t port = udi_cdc_setup_to_port();
UNUSED(port); UNUSED(port);
@ -797,17 +797,17 @@ void udi_cdc_ctrl_signal_dsr(bool b_set)
udi_cdc_ctrl_state_change(0, b_set, CDC_SERIAL_STATE_DSR); udi_cdc_ctrl_state_change(0, b_set, CDC_SERIAL_STATE_DSR);
} }
void udi_cdc_signal_framing_error(void) void udi_cdc_signal_framing_error()
{ {
udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_FRAMING); udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_FRAMING);
} }
void udi_cdc_signal_parity_error(void) void udi_cdc_signal_parity_error()
{ {
udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_PARITY); udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_PARITY);
} }
void udi_cdc_signal_overrun(void) void udi_cdc_signal_overrun()
{ {
udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_OVERRUN); udi_cdc_ctrl_state_change(0, true, CDC_SERIAL_STATE_OVERRUN);
} }
@ -853,7 +853,7 @@ iram_size_t udi_cdc_multi_get_nb_received_data(uint8_t port)
return nb_received; return nb_received;
} }
iram_size_t udi_cdc_get_nb_received_data(void) iram_size_t udi_cdc_get_nb_received_data()
{ {
return udi_cdc_multi_get_nb_received_data(0); return udi_cdc_multi_get_nb_received_data(0);
} }
@ -863,7 +863,7 @@ bool udi_cdc_multi_is_rx_ready(uint8_t port)
return (udi_cdc_multi_get_nb_received_data(port) > 0); return (udi_cdc_multi_get_nb_received_data(port) > 0);
} }
bool udi_cdc_is_rx_ready(void) bool udi_cdc_is_rx_ready()
{ {
return udi_cdc_multi_is_rx_ready(0); return udi_cdc_multi_is_rx_ready(0);
} }
@ -912,7 +912,7 @@ udi_cdc_getc_process_one_byte:
return rx_data; return rx_data;
} }
int udi_cdc_getc(void) int udi_cdc_getc()
{ {
return udi_cdc_multi_getc(0); return udi_cdc_multi_getc(0);
} }
@ -1041,7 +1041,7 @@ iram_size_t __attribute__((optimize("O0"))) udi_cdc_multi_get_free_tx_buffer(uin
return retval; return retval;
} }
iram_size_t udi_cdc_get_free_tx_buffer(void) iram_size_t udi_cdc_get_free_tx_buffer()
{ {
return udi_cdc_multi_get_free_tx_buffer(0); return udi_cdc_multi_get_free_tx_buffer(0);
} }
@ -1051,7 +1051,7 @@ bool udi_cdc_multi_is_tx_ready(uint8_t port)
return (udi_cdc_multi_get_free_tx_buffer(port) != 0); return (udi_cdc_multi_get_free_tx_buffer(port) != 0);
} }
bool udi_cdc_is_tx_ready(void) bool udi_cdc_is_tx_ready()
{ {
return udi_cdc_multi_is_tx_ready(0); return udi_cdc_multi_is_tx_ready(0);
} }

View File

@ -366,38 +366,38 @@ void udi_cdc_ctrl_signal_dsr(bool b_set);
/** /**
* \brief Notify a framing error * \brief Notify a framing error
*/ */
void udi_cdc_signal_framing_error(void); void udi_cdc_signal_framing_error();
/** /**
* \brief Notify a parity error * \brief Notify a parity error
*/ */
void udi_cdc_signal_parity_error(void); void udi_cdc_signal_parity_error();
/** /**
* \brief Notify a overrun * \brief Notify a overrun
*/ */
void udi_cdc_signal_overrun(void); void udi_cdc_signal_overrun();
/** /**
* \brief Gets the number of byte received * \brief Gets the number of byte received
* *
* \return the number of data available * \return the number of data available
*/ */
iram_size_t udi_cdc_get_nb_received_data(void); iram_size_t udi_cdc_get_nb_received_data();
/** /**
* \brief This function checks if a character has been received on the CDC line * \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. * \return \c 1 if a byte is ready to be read.
*/ */
bool udi_cdc_is_rx_ready(void); bool udi_cdc_is_rx_ready();
/** /**
* \brief Waits and gets a value on CDC line * \brief Waits and gets a value on CDC line
* *
* \return value read on CDC line * \return value read on CDC line
*/ */
int udi_cdc_getc(void); int udi_cdc_getc();
/** /**
* \brief Reads a RAM buffer on CDC line * \brief Reads a RAM buffer on CDC line
@ -425,7 +425,7 @@ iram_size_t udi_cdc_read_no_polling(void* buf, iram_size_t size);
* *
* \return 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); iram_size_t udi_cdc_get_free_tx_buffer();
/** /**
* \brief This function checks if a new character sent is possible * \brief This function checks if a new character sent is possible
@ -433,7 +433,7 @@ iram_size_t udi_cdc_get_free_tx_buffer(void);
* *
* \return \c 1 if a new character can be sent * \return \c 1 if a new character can be sent
*/ */
bool udi_cdc_is_tx_ready(void); bool udi_cdc_is_tx_ready();
/** /**
* \brief Puts a byte on CDC line * \brief Puts a byte on CDC line
@ -611,9 +611,9 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s
* Content of conf_usb.h: * Content of conf_usb.h:
* \code * \code
#define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable()
extern bool my_callback_cdc_enable(void); extern bool my_callback_cdc_enable();
#define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable()
extern void my_callback_cdc_disable(void); extern void my_callback_cdc_disable();
#define UDI_CDC_LOW_RATE #define UDI_CDC_LOW_RATE
#define UDI_CDC_DEFAULT_RATE 115200 #define UDI_CDC_DEFAULT_RATE 115200
@ -627,17 +627,17 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s
* Add to application C-file: * Add to application C-file:
* \code * \code
static bool my_flag_autorize_cdc_transfert = false; static bool my_flag_autorize_cdc_transfert = false;
bool my_callback_cdc_enable(void) bool my_callback_cdc_enable()
{ {
my_flag_autorize_cdc_transfert = true; my_flag_autorize_cdc_transfert = true;
return true; return true;
} }
void my_callback_cdc_disable(void) void my_callback_cdc_disable()
{ {
my_flag_autorize_cdc_transfert = false; my_flag_autorize_cdc_transfert = false;
} }
void task(void) void task()
{ {
if (my_flag_autorize_cdc_transfert) { if (my_flag_autorize_cdc_transfert) {
udi_cdc_putc('A'); udi_cdc_putc('A');
@ -652,14 +652,14 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s
* - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode * - \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. * \note The USB serial number is mandatory when a CDC interface is used.
* - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() * - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable()
extern bool my_callback_cdc_enable(void); \endcode extern bool my_callback_cdc_enable(); \endcode
* \note After the device enumeration (detecting and identifying USB devices), * \note After the device enumeration (detecting and identifying USB devices),
* the USB host starts the device configuration. When the USB CDC interface * 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 * 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. * 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. * 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() * - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable()
extern void my_callback_cdc_disable(void); \endcode extern void my_callback_cdc_disable(); \endcode
* \note When the USB device is unplugged or is reset by the USB host, the USB * \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 * interface is disabled and the UDI_CDC_DISABLE_EXT() callback function
* is called. Thus, the data transfer must be stopped on CDC interface. * is called. Thus, the data transfer must be stopped on CDC interface.
@ -673,7 +673,7 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s
* \note Default configuration of communication port at startup. * \note Default configuration of communication port at startup.
* -# Send or wait data on CDC line: * -# Send or wait data on CDC line:
* - \code // Waits and gets a value on CDC line * - \code // Waits and gets a value on CDC line
int udi_cdc_getc(void); int udi_cdc_getc();
// Reads a RAM buffer on CDC line // Reads a RAM buffer on CDC line
iram_size_t udi_cdc_read_buf(int* buf, iram_size_t size); iram_size_t udi_cdc_read_buf(int* buf, iram_size_t size);
// Puts a byte on CDC line // Puts a byte on CDC line

View File

@ -71,10 +71,10 @@
* *
* @{ * @{
*/ */
bool udi_msc_enable(void); bool udi_msc_enable();
void udi_msc_disable(void); void udi_msc_disable();
bool udi_msc_setup(void); bool udi_msc_setup();
uint8_t udi_msc_getsetting(void); uint8_t udi_msc_getsetting();
//! Global structure which contains standard UDI API for UDC //! Global structure which contains standard UDI API for UDC
UDC_DESC_STORAGE udi_api_t udi_api_msc = { UDC_DESC_STORAGE udi_api_t udi_api_msc = {
@ -151,12 +151,12 @@ volatile bool udi_msc_b_reset_trans = true;
/** /**
* \brief Stall CBW request * \brief Stall CBW request
*/ */
static void udi_msc_cbw_invalid(void); static void udi_msc_cbw_invalid();
/** /**
* \brief Stall CSW request * \brief Stall CSW request
*/ */
static void udi_msc_csw_invalid(void); static void udi_msc_csw_invalid();
/** /**
* \brief Links a callback and buffer on endpoint OUT reception * \brief Links a callback and buffer on endpoint OUT reception
@ -165,7 +165,7 @@ static void udi_msc_csw_invalid(void);
* - enable interface * - enable interface
* - at the end of previous command after sending the CSW * - at the end of previous command after sending the CSW
*/ */
static void udi_msc_cbw_wait(void); static void udi_msc_cbw_wait();
/** /**
* \brief Callback called after CBW reception * \brief Callback called after CBW reception
@ -228,7 +228,7 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent,
* *
* Called at the end of SCSI command * Called at the end of SCSI command
*/ */
static void udi_msc_csw_process(void); static void udi_msc_csw_process();
/** /**
* \brief Sends CSW * \brief Sends CSW
@ -236,7 +236,7 @@ static void udi_msc_csw_process(void);
* Called by #udi_msc_csw_process() * Called by #udi_msc_csw_process()
* or UDD callback when endpoint halt is cleared * or UDD callback when endpoint halt is cleared
*/ */
void udi_msc_csw_send(void); void udi_msc_csw_send();
/** /**
* \brief Callback called after CSW sent * \brief Callback called after CSW sent
@ -259,7 +259,7 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent,
/** /**
* \brief Reinitialize sense data. * \brief Reinitialize sense data.
*/ */
static void udi_msc_clear_sense(void); static void udi_msc_clear_sense();
/** /**
* \brief Update sense data with new value to signal a fail * \brief Update sense data with new value to signal a fail
@ -274,37 +274,37 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense,
/** /**
* \brief Update sense data with new value to signal success * \brief Update sense data with new value to signal success
*/ */
static void udi_msc_sense_pass(void); static void udi_msc_sense_pass();
/** /**
* \brief Update sense data to signal that memory is not present * \brief Update sense data to signal that memory is not present
*/ */
static void udi_msc_sense_fail_not_present(void); static void udi_msc_sense_fail_not_present();
/** /**
* \brief Update sense data to signal that memory is busy * \brief Update sense data to signal that memory is busy
*/ */
static void udi_msc_sense_fail_busy_or_change(void); static void udi_msc_sense_fail_busy_or_change();
/** /**
* \brief Update sense data to signal a hardware error on memory * \brief Update sense data to signal a hardware error on memory
*/ */
static void udi_msc_sense_fail_hardware(void); static void udi_msc_sense_fail_hardware();
/** /**
* \brief Update sense data to signal that memory is protected * \brief Update sense data to signal that memory is protected
*/ */
static void udi_msc_sense_fail_protected(void); static void udi_msc_sense_fail_protected();
/** /**
* \brief Update sense data to signal that CDB fields are not valid * \brief Update sense data to signal that CDB fields are not valid
*/ */
static void udi_msc_sense_fail_cdb_invalid(void); static void udi_msc_sense_fail_cdb_invalid();
/** /**
* \brief Update sense data to signal that command is not supported * \brief Update sense data to signal that command is not supported
*/ */
static void udi_msc_sense_command_invalid(void); static void udi_msc_sense_command_invalid();
//@} //@}
@ -317,31 +317,31 @@ static void udi_msc_sense_command_invalid(void);
* \brief Process SPC Request Sense command * \brief Process SPC Request Sense command
* Returns error information about last command * Returns error information about last command
*/ */
static void udi_msc_spc_requestsense(void); static void udi_msc_spc_requestsense();
/** /**
* \brief Process SPC Inquiry command * \brief Process SPC Inquiry command
* Returns information (name,version) about disk * Returns information (name,version) about disk
*/ */
static void udi_msc_spc_inquiry(void); static void udi_msc_spc_inquiry();
/** /**
* \brief Checks state of disk * \brief Checks state of disk
* *
* \retval true if disk is ready, otherwise false and updates sense data * \retval true if disk is ready, otherwise false and updates sense data
*/ */
static bool udi_msc_spc_testunitready_global(void); static bool udi_msc_spc_testunitready_global();
/** /**
* \brief Process test unit ready command * \brief Process test unit ready command
* Returns state of logical unit * Returns state of logical unit
*/ */
static void udi_msc_spc_testunitready(void); static void udi_msc_spc_testunitready();
/** /**
* \brief Process prevent allow medium removal command * \brief Process prevent allow medium removal command
*/ */
static void udi_msc_spc_prevent_allow_medium_removal(void); static void udi_msc_spc_prevent_allow_medium_removal();
/** /**
* \brief Process mode sense command * \brief Process mode sense command
@ -354,12 +354,12 @@ static void udi_msc_spc_mode_sense(bool b_sense10);
/** /**
* \brief Process start stop command * \brief Process start stop command
*/ */
static void udi_msc_sbc_start_stop(void); static void udi_msc_sbc_start_stop();
/** /**
* \brief Process read capacity command * \brief Process read capacity command
*/ */
static void udi_msc_sbc_read_capacity(void); static void udi_msc_sbc_read_capacity();
/** /**
* \brief Process read10 or write10 command * \brief Process read10 or write10 command
@ -373,7 +373,7 @@ static void udi_msc_sbc_trans(bool b_read);
//@} //@}
bool udi_msc_enable(void) bool udi_msc_enable()
{ {
uint8_t lun; uint8_t lun;
udi_msc_b_trans_req = false; udi_msc_b_trans_req = false;
@ -398,7 +398,7 @@ bool udi_msc_enable(void)
} }
void udi_msc_disable(void) void udi_msc_disable()
{ {
udi_msc_b_trans_req = false; udi_msc_b_trans_req = false;
udi_msc_b_ack_trans = true; udi_msc_b_ack_trans = true;
@ -407,7 +407,7 @@ void udi_msc_disable(void)
} }
bool udi_msc_setup(void) bool udi_msc_setup()
{ {
if (Udd_setup_is_in()) { if (Udd_setup_is_in()) {
// Requests Interface GET // Requests Interface GET
@ -451,7 +451,7 @@ bool udi_msc_setup(void)
return false; // Not supported request return false; // Not supported request
} }
uint8_t udi_msc_getsetting(void) uint8_t udi_msc_getsetting()
{ {
return 0; // MSC don't have multiple alternate setting return 0; // MSC don't have multiple alternate setting
} }
@ -460,7 +460,7 @@ uint8_t udi_msc_getsetting(void)
// ------------------------ // ------------------------
//------- Routines to process CBW packet //------- Routines to process CBW packet
static void udi_msc_cbw_invalid(void) static void udi_msc_cbw_invalid()
{ {
if (!udi_msc_b_cbw_invalid) if (!udi_msc_b_cbw_invalid)
return; // Don't re-stall endpoint if error reseted by setup return; // Don't re-stall endpoint if error reseted by setup
@ -469,7 +469,7 @@ static void udi_msc_cbw_invalid(void)
udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid);
} }
static void udi_msc_csw_invalid(void) static void udi_msc_csw_invalid()
{ {
if (!udi_msc_b_cbw_invalid) if (!udi_msc_b_cbw_invalid)
return; // Don't re-stall endpoint if error reseted by setup return; // Don't re-stall endpoint if error reseted by setup
@ -478,7 +478,7 @@ static void udi_msc_csw_invalid(void)
udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid);
} }
static void udi_msc_cbw_wait(void) static void udi_msc_cbw_wait()
{ {
// Register buffer and callback on OUT endpoint // Register buffer and callback on OUT endpoint
if (!udd_ep_run(UDI_MSC_EP_OUT, true, if (!udd_ep_run(UDI_MSC_EP_OUT, true,
@ -648,7 +648,7 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent,
// ------------------------ // ------------------------
//------- Routines to process CSW packet //------- Routines to process CSW packet
static void udi_msc_csw_process(void) static void udi_msc_csw_process()
{ {
if (0 != udi_msc_csw.dCSWDataResidue) { if (0 != udi_msc_csw.dCSWDataResidue) {
// Residue not NULL // Residue not NULL
@ -665,7 +665,7 @@ static void udi_msc_csw_process(void)
} }
void udi_msc_csw_send(void) void udi_msc_csw_send()
{ {
// Sends CSW on IN endpoint // Sends CSW on IN endpoint
if (!udd_ep_run(UDI_MSC_EP_IN, false, if (!udd_ep_run(UDI_MSC_EP_IN, false,
@ -694,7 +694,7 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent,
// ------------------------ // ------------------------
//------- Routines manage sense data //------- Routines manage sense data
static void udi_msc_clear_sense(void) static void udi_msc_clear_sense()
{ {
memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data)); memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data));
udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT; udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT;
@ -715,42 +715,42 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense,
udi_msc_sense.AddSnsCodeQlfr = add_sense; udi_msc_sense.AddSnsCodeQlfr = add_sense;
} }
static void udi_msc_sense_pass(void) static void udi_msc_sense_pass()
{ {
udi_msc_clear_sense(); udi_msc_clear_sense();
udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS; udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS;
} }
static void udi_msc_sense_fail_not_present(void) static void udi_msc_sense_fail_not_present()
{ {
udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0); udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0);
} }
static void udi_msc_sense_fail_busy_or_change(void) static void udi_msc_sense_fail_busy_or_change()
{ {
udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION,
SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0);
} }
static void udi_msc_sense_fail_hardware(void) static void udi_msc_sense_fail_hardware()
{ {
udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR,
SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0);
} }
static void udi_msc_sense_fail_protected(void) static void udi_msc_sense_fail_protected()
{ {
udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0); udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0);
} }
static void udi_msc_sense_fail_cdb_invalid(void) static void udi_msc_sense_fail_cdb_invalid()
{ {
udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST,
SCSI_ASC_INVALID_FIELD_IN_CDB, 0); SCSI_ASC_INVALID_FIELD_IN_CDB, 0);
} }
static void udi_msc_sense_command_invalid(void) static void udi_msc_sense_command_invalid()
{ {
udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST,
SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0);
@ -760,7 +760,7 @@ static void udi_msc_sense_command_invalid(void)
// ------------------------ // ------------------------
//------- Routines manage SCSI Commands //------- Routines manage SCSI Commands
static void udi_msc_spc_requestsense(void) static void udi_msc_spc_requestsense()
{ {
uint8_t length = udi_msc_cbw.CDB[4]; uint8_t length = udi_msc_cbw.CDB[4];
@ -775,7 +775,7 @@ static void udi_msc_spc_requestsense(void)
} }
static void udi_msc_spc_inquiry(void) static void udi_msc_spc_inquiry()
{ {
uint8_t length, i; uint8_t length, i;
UDC_DATA(4) UDC_DATA(4)
@ -836,7 +836,7 @@ static void udi_msc_spc_inquiry(void)
} }
static bool udi_msc_spc_testunitready_global(void) static bool udi_msc_spc_testunitready_global()
{ {
switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) { switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) {
case CTRL_GOOD: case CTRL_GOOD:
@ -856,7 +856,7 @@ static bool udi_msc_spc_testunitready_global(void)
} }
static void udi_msc_spc_testunitready(void) static void udi_msc_spc_testunitready()
{ {
if (udi_msc_spc_testunitready_global()) { if (udi_msc_spc_testunitready_global()) {
// LUN ready, then update sense data with status pass // LUN ready, then update sense data with status pass
@ -944,7 +944,7 @@ static void udi_msc_spc_mode_sense(bool b_sense10)
} }
static void udi_msc_spc_prevent_allow_medium_removal(void) static void udi_msc_spc_prevent_allow_medium_removal()
{ {
uint8_t prevent = udi_msc_cbw.CDB[4]; uint8_t prevent = udi_msc_cbw.CDB[4];
if (0 == prevent) { if (0 == prevent) {
@ -956,7 +956,7 @@ static void udi_msc_spc_prevent_allow_medium_removal(void)
} }
static void udi_msc_sbc_start_stop(void) static void udi_msc_sbc_start_stop()
{ {
bool start = 0x1 & udi_msc_cbw.CDB[4]; bool start = 0x1 & udi_msc_cbw.CDB[4];
bool loej = 0x2 & udi_msc_cbw.CDB[4]; bool loej = 0x2 & udi_msc_cbw.CDB[4];
@ -968,7 +968,7 @@ static void udi_msc_sbc_start_stop(void)
} }
static void udi_msc_sbc_read_capacity(void) static void udi_msc_sbc_read_capacity()
{ {
UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity; UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity;
@ -1039,7 +1039,7 @@ static void udi_msc_sbc_trans(bool b_read)
} }
bool udi_msc_process_trans(void) bool udi_msc_process_trans()
{ {
Ctrl_status status; Ctrl_status status;

View File

@ -148,7 +148,7 @@ typedef struct {
* *
* Routine called by the main loop * Routine called by the main loop
*/ */
bool udi_msc_process_trans(void); bool udi_msc_process_trans();
/** /**
* \brief Transfers data to/from USB MSC endpoints * \brief Transfers data to/from USB MSC endpoints
@ -206,26 +206,26 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
#define UDI_MSC_GLOBAL_PRODUCT_VERSION \ #define UDI_MSC_GLOBAL_PRODUCT_VERSION \
'1', '.', '0', '0' '1', '.', '0', '0'
#define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable()
extern bool my_callback_msc_enable(void); extern bool my_callback_msc_enable();
#define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable()
extern void my_callback_msc_disable(void); extern void my_callback_msc_disable();
#include "udi_msc_conf.h" // At the end of conf_usb.h file #include "udi_msc_conf.h" // At the end of conf_usb.h file
\endcode \endcode
* *
* Add to application C-file: * Add to application C-file:
* \code * \code
static bool my_flag_autorize_msc_transfert = false; static bool my_flag_autorize_msc_transfert = false;
bool my_callback_msc_enable(void) bool my_callback_msc_enable()
{ {
my_flag_autorize_msc_transfert = true; my_flag_autorize_msc_transfert = true;
return true; return true;
} }
void my_callback_msc_disable(void) void my_callback_msc_disable()
{ {
my_flag_autorize_msc_transfert = false; my_flag_autorize_msc_transfert = false;
} }
void task(void) void task()
{ {
udi_msc_process_trans(); udi_msc_process_trans();
} }
@ -244,7 +244,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
* \note The USB MSC interface requires a vendor ID (8 ASCII characters) * \note The USB MSC interface requires a vendor ID (8 ASCII characters)
* and a product version (4 ASCII characters). * and a product version (4 ASCII characters).
* - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable()
extern bool my_callback_msc_enable(void); \endcode extern bool my_callback_msc_enable(); \endcode
* \note After the device enumeration (detecting and identifying USB devices), * \note After the device enumeration (detecting and identifying USB devices),
* the USB host starts the device configuration. When the USB MSC interface * 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 * from the device is accepted by the host, the USB host enables this interface and the
@ -252,7 +252,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
* Thus, when this event is received, the tasks which call * Thus, when this event is received, the tasks which call
* udi_msc_process_trans() must be enabled. * udi_msc_process_trans() must be enabled.
* - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() * - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable()
extern void my_callback_msc_disable(void); \endcode extern void my_callback_msc_disable(); \endcode
* \note When the USB device is unplugged or is reset by the USB host, the USB * \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 * 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(). * is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans().
@ -260,14 +260,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
* which provides the memories interfaces. However, the memory data transfers * which provides the memories interfaces. However, the memory data transfers
* must be done outside USB interrupt routine. This is done in the MSC process * must be done outside USB interrupt routine. This is done in the MSC process
* ("udi_msc_process_trans()") called by main loop: * ("udi_msc_process_trans()") called by main loop:
* - \code * void task(void) { * - \code * void task() {
udi_msc_process_trans(); udi_msc_process_trans();
} \endcode } \endcode
* -# The MSC speed depends on task periodicity. To get the best speed * -# 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 * the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup
* this task (Example, through a mutex): * this task (Example, through a mutex):
* - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans() * - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans()
void msc_notify_trans(void) { void msc_notify_trans() {
wakeup_my_task(); wakeup_my_task();
} \endcode } \endcode
* *

View File

@ -357,41 +357,41 @@ static uint16_t udd_ctrl_payload_buf_cnt;
* *
* Called after a USB line reset or when UDD is enabled * Called after a USB line reset or when UDD is enabled
*/ */
static void udd_reset_ep_ctrl(void); static void udd_reset_ep_ctrl();
/** /**
* \brief Reset control endpoint management * \brief Reset control endpoint management
* *
* Called after a USB line reset or at the end of SETUP request (after ZLP) * Called after a USB line reset or at the end of SETUP request (after ZLP)
*/ */
static void udd_ctrl_init(void); static void udd_ctrl_init();
//! \brief Managed reception of SETUP packet on control endpoint //! \brief Managed reception of SETUP packet on control endpoint
static void udd_ctrl_setup_received(void); static void udd_ctrl_setup_received();
//! \brief Managed reception of IN packet on control endpoint //! \brief Managed reception of IN packet on control endpoint
static void udd_ctrl_in_sent(void); static void udd_ctrl_in_sent();
//! \brief Managed reception of OUT packet on control endpoint //! \brief Managed reception of OUT packet on control endpoint
static void udd_ctrl_out_received(void); static void udd_ctrl_out_received();
//! \brief Managed underflow event of IN packet on control endpoint //! \brief Managed underflow event of IN packet on control endpoint
static void udd_ctrl_underflow(void); static void udd_ctrl_underflow();
//! \brief Managed overflow event of OUT packet on control endpoint //! \brief Managed overflow event of OUT packet on control endpoint
static void udd_ctrl_overflow(void); static void udd_ctrl_overflow();
//! \brief Managed stall event of IN/OUT packet on control endpoint //! \brief Managed stall event of IN/OUT packet on control endpoint
static void udd_ctrl_stall_data(void); static void udd_ctrl_stall_data();
//! \brief Send a ZLP IN on control endpoint //! \brief Send a ZLP IN on control endpoint
static void udd_ctrl_send_zlp_in(void); static void udd_ctrl_send_zlp_in();
//! \brief Send a ZLP OUT on control endpoint //! \brief Send a ZLP OUT on control endpoint
static void udd_ctrl_send_zlp_out(void); static void udd_ctrl_send_zlp_out();
//! \brief Call callback associated to setup request //! \brief Call callback associated to setup request
static void udd_ctrl_endofrequest(void); static void udd_ctrl_endofrequest();
/** /**
@ -401,7 +401,7 @@ static void udd_ctrl_endofrequest(void);
* *
* \return \c 1 if an event about control endpoint is occured, otherwise \c 0. * \return \c 1 if an event about control endpoint is occured, otherwise \c 0.
*/ */
static bool udd_ctrl_interrupt(void); static bool udd_ctrl_interrupt();
//@} //@}
@ -448,10 +448,10 @@ typedef struct {
static udd_ep_job_t udd_ep_job[USB_DEVICE_MAX_EP]; static udd_ep_job_t udd_ep_job[USB_DEVICE_MAX_EP];
//! \brief Reset all job table //! \brief Reset all job table
static void udd_ep_job_table_reset(void); static void udd_ep_job_table_reset();
//! \brief Abort all endpoint jobs on going //! \brief Abort all endpoint jobs on going
static void udd_ep_job_table_kill(void); static void udd_ep_job_table_kill();
#ifdef UDD_EP_FIFO_SUPPORTED #ifdef UDD_EP_FIFO_SUPPORTED
/** /**
@ -500,7 +500,7 @@ static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_n
* *
* \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occured, otherwise \c 0. * \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occured, otherwise \c 0.
*/ */
static bool udd_ep_interrupt(void); static bool udd_ep_interrupt();
#endif // (0!=USB_DEVICE_MAX_EP) #endif // (0!=USB_DEVICE_MAX_EP)
//@} //@}
@ -524,8 +524,8 @@ static bool udd_ep_interrupt(void);
* See Technical reference $3.8.3 Masking interrupt requests in peripheral modules. * See Technical reference $3.8.3 Masking interrupt requests in peripheral modules.
*/ */
#ifdef UHD_ENABLE #ifdef UHD_ENABLE
void udd_interrupt(void); void udd_interrupt();
void udd_interrupt(void) void udd_interrupt()
#else #else
ISR(UDD_USB_INT_FUN) ISR(UDD_USB_INT_FUN)
#endif #endif
@ -643,13 +643,13 @@ udd_interrupt_sof_end:
} }
bool udd_include_vbus_monitoring(void) bool udd_include_vbus_monitoring()
{ {
return true; return true;
} }
void udd_enable(void) void udd_enable()
{ {
irqflags_t flags; irqflags_t flags;
@ -736,7 +736,7 @@ void udd_enable(void)
} }
void udd_disable(void) void udd_disable()
{ {
irqflags_t flags; irqflags_t flags;
@ -777,7 +777,7 @@ void udd_disable(void)
} }
void udd_attach(void) void udd_attach()
{ {
irqflags_t flags; irqflags_t flags;
flags = cpu_irq_save(); flags = cpu_irq_save();
@ -818,7 +818,7 @@ void udd_attach(void)
} }
void udd_detach(void) void udd_detach()
{ {
otg_unfreeze_clock(); otg_unfreeze_clock();
@ -829,7 +829,7 @@ void udd_detach(void)
} }
bool udd_is_high_speed(void) bool udd_is_high_speed()
{ {
#ifdef USB_DEVICE_HS_SUPPORT #ifdef USB_DEVICE_HS_SUPPORT
return !Is_udd_full_speed_mode(); return !Is_udd_full_speed_mode();
@ -847,23 +847,23 @@ void udd_set_address(uint8_t address)
} }
uint8_t udd_getaddress(void) uint8_t udd_getaddress()
{ {
return udd_get_configured_address(); return udd_get_configured_address();
} }
uint16_t udd_get_frame_number(void) uint16_t udd_get_frame_number()
{ {
return udd_frame_number(); return udd_frame_number();
} }
uint16_t udd_get_micro_frame_number(void) uint16_t udd_get_micro_frame_number()
{ {
return udd_micro_frame_number(); return udd_micro_frame_number();
} }
void udd_send_remotewakeup(void) void udd_send_remotewakeup()
{ {
#ifndef UDD_NO_SLEEP_MGR #ifndef UDD_NO_SLEEP_MGR
if (!udd_b_idle) if (!udd_b_idle)
@ -1242,27 +1242,27 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep,
#ifdef USB_DEVICE_HS_SUPPORT #ifdef USB_DEVICE_HS_SUPPORT
void udd_test_mode_j(void) void udd_test_mode_j()
{ {
udd_enable_hs_test_mode(); udd_enable_hs_test_mode();
udd_enable_hs_test_mode_j(); udd_enable_hs_test_mode_j();
} }
void udd_test_mode_k(void) void udd_test_mode_k()
{ {
udd_enable_hs_test_mode(); udd_enable_hs_test_mode();
udd_enable_hs_test_mode_k(); udd_enable_hs_test_mode_k();
} }
void udd_test_mode_se0_nak(void) void udd_test_mode_se0_nak()
{ {
udd_enable_hs_test_mode(); udd_enable_hs_test_mode();
} }
void udd_test_mode_packet(void) void udd_test_mode_packet()
{ {
uint8_t i; uint8_t i;
uint8_t *ptr_dest; uint8_t *ptr_dest;
@ -1310,7 +1310,7 @@ void udd_test_mode_packet(void)
// ------------------------ // ------------------------
//--- INTERNAL ROUTINES TO MANAGED THE CONTROL ENDPOINT //--- INTERNAL ROUTINES TO MANAGED THE CONTROL ENDPOINT
static void udd_reset_ep_ctrl(void) static void udd_reset_ep_ctrl()
{ {
irqflags_t flags; irqflags_t flags;
@ -1334,7 +1334,7 @@ static void udd_reset_ep_ctrl(void)
cpu_irq_restore(flags); cpu_irq_restore(flags);
} }
static void udd_ctrl_init(void) static void udd_ctrl_init()
{ {
irqflags_t flags; irqflags_t flags;
flags = cpu_irq_save(); flags = cpu_irq_save();
@ -1357,7 +1357,7 @@ static void udd_ctrl_init(void)
} }
static void udd_ctrl_setup_received(void) static void udd_ctrl_setup_received()
{ {
irqflags_t flags; irqflags_t flags;
uint8_t i; uint8_t i;
@ -1419,7 +1419,7 @@ static void udd_ctrl_setup_received(void)
} }
static void udd_ctrl_in_sent(void) static void udd_ctrl_in_sent()
{ {
static bool b_shortpacket = false; static bool b_shortpacket = false;
uint16_t nb_remain; uint16_t nb_remain;
@ -1503,7 +1503,7 @@ static void udd_ctrl_in_sent(void)
} }
static void udd_ctrl_out_received(void) static void udd_ctrl_out_received()
{ {
irqflags_t flags; irqflags_t flags;
uint8_t i; uint8_t i;
@ -1594,7 +1594,7 @@ static void udd_ctrl_out_received(void)
} }
static void udd_ctrl_underflow(void) static void udd_ctrl_underflow()
{ {
if (Is_udd_out_received(0)) if (Is_udd_out_received(0))
return; // Underflow ignored if OUT data is received return; // Underflow ignored if OUT data is received
@ -1611,7 +1611,7 @@ static void udd_ctrl_underflow(void)
} }
static void udd_ctrl_overflow(void) static void udd_ctrl_overflow()
{ {
if (Is_udd_in_send(0)) if (Is_udd_in_send(0))
return; // Overflow ignored if IN data is received return; // Overflow ignored if IN data is received
@ -1627,7 +1627,7 @@ static void udd_ctrl_overflow(void)
} }
static void udd_ctrl_stall_data(void) static void udd_ctrl_stall_data()
{ {
// Stall all packets on IN & OUT control endpoint // Stall all packets on IN & OUT control endpoint
udd_ep_control_state = UDD_EPCTRL_STALL_REQ; udd_ep_control_state = UDD_EPCTRL_STALL_REQ;
@ -1635,7 +1635,7 @@ static void udd_ctrl_stall_data(void)
} }
static void udd_ctrl_send_zlp_in(void) static void udd_ctrl_send_zlp_in()
{ {
irqflags_t flags; irqflags_t flags;
@ -1653,7 +1653,7 @@ static void udd_ctrl_send_zlp_in(void)
} }
static void udd_ctrl_send_zlp_out(void) static void udd_ctrl_send_zlp_out()
{ {
irqflags_t flags; irqflags_t flags;
@ -1669,7 +1669,7 @@ static void udd_ctrl_send_zlp_out(void)
} }
static void udd_ctrl_endofrequest(void) static void udd_ctrl_endofrequest()
{ {
// If a callback is registered then call it // If a callback is registered then call it
if (udd_g_ctrlreq.callback) { if (udd_g_ctrlreq.callback) {
@ -1678,7 +1678,7 @@ static void udd_ctrl_endofrequest(void)
} }
static bool udd_ctrl_interrupt(void) static bool udd_ctrl_interrupt()
{ {
if (!Is_udd_endpoint_interrupt(0)) { if (!Is_udd_endpoint_interrupt(0)) {
@ -1734,7 +1734,7 @@ static bool udd_ctrl_interrupt(void)
#if (0 != USB_DEVICE_MAX_EP) #if (0 != USB_DEVICE_MAX_EP)
static void udd_ep_job_table_reset(void) static void udd_ep_job_table_reset()
{ {
uint8_t i; uint8_t i;
for (i = 0; i < USB_DEVICE_MAX_EP; i++) { for (i = 0; i < USB_DEVICE_MAX_EP; i++) {
@ -1744,7 +1744,7 @@ static void udd_ep_job_table_reset(void)
} }
static void udd_ep_job_table_kill(void) static void udd_ep_job_table_kill()
{ {
uint8_t i; uint8_t i;
@ -1970,7 +1970,7 @@ static void udd_ep_out_received(udd_ep_id_t ep)
} }
#endif // #ifdef UDD_EP_FIFO_SUPPORTED #endif // #ifdef UDD_EP_FIFO_SUPPORTED
static bool udd_ep_interrupt(void) static bool udd_ep_interrupt()
{ {
udd_ep_id_t ep; udd_ep_id_t ep;
udd_ep_job_t *ptr_job; udd_ep_job_t *ptr_job;

View File

@ -66,13 +66,13 @@ extern "C" {
* *
* \return \c true if the ID pin management has been started, otherwise \c false. * \return \c true if the ID pin management has been started, otherwise \c false.
*/ */
bool otg_dual_enable(void); bool otg_dual_enable();
/** /**
* \brief Uninitialize the dual role * \brief Uninitialize the dual role
* This function is implemented in uotghs_host.c file. * This function is implemented in uotghs_host.c file.
*/ */
void otg_dual_disable(void); void otg_dual_disable();
//! @name UOTGHS OTG ID pin management //! @name UOTGHS OTG ID pin management

View File

@ -56,7 +56,7 @@
static volatile bool main_b_cdc_enable = false; static volatile bool main_b_cdc_enable = false;
static volatile bool main_b_dtr_active = false; static volatile bool main_b_dtr_active = false;
void usb_task_idle(void) { void usb_task_idle() {
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
// Attend SD card access from the USB MSD -- Prioritize access to improve speed // Attend SD card access from the USB MSD -- Prioritize access to improve speed
int delay = 2; int delay = 2;
@ -70,14 +70,14 @@ void usb_task_idle(void) {
} }
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
bool usb_task_msc_enable(void) { return ((main_b_msc_enable = true)); } bool usb_task_msc_enable() { return ((main_b_msc_enable = true)); }
void usb_task_msc_disable(void) { main_b_msc_enable = false; } void usb_task_msc_disable() { main_b_msc_enable = false; }
bool usb_task_msc_isenabled(void) { return main_b_msc_enable; } bool usb_task_msc_isenabled() { return main_b_msc_enable; }
#endif #endif
bool usb_task_cdc_enable(const uint8_t port) { UNUSED(port); return ((main_b_cdc_enable = true)); } 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; } 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; } bool usb_task_cdc_isenabled() { return main_b_cdc_enable; }
/*! \brief Called by CDC interface /*! \brief Called by CDC interface
* Callback running when CDC device have received data * Callback running when CDC device have received data
@ -121,7 +121,7 @@ void usb_task_cdc_set_dtr(const uint8_t port, const bool b_enable) {
} }
} }
bool usb_task_cdc_dtr_active(void) { return main_b_dtr_active; } bool usb_task_cdc_dtr_active() { return main_b_dtr_active; }
/// Microsoft WCID descriptor /// Microsoft WCID descriptor
typedef struct USB_MicrosoftCompatibleDescriptor_Interface { typedef struct USB_MicrosoftCompatibleDescriptor_Interface {
@ -202,7 +202,7 @@ static USB_MicrosoftExtendedPropertiesDescriptor microsoft_extended_properties_d
** WCID configuration information ** WCID configuration information
** Hooked into UDC via UDC_GET_EXTRA_STRING #define. ** Hooked into UDC via UDC_GET_EXTRA_STRING #define.
*/ */
bool usb_task_extra_string(void) { bool usb_task_extra_string() {
static uint8_t udi_msft_magic[] = "MSFT100\xEE"; static uint8_t udi_msft_magic[] = "MSFT100\xEE";
static uint8_t udi_cdc_name[] = "CDC interface"; static uint8_t udi_cdc_name[] = "CDC interface";
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
@ -262,7 +262,7 @@ bool usb_task_extra_string(void) {
/************************************************************************************************** /**************************************************************************************************
** Handle device requests that the ASF stack doesn't ** Handle device requests that the ASF stack doesn't
*/ */
bool usb_task_other_requests(void) { bool usb_task_other_requests() {
uint8_t* ptr = 0; uint8_t* ptr = 0;
uint16_t size = 0; uint16_t size = 0;
@ -297,7 +297,7 @@ bool usb_task_other_requests(void) {
return true; return true;
} }
void usb_task_init(void) { void usb_task_init() {
uint16_t *ptr; uint16_t *ptr;

View File

@ -58,12 +58,12 @@ extern "C" {
* *
* \retval true if MSC startup is ok * \retval true if MSC startup is ok
*/ */
bool usb_task_msc_enable(void); bool usb_task_msc_enable();
/*! \brief Called by MSC interface /*! \brief Called by MSC interface
* Callback running when USB Host disable MSC interface * Callback running when USB Host disable MSC interface
*/ */
void usb_task_msc_disable(void); void usb_task_msc_disable();
/*! \brief Opens the communication port /*! \brief Opens the communication port
* This is called by CDC interface when USB Host enable it. * This is called by CDC interface when USB Host enable it.
@ -84,25 +84,25 @@ 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 /*! \brief Check if MSC is enumerated and configured on the PC side
*/ */
bool usb_task_msc_isenabled(void); bool usb_task_msc_isenabled();
/*! \brief Check if CDC is enumerated and configured on the PC side /*! \brief Check if CDC is enumerated and configured on the PC side
*/ */
bool usb_task_cdc_isenabled(void); bool usb_task_cdc_isenabled();
/*! \brief Check if CDC is actually OPEN by an application on the PC side /*! \brief Check if CDC is actually OPEN by an application on the PC side
* assuming DTR signal means a program is listening to messages * assuming DTR signal means a program is listening to messages
*/ */
bool usb_task_cdc_dtr_active(void); bool usb_task_cdc_dtr_active();
/*! \brief Called by UDC when USB Host request a extra string different /*! \brief Called by UDC when USB Host request a extra string different
* of this specified in USB device descriptor * of this specified in USB device descriptor
*/ */
bool usb_task_extra_string(void); bool usb_task_extra_string();
/*! \brief Called by UDC when USB Host performs unknown requests /*! \brief Called by UDC when USB Host performs unknown requests
*/ */
bool usb_task_other_requests(void); bool usb_task_other_requests();
/*! \brief Called by CDC interface /*! \brief Called by CDC interface
* Callback running when CDC device have received data * Callback running when CDC device have received data
@ -117,15 +117,15 @@ void usb_task_cdc_config(const uint8_t port, usb_cdc_line_coding_t *cfg);
/*! \brief The USB device interrupt /*! \brief The USB device interrupt
*/ */
void USBD_ISR(void); void USBD_ISR();
/*! \brief USB task init /*! \brief USB task init
*/ */
void usb_task_init(void); void usb_task_init();
/*! \brief USB task idle /*! \brief USB task idle
*/ */
void usb_task_idle(void); void usb_task_idle();
#ifdef __cplusplus #ifdef __cplusplus
} }

View File

@ -32,7 +32,7 @@
// process, because watchdog initialization at hardware reset on SAM3X8E // process, because watchdog initialization at hardware reset on SAM3X8E
// is unreliable, and there is risk of unintended resets if we delay // is unreliable, and there is risk of unintended resets if we delay
// that initialization to a later time. // that initialization to a later time.
void watchdogSetup(void) { void watchdogSetup() {
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)
@ -106,7 +106,7 @@ void watchdogSetup(void) {
// Initialize watchdog - On SAM3X, Watchdog was already configured // Initialize watchdog - On SAM3X, Watchdog was already configured
// and enabled or disabled at startup, so no need to reconfigure it // and enabled or disabled at startup, so no need to reconfigure it
// here. // here.
void watchdog_init(void) { void watchdog_init() {
// Reset watchdog to start clean // Reset watchdog to start clean
WDT_Restart(WDT); WDT_Restart(WDT);
} }

View File

@ -29,7 +29,7 @@ class FlushableHardwareSerial : public HardwareSerial {
public: public:
FlushableHardwareSerial(int uart_nr); FlushableHardwareSerial(int uart_nr);
inline void flushTX(void) { /* No need to flush the hardware serial, but defined here for compatibility. */ } inline void flushTX() { /* No need to flush the hardware serial, but defined here for compatibility. */ }
}; };
extern FlushableHardwareSerial flushableSerial; extern FlushableHardwareSerial flushableSerial;

View File

@ -78,11 +78,11 @@ volatile int numPWMUsed = 0,
// Public functions // Public functions
// ------------------------ // ------------------------
void HAL_init(void) { void HAL_init() {
i2s_init(); i2s_init();
} }
void HAL_init_board(void) { void HAL_init_board() {
#if EITHER(EEPROM_SETTINGS, WEBSUPPORT) #if EITHER(EEPROM_SETTINGS, WEBSUPPORT)
spiffs_init(); spiffs_init();
#endif #endif
@ -99,15 +99,15 @@ void HAL_init_board(void) {
#endif #endif
} }
void HAL_idletask(void) { void HAL_idletask() {
#if ENABLED(OTASUPPORT) #if ENABLED(OTASUPPORT)
OTA_handle(); OTA_handle();
#endif #endif
} }
void HAL_clear_reset_source(void) { } void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source(void) { return rtc_get_reset_reason(1); } uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); }
void _delay_ms(int delay_ms) { delay(delay_ms); } void _delay_ms(int delay_ms) { delay(delay_ms); }

View File

@ -85,16 +85,16 @@ extern uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// clear reset reason // clear reset reason
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
// reset reason // reset reason
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();
void _delay_ms(int delay); void _delay_ms(int delay);
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory(void); int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
void analogWrite(pin_t pin, int value); void analogWrite(pin_t pin, int value);
@ -108,7 +108,7 @@ void eeprom_update_block (const void *__src, void *__dst, size_t __n);
// ADC // ADC
#define HAL_ANALOG_SELECT(pin) #define HAL_ANALOG_SELECT(pin)
void HAL_adc_init(void); void HAL_adc_init();
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
@ -123,6 +123,6 @@ void HAL_adc_start_conversion(uint8_t adc_pin);
// Enable hooks into idle and setup for HAL // Enable hooks into idle and setup for HAL
#define HAL_IDLETASK 1 #define HAL_IDLETASK 1
#define BOARD_INIT() HAL_init_board(); #define BOARD_INIT() HAL_init_board();
void HAL_idletask(void); void HAL_idletask();
void HAL_init(void); void HAL_init();
void HAL_init_board(void); void HAL_init_board();

View File

@ -80,7 +80,7 @@ void spiInit(uint8_t spiRate) {
SPI.begin(); SPI.begin();
} }
uint8_t spiRec(void) { uint8_t spiRec() {
SPI.beginTransaction(spiConfig); SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF); uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction(); SPI.endTransaction();

View File

@ -66,15 +66,15 @@ ring_buffer_pos_t RingBuffer::write(const uint8_t *buffer, ring_buffer_pos_t siz
return written; return written;
} }
int RingBuffer::available(void) { int RingBuffer::available() {
return (size - read_index + write_index) & (size - 1); return (size - read_index + write_index) & (size - 1);
} }
int RingBuffer::peek(void) { int RingBuffer::peek() {
return available() ? data[read_index] : -1; return available() ? data[read_index] : -1;
} }
int RingBuffer::read(void) { int RingBuffer::read() {
if (available()) { if (available()) {
const int ret = data[read_index]; const int ret = data[read_index];
read_index = NEXT_INDEX(read_index, size); read_index = NEXT_INDEX(read_index, size);
@ -94,7 +94,7 @@ ring_buffer_pos_t RingBuffer::read(uint8_t *buffer) {
return len; return len;
} }
void RingBuffer::flush(void) { read_index = write_index; } void RingBuffer::flush() { read_index = write_index; }
// WebSocketSerial impl // WebSocketSerial impl
WebSocketSerial::WebSocketSerial() WebSocketSerial::WebSocketSerial()
@ -120,10 +120,10 @@ void WebSocketSerial::begin(const long baud_setting) {
} }
void WebSocketSerial::end() { } void WebSocketSerial::end() { }
int WebSocketSerial::peek(void) { return rx_buffer.peek(); } int WebSocketSerial::peek() { return rx_buffer.peek(); }
int WebSocketSerial::read(void) { return rx_buffer.read(); } int WebSocketSerial::read() { return rx_buffer.read(); }
int WebSocketSerial::available(void) { return rx_buffer.available(); } int WebSocketSerial::available() { return rx_buffer.available(); }
void WebSocketSerial::flush(void) { rx_buffer.flush(); } void WebSocketSerial::flush() { rx_buffer.flush(); }
size_t WebSocketSerial::write(const uint8_t c) { size_t WebSocketSerial::write(const uint8_t c) {
size_t ret = tx_buffer.write(c); size_t ret = tx_buffer.write(c);
@ -145,7 +145,7 @@ size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) {
return written; return written;
} }
void WebSocketSerial::flushTX(void) { void WebSocketSerial::flushTX() {
// No need to do anything as there's no benefit to sending partial lines over the websocket connection. // No need to do anything as there's no benefit to sending partial lines over the websocket connection.
} }

View File

@ -45,11 +45,11 @@ public:
RingBuffer(ring_buffer_pos_t size); RingBuffer(ring_buffer_pos_t size);
~RingBuffer(); ~RingBuffer();
int available(void); int available();
int peek(void); int peek();
int read(void); int read();
ring_buffer_pos_t read(uint8_t *buffer); ring_buffer_pos_t read(uint8_t *buffer);
void flush(void); void flush();
ring_buffer_pos_t write(const uint8_t c); ring_buffer_pos_t write(const uint8_t c);
ring_buffer_pos_t write(const uint8_t* buffer, ring_buffer_pos_t size); ring_buffer_pos_t write(const uint8_t* buffer, ring_buffer_pos_t size);
}; };
@ -62,11 +62,11 @@ public:
WebSocketSerial(); WebSocketSerial();
void begin(const long); void begin(const long);
void end(); void end();
int available(void); int available();
int peek(void); int peek();
int read(void); int read();
void flush(void); void flush();
void flushTX(void); void flushTX();
size_t write(const uint8_t c); size_t write(const uint8_t c);
size_t write(const uint8_t* buffer, size_t size); size_t write(const uint8_t* buffer, size_t size);

View File

@ -38,9 +38,9 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void ICACHE_RAM_ATTR endstop_ISR(void) { endstops.update(); } void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#if HAS_X_MAX #if HAS_X_MAX
_ATTACH(X_MAX_PIN); _ATTACH(X_MAX_PIN);

View File

@ -79,13 +79,13 @@ typedef uint64_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler(void) #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler(void) #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
#define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler(void) #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
extern "C" void tempTC_Handler(void); extern "C" void tempTC_Handler();
extern "C" void stepTC_Handler(void); extern "C" void stepTC_Handler();
extern "C" void pwmTC_Handler(void); extern "C" void pwmTC_Handler();
// ------------------------ // ------------------------
// Types // Types
@ -95,7 +95,7 @@ typedef struct {
timer_group_t group; timer_group_t group;
timer_idx_t idx; timer_idx_t idx;
uint32_t divider; uint32_t divider;
void (*fn)(void); void (*fn)();
} tTimerConfig; } tTimerConfig;
// ------------------------ // ------------------------

View File

@ -28,11 +28,11 @@
#include "watchdog.h" #include "watchdog.h"
void watchdogSetup(void) { void watchdogSetup() {
// do whatever. don't remove this function. // do whatever. don't remove this function.
} }
void watchdog_init(void) { void watchdog_init() {
// TODO // TODO
} }

View File

@ -31,10 +31,10 @@ HalSerial usb_serial;
extern "C" void u8g_xMicroDelay(uint16_t val) { extern "C" void u8g_xMicroDelay(uint16_t val) {
DELAY_US(val); DELAY_US(val);
} }
extern "C" void u8g_MicroDelay(void) { extern "C" void u8g_MicroDelay() {
u8g_xMicroDelay(1); u8g_xMicroDelay(1);
} }
extern "C" void u8g_10MicroDelay(void) { extern "C" void u8g_10MicroDelay() {
u8g_xMicroDelay(10); u8g_xMicroDelay(10);
} }
extern "C" void u8g_Delay(uint16_t val) { extern "C" void u8g_Delay(uint16_t val) {
@ -51,7 +51,7 @@ int freeMemory() {
// ADC // ADC
// ------------------------ // ------------------------
void HAL_adc_init(void) { void HAL_adc_init() {
} }
@ -64,18 +64,18 @@ void HAL_adc_start_conversion(const uint8_t ch) {
active_ch = ch; active_ch = ch;
} }
bool HAL_adc_finished(void) { bool HAL_adc_finished() {
return true; return true;
} }
uint16_t HAL_adc_get_result(void) { uint16_t HAL_adc_get_result() {
pin_t pin = analogInputToDigitalPin(active_ch); pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0; if (!VALID_PIN(pin)) return 0;
uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
return data; // return 10bit value as Marlin expects return data; // return 10bit value as Marlin expects
} }
void HAL_pwm_init(void) { void HAL_pwm_init() {
} }

View File

@ -78,12 +78,12 @@ extern HalSerial usb_serial;
#define ENABLE_ISRS() #define ENABLE_ISRS()
#define DISABLE_ISRS() #define DISABLE_ISRS()
inline void HAL_init(void) { } inline void HAL_init() { }
// Utility functions // Utility functions
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory(void); int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// ADC // ADC
@ -92,10 +92,10 @@ int freeMemory(void);
#define HAL_READ_ADC() HAL_adc_get_result() #define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true #define HAL_ADC_READY() true
void HAL_adc_init(void); void HAL_adc_init();
void HAL_adc_enable_channel(int pin); void HAL_adc_enable_channel(int pin);
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
/* ---------------- Delay in cycles */ /* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {

View File

@ -28,8 +28,8 @@
#include "../shared/Delay.h" #include "../shared/Delay.h"
// Interrupts // Interrupts
void cli(void) { } // Disable void cli() { } // Disable
void sei(void) { } // Enable void sei() { } // Enable
// Time functions // Time functions
void _delay_ms(const int delay_ms) { void _delay_ms(const int delay_ms) {

View File

@ -63,9 +63,9 @@ typedef uint8_t byte;
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
//Interrupts //Interrupts
void cli(void); // Disable void cli(); // Disable
void sei(void); // Enable void sei(); // Enable
void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode); void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode);
void detachInterrupt(uint32_t pin); void detachInterrupt(uint32_t pin);
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin); extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);

View File

@ -108,11 +108,11 @@ public:
void flush() { receive_buffer.clear(); } void flush() { receive_buffer.clear(); }
uint8_t availableForWrite(void) { uint8_t availableForWrite() {
return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free(); return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
} }
void flushTX(void) { void flushTX() {
if (host_connected) if (host_connected)
while (transmit_buffer.available()) { /* nada */ } while (transmit_buffer.available()) { /* nada */ }
} }
@ -200,7 +200,7 @@ public:
void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); } void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); }
void println(float value, int round = 6) { printf("%f\n" , value); } void println(float value, int round = 6) { printf("%f\n" , value); }
void println(double value, int round = 6) { printf("%f\n" , value); } void println(double value, int round = 6) { printf("%f\n" , value); }
void println(void) { print('\n'); } void println() { print('\n'); }
volatile RingBuffer<uint8_t, 128> receive_buffer; volatile RingBuffer<uint8_t, 128> receive_buffer;
volatile RingBuffer<uint8_t, 128> transmit_buffer; volatile RingBuffer<uint8_t, 128> transmit_buffer;

View File

@ -104,7 +104,7 @@ void simulation_loop() {
} }
} }
int main(void) { int main() {
std::thread write_serial (write_serial_thread); std::thread write_serial (write_serial_thread);
std::thread read_serial (read_serial_thread); std::thread read_serial (read_serial_thread);

View File

@ -37,7 +37,7 @@ HAL_TEMP_TIMER_ISR();
Timer timers[2]; Timer timers[2];
void HAL_timer_init(void) { void HAL_timer_init() {
timers[0].init(0, STEPPER_TIMER_RATE, TIMER0_IRQHandler); timers[0].init(0, STEPPER_TIMER_RATE, TIMER0_IRQHandler);
timers[1].init(1, TEMP_TIMER_RATE, TIMER1_IRQHandler); timers[1].init(1, TEMP_TIMER_RATE, TIMER1_IRQHandler);
} }

View File

@ -59,16 +59,16 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
#define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler(void) #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler()
#define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler(void) #define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler()
// PWM timer // PWM timer
#define HAL_PWM_TIMER #define HAL_PWM_TIMER
#define HAL_PWM_TIMER_ISR() extern "C" void TIMER3_IRQHandler(void) #define HAL_PWM_TIMER_ISR() extern "C" void TIMER3_IRQHandler()
#define HAL_PWM_TIMER_IRQn #define HAL_PWM_TIMER_IRQn
void HAL_timer_init(void); void HAL_timer_init();
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare); void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare);

View File

@ -28,19 +28,19 @@
#include "watchdog.h" #include "watchdog.h"
void watchdog_init(void) {} void watchdog_init() {}
void HAL_clear_reset_source(void) {} void HAL_clear_reset_source() {}
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
return RST_POWER_ON; return RST_POWER_ON;
} }
void watchdog_reset() {} void watchdog_reset() {}
#else #else
void HAL_clear_reset_source(void) {} void HAL_clear_reset_source() {}
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
#endif // USE_WATCHDOG #endif // USE_WATCHDOG
#endif // __PLAT_LINUX__ #endif // __PLAT_LINUX__

View File

@ -23,7 +23,7 @@
#define WDT_TIMEOUT 4000000 // 4 second timeout #define WDT_TIMEOUT 4000000 // 4 second timeout
void watchdog_init(void); void watchdog_init();
void watchdog_reset(void); void watchdog_reset();
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();

View File

@ -44,7 +44,7 @@
#define sw_barrier() __asm__ volatile("": : :"memory"); #define sw_barrier() __asm__ volatile("": : :"memory");
// (re)initialize UART0 as a monitor output to 250000,n,8,1 // (re)initialize UART0 as a monitor output to 250000,n,8,1
static void TXBegin(void) { static void TXBegin() {
} }
// Send character through UART with no interrupts // Send character through UART with no interrupts
@ -210,7 +210,7 @@ void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause
} }
extern "C" { extern "C" {
__attribute__((naked)) void NMI_Handler(void) { __attribute__((naked)) void NMI_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -223,7 +223,7 @@ __attribute__((naked)) void NMI_Handler(void) {
); );
} }
__attribute__((naked)) void HardFault_Handler(void) { __attribute__((naked)) void HardFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -236,7 +236,7 @@ __attribute__((naked)) void HardFault_Handler(void) {
); );
} }
__attribute__((naked)) void MemManage_Handler(void) { __attribute__((naked)) void MemManage_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -249,7 +249,7 @@ __attribute__((naked)) void MemManage_Handler(void) {
); );
} }
__attribute__((naked)) void BusFault_Handler(void) { __attribute__((naked)) void BusFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -262,7 +262,7 @@ __attribute__((naked)) void BusFault_Handler(void) {
); );
} }
__attribute__((naked)) void UsageFault_Handler(void) { __attribute__((naked)) void UsageFault_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -275,7 +275,7 @@ __attribute__((naked)) void UsageFault_Handler(void) {
); );
} }
__attribute__((naked)) void DebugMon_Handler(void) { __attribute__((naked)) void DebugMon_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -289,7 +289,7 @@ __attribute__((naked)) void DebugMon_Handler(void) {
} }
/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */ /* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
__attribute__((naked)) void WDT_IRQHandler(void) { __attribute__((naked)) void WDT_IRQHandler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")
@ -302,7 +302,7 @@ __attribute__((naked)) void WDT_IRQHandler(void) {
); );
} }
__attribute__((naked)) void RSTC_Handler(void) { __attribute__((naked)) void RSTC_Handler() {
__asm__ __volatile__ ( __asm__ __volatile__ (
".syntax unified" "\n\t" ".syntax unified" "\n\t"
A("tst lr, #4") A("tst lr, #4")

View File

@ -30,10 +30,10 @@
extern "C" void u8g_xMicroDelay(uint16_t val) { extern "C" void u8g_xMicroDelay(uint16_t val) {
DELAY_US(val); DELAY_US(val);
} }
extern "C" void u8g_MicroDelay(void) { extern "C" void u8g_MicroDelay() {
u8g_xMicroDelay(1); u8g_xMicroDelay(1);
} }
extern "C" void u8g_10MicroDelay(void) { extern "C" void u8g_10MicroDelay() {
u8g_xMicroDelay(10); u8g_xMicroDelay(10);
} }
extern "C" void u8g_Delay(uint16_t val) { extern "C" void u8g_Delay(uint16_t val) {

View File

@ -28,7 +28,7 @@
#define CPU_32_BIT #define CPU_32_BIT
void HAL_init(void); void HAL_init();
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
@ -113,7 +113,7 @@ extern "C" volatile uint32_t _millis;
// //
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory(void); int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// //
@ -144,7 +144,7 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09 #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
#define HAL_IDLETASK 1 #define HAL_IDLETASK 1
void HAL_idletask(void); void HAL_idletask();
#define PLATFORM_M997_SUPPORT #define PLATFORM_M997_SUPPORT
void flashFirmware(int16_t value); void flashFirmware(int16_t value);

View File

@ -27,28 +27,28 @@
#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) #if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0)
MarlinSerial MSerial(LPC_UART0); MarlinSerial MSerial(LPC_UART0);
extern "C" void UART0_IRQHandler(void) { extern "C" void UART0_IRQHandler() {
MSerial.IRQHandler(); MSerial.IRQHandler();
} }
#endif #endif
#if (defined(SERIAL_PORT) && SERIAL_PORT == 1) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 1) #if (defined(SERIAL_PORT) && SERIAL_PORT == 1) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 1)
MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1); MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
extern "C" void UART1_IRQHandler(void) { extern "C" void UART1_IRQHandler() {
MSerial1.IRQHandler(); MSerial1.IRQHandler();
} }
#endif #endif
#if (defined(SERIAL_PORT) && SERIAL_PORT == 2) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 2) #if (defined(SERIAL_PORT) && SERIAL_PORT == 2) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 2)
MarlinSerial MSerial2(LPC_UART2); MarlinSerial MSerial2(LPC_UART2);
extern "C" void UART2_IRQHandler(void) { extern "C" void UART2_IRQHandler() {
MSerial2.IRQHandler(); MSerial2.IRQHandler();
} }
#endif #endif
#if (defined(SERIAL_PORT) && SERIAL_PORT == 3) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 3) #if (defined(SERIAL_PORT) && SERIAL_PORT == 3) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 3)
MarlinSerial MSerial3(LPC_UART3); MarlinSerial MSerial3(LPC_UART3);
extern "C" void UART3_IRQHandler(void) { extern "C" void UART3_IRQHandler() {
MSerial3.IRQHandler(); MSerial3.IRQHandler();
} }
#endif #endif

View File

@ -38,9 +38,9 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#if HAS_X_MAX #if HAS_X_MAX
#if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN) #if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN)

View File

@ -89,7 +89,7 @@ uint8_t digipot_mcp4451_start(uint8_t sla) { // send slave address and write bi
return 1; return 1;
} }
void digipot_mcp4451_init(void) { void digipot_mcp4451_init() {
/** /**
* Init I2C pin connect * Init I2C pin connect
*/ */

View File

@ -45,7 +45,7 @@
#include <lpc17xx_libcfg_default.h> #include <lpc17xx_libcfg_default.h>
uint8_t digipot_mcp4451_start(uint8_t sla); uint8_t digipot_mcp4451_start(uint8_t sla);
void digipot_mcp4451_init(void); void digipot_mcp4451_init();
uint8_t digipot_mcp4451_send_byte(uint8_t data); uint8_t digipot_mcp4451_send_byte(uint8_t data);
#ifdef __cplusplus #ifdef __cplusplus

View File

@ -42,11 +42,11 @@ extern "C" {
extern uint32_t MSC_SD_Init(uint8_t pdrv); extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern "C" int isLPC1769(); extern "C" int isLPC1769();
extern "C" void disk_timerproc(void); extern "C" void disk_timerproc();
void SysTick_Callback() { disk_timerproc(); } void SysTick_Callback() { disk_timerproc(); }
void HAL_init(void) { void HAL_init() {
// Init LEDs // Init LEDs
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
@ -149,7 +149,7 @@ void HAL_init(void) {
} }
// HAL idle task // HAL idle task
void HAL_idletask(void) { void HAL_idletask() {
#if ENABLED(SHARED_SD_CARD) #if ENABLED(SHARED_SD_CARD)
// If Marlin is using the SD card we need to lock it to prevent access from // If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB. // a PC via USB.

View File

@ -31,7 +31,7 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include "timers.h" #include "timers.h"
void HAL_timer_init(void) { void HAL_timer_init() {
SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0 SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0
LPC_TIM0->PR = (HAL_TIMER_RATE) / (STEPPER_TIMER_RATE) - 1; // Use prescaler to set frequency if needed LPC_TIM0->PR = (HAL_TIMER_RATE) / (STEPPER_TIMER_RATE) - 1; // Use prescaler to set frequency if needed

View File

@ -53,7 +53,7 @@
#define _HAL_TIMER(T) _CAT(LPC_TIM, T) #define _HAL_TIMER(T) _CAT(LPC_TIM, T)
#define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn #define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn
#define __HAL_TIMER_ISR(T) extern "C" void TIMER##T##_IRQHandler(void) #define __HAL_TIMER_ISR(T) extern "C" void TIMER##T##_IRQHandler()
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) #define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
typedef uint32_t hal_timer_t; typedef uint32_t hal_timer_t;
@ -94,7 +94,7 @@ typedef uint32_t hal_timer_t;
// ------------------------ // ------------------------
// Public functions // Public functions
// ------------------------ // ------------------------
void HAL_timer_init(void); void HAL_timer_init();
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); 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) { FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {

View File

@ -163,7 +163,7 @@ uint8_t u8g_i2c_send_byte(uint8_t data) {
return 1; return 1;
} }
void u8g_i2c_stop(void) { void u8g_i2c_stop() {
} }

View File

@ -25,4 +25,4 @@ void u8g_i2c_init(uint8_t options);
uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos); uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos);
uint8_t u8g_i2c_start(uint8_t sla); uint8_t u8g_i2c_start(uint8_t sla);
uint8_t u8g_i2c_send_byte(uint8_t data); uint8_t u8g_i2c_send_byte(uint8_t data);
void u8g_i2c_stop(void); void u8g_i2c_stop();

View File

@ -35,8 +35,8 @@
#endif #endif
void U8g_delay(int msec); void U8g_delay(int msec);
void u8g_MicroDelay(void); void u8g_MicroDelay();
void u8g_10MicroDelay(void); void u8g_10MicroDelay();
#ifdef __cplusplus #ifdef __cplusplus
} }

View File

@ -138,7 +138,7 @@ uint8_t u8g_i2c_start_sw(uint8_t sla) { // assert start condition and then send
} }
void u8g_i2c_stop_sw(void) { } void u8g_i2c_stop_sw() { }
void u8g_i2c_init_sw(uint8_t clock_option) { u8g_i2c_start(0); } // send slave address and write bit void u8g_i2c_init_sw(uint8_t clock_option) { u8g_i2c_start(0); } // send slave address and write bit

View File

@ -29,7 +29,7 @@
#include "lpc17xx_wdt.h" #include "lpc17xx_wdt.h"
#include "watchdog.h" #include "watchdog.h"
void watchdog_init(void) { void watchdog_init() {
#if ENABLED(WATCHDOG_RESET_MANUAL) #if ENABLED(WATCHDOG_RESET_MANUAL)
// We enable the watchdog timer, but only for the interrupt. // We enable the watchdog timer, but only for the interrupt.
@ -56,11 +56,11 @@ void watchdog_init(void) {
WDT_Start(WDT_TIMEOUT); WDT_Start(WDT_TIMEOUT);
} }
void HAL_clear_reset_source(void) { void HAL_clear_reset_source() {
WDT_ClrTimeOutFlag(); WDT_ClrTimeOutFlag();
} }
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
if (TEST(WDT_ReadTimeOutFlag(), 0)) return RST_WATCHDOG; if (TEST(WDT_ReadTimeOutFlag(), 0)) return RST_WATCHDOG;
return RST_POWER_ON; return RST_POWER_ON;
} }
@ -74,10 +74,10 @@ void watchdog_reset() {
#else #else
void watchdog_init(void) {} void watchdog_init() {}
void watchdog_reset(void) {} void watchdog_reset() {}
void HAL_clear_reset_source(void) {} void HAL_clear_reset_source() {}
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
#endif // USE_WATCHDOG #endif // USE_WATCHDOG

View File

@ -23,7 +23,7 @@
#define WDT_TIMEOUT 4000000 // 4 second timeout #define WDT_TIMEOUT 4000000 // 4 second timeout
void watchdog_init(void); void watchdog_init();
void watchdog_reset(void); void watchdog_reset();
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();

View File

@ -368,7 +368,7 @@ uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// HAL initialization task // HAL initialization task
void HAL_init(void) { void HAL_init() {
#if DMA_IS_REQUIRED #if DMA_IS_REQUIRED
dma_init(); dma_init();
#endif #endif
@ -383,15 +383,15 @@ void HAL_init(void) {
// HAL idle task // HAL idle task
/* /*
void HAL_idletask(void) { void HAL_idletask() {
} }
*/ */
void HAL_clear_reset_source(void) { } void HAL_clear_reset_source() { }
#pragma push_macro("WDT") #pragma push_macro("WDT")
#undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
RSTC_RCAUSE_Type resetCause; RSTC_RCAUSE_Type resetCause;
resetCause.reg = REG_RSTC_RCAUSE; resetCause.reg = REG_RSTC_RCAUSE;
@ -421,7 +421,7 @@ int freeMemory() {
// ADC // ADC
// ------------------------ // ------------------------
void HAL_adc_init(void) { void HAL_adc_init() {
#if ADC_IS_REQUIRED #if ADC_IS_REQUIRED
memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values
@ -469,7 +469,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = 0xFFFF; HAL_adc_result = 0xFFFF;
} }
uint16_t HAL_adc_get_result(void) { uint16_t HAL_adc_get_result() {
return HAL_adc_result; return HAL_adc_result;
} }

View File

@ -91,8 +91,8 @@ typedef int8_t pin_t;
#define cli() __disable_irq() // Disable interrupts #define cli() __disable_irq() // Disable interrupts
#define sei() __enable_irq() // Enable interrupts #define sei() __enable_irq() // Enable interrupts
void HAL_clear_reset_source(void); // clear reset reason void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(void); // get reset reason uint8_t HAL_get_reset_source(); // get reset reason
// //
// EEPROM // EEPROM
@ -107,14 +107,14 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion
#define HAL_ANALOG_SELECT(pin) #define HAL_ANALOG_SELECT(pin)
void HAL_adc_init(void); void HAL_adc_init();
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true #define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
// //
// Pin Map // Pin Map
@ -131,10 +131,10 @@ void tone(const pin_t _pin, const unsigned int frequency, const unsigned long du
void noTone(const pin_t _pin); void noTone(const pin_t _pin);
// Enable hooks into idle and setup for HAL // Enable hooks into idle and setup for HAL
void HAL_init(void); void HAL_init();
/* /*
#define HAL_IDLETASK 1 #define HAL_IDLETASK 1
void HAL_idletask(void); void HAL_idletask();
*/ */
// //
@ -144,7 +144,7 @@ FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory(void); int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
#ifdef __cplusplus #ifdef __cplusplus

View File

@ -64,7 +64,7 @@
// ------------------------ // ------------------------
// Hardware SPI // Hardware SPI
// ------------------------ // ------------------------
void spiBegin(void) { void spiBegin() {
spiInit(SPI_HALF_SPEED); spiInit(SPI_HALF_SPEED);
} }
@ -92,7 +92,7 @@
* *
* @details * @details
*/ */
uint8_t spiRec(void) { uint8_t spiRec() {
sdSPI.beginTransaction(spiConfig); sdSPI.beginTransaction(spiConfig);
uint8_t returnByte = sdSPI.transfer(0xFF); uint8_t returnByte = sdSPI.transfer(0xFF);
sdSPI.endTransaction(); sdSPI.endTransaction();

View File

@ -112,9 +112,9 @@
&& !MATCH_Z_MIN_PROBE_EILINE(P)) && !MATCH_Z_MIN_PROBE_EILINE(P))
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#if HAS_X_MAX #if HAS_X_MAX
#if !AVAILABLE_EILINE(X_MAX_PIN) #if !AVAILABLE_EILINE(X_MAX_PIN)
static_assert(false, "X_MAX_PIN has no EXTINT line available."); static_assert(false, "X_MAX_PIN has no EXTINT line available.");

View File

@ -27,7 +27,7 @@
#include "watchdog.h" #include "watchdog.h"
void watchdog_init(void) { void watchdog_init() {
// The low-power oscillator used by the WDT runs at 32,768 Hz with // The low-power oscillator used by the WDT runs at 32,768 Hz with
// a 1:32 prescale, thus 1024 Hz, though probably not super precise. // a 1:32 prescale, thus 1024 Hz, though probably not super precise.

View File

@ -60,7 +60,7 @@ uint16_t HAL_adc_result;
#endif #endif
// HAL initialization task // HAL initialization task
void HAL_init(void) { void HAL_init() {
FastIO_init(); FastIO_init();
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
@ -84,9 +84,9 @@ void HAL_init(void) {
#endif // EEPROM_EMULATED_SRAM #endif // EEPROM_EMULATED_SRAM
} }
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG; if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE; if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL; if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
@ -108,7 +108,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = analogRead(adc_pin); HAL_adc_result = analogRead(adc_pin);
} }
uint16_t HAL_adc_get_result(void) { uint16_t HAL_adc_get_result() {
return HAL_adc_result; return HAL_adc_result;
} }

View File

@ -147,13 +147,13 @@ extern uint16_t HAL_adc_result;
#define __bss_end __bss_end__ #define __bss_end __bss_end__
// Enable hooks into setup for HAL // Enable hooks into setup for HAL
void HAL_init(void); void HAL_init();
// Clear reset reason // Clear reset reason
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
// Reset reason // Reset reason
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();
void _delay_ms(const int delay); void _delay_ms(const int delay);
@ -185,7 +185,7 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n);
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
inline void HAL_adc_init(void) {} inline void HAL_adc_init() {}
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
@ -193,7 +193,7 @@ inline void HAL_adc_init(void) {}
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin

View File

@ -59,7 +59,7 @@ static SPISettings spiConfig;
* *
* @details Only configures SS pin since stm32duino creates and initialize the SPI object * @details Only configures SS pin since stm32duino creates and initialize the SPI object
*/ */
void spiBegin(void) { void spiBegin() {
#if !PIN_EXISTS(SS) #if !PIN_EXISTS(SS)
#error "SS_PIN not defined!" #error "SS_PIN not defined!"
#endif #endif
@ -93,7 +93,7 @@ void spiInit(uint8_t spiRate) {
* *
* @details * @details
*/ */
uint8_t spiRec(void) { uint8_t spiRec() {
SPI.beginTransaction(spiConfig); SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF); uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction(); SPI.endTransaction();

View File

@ -25,9 +25,9 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#if HAS_X_MAX #if HAS_X_MAX
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif

View File

@ -201,16 +201,16 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
#if SERIAL_PORT > 0 #if SERIAL_PORT > 0
#if SERIAL_PORT2 #if SERIAL_PORT2
#if SERIAL_PORT2 > 0 #if SERIAL_PORT2 > 0
void board_setup_usb(void) {} void board_setup_usb() {}
#endif #endif
#else #else
void board_setup_usb(void) {} void board_setup_usb() {}
#endif #endif
#endif #endif
} } } }
#endif #endif
void HAL_init(void) { void HAL_init() {
NVIC_SetPriorityGrouping(0x3); NVIC_SetPriorityGrouping(0x3);
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW); OUT_WRITE(LED_PIN, LOW);
@ -226,7 +226,7 @@ void HAL_init(void) {
} }
// HAL idle task // HAL idle task
void HAL_idletask(void) { void HAL_idletask() {
#ifdef USE_USB_COMPOSITE #ifdef USE_USB_COMPOSITE
#if ENABLED(SHARED_SD_CARD) #if ENABLED(SHARED_SD_CARD)
// If Marlin is using the SD card we need to lock it to prevent access from // If Marlin is using the SD card we need to lock it to prevent access from
@ -245,19 +245,19 @@ void HAL_idletask(void) {
/* VGPV Done with defines /* VGPV Done with defines
// disable interrupts // disable interrupts
void cli(void) { noInterrupts(); } void cli() { noInterrupts(); }
// enable interrupts // enable interrupts
void sei(void) { interrupts(); } void sei() { interrupts(); }
*/ */
void HAL_clear_reset_source(void) { } void HAL_clear_reset_source() { }
/** /**
* TODO: Check this and change or remove. * TODO: Check this and change or remove.
* currently returns 1 that's equal to poweron reset. * currently returns 1 that's equal to poweron reset.
*/ */
uint8_t HAL_get_reset_source(void) { return 1; } uint8_t HAL_get_reset_source() { return 1; }
void _delay_ms(const int delay_ms) { delay(delay_ms); } void _delay_ms(const int delay_ms) { delay(delay_ms); }
@ -297,7 +297,7 @@ extern "C" {
// ADC // ADC
// ------------------------ // ------------------------
// Init the AD in continuous capture mode // Init the AD in continuous capture mode
void HAL_adc_init(void) { void HAL_adc_init() {
// configure the ADC // configure the ADC
adc.calibrate(); adc.calibrate();
#if F_CPU > 72000000 #if F_CPU > 72000000
@ -356,7 +356,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only. HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
} }
uint16_t HAL_adc_get_result(void) { return HAL_adc_result; } uint16_t HAL_adc_get_result() { return HAL_adc_result; }
uint16_t analogRead(pin_t pin) { uint16_t analogRead(pin_t pin) {
const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;

View File

@ -116,9 +116,9 @@
#endif #endif
// Set interrupt grouping for this MCU // Set interrupt grouping for this MCU
void HAL_init(void); void HAL_init();
#define HAL_IDLETASK 1 #define HAL_IDLETASK 1
void HAL_idletask(void); void HAL_idletask();
/** /**
* TODO: review this to return 1 for pins that are not analog input * TODO: review this to return 1 for pins that are not analog input
@ -183,10 +183,10 @@ extern uint16_t HAL_adc_result;
#define __bss_end __bss_end__ #define __bss_end __bss_end__
// Clear reset reason // Clear reset reason
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
// Reset reason // Reset reason
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();
void _delay_ms(const int delay); void _delay_ms(const int delay);
@ -195,7 +195,7 @@ void _delay_ms(const int delay);
/* /*
extern "C" { extern "C" {
int freeMemory(void); int freeMemory();
} }
*/ */
@ -235,14 +235,14 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n);
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG);
void HAL_adc_init(void); void HAL_adc_init();
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true #define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?

View File

@ -112,7 +112,7 @@ void spiInit(uint8_t spiRate) {
* *
* @details * @details
*/ */
uint8_t spiRec(void) { uint8_t spiRec() {
uint8_t returnByte = SPI.transfer(ff); uint8_t returnByte = SPI.transfer(ff);
return returnByte; return returnByte;
} }

View File

@ -499,7 +499,7 @@ uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool m
* New functions added to manage callbacks. * New functions added to manage callbacks.
* Victor Perez 2017 * Victor Perez 2017
*/ */
void SPIClass::onReceive(void(*callback)(void)) { void SPIClass::onReceive(void(*callback)()) {
_currentSetting->receiveCallback = callback; _currentSetting->receiveCallback = callback;
if (callback) { if (callback) {
switch (_currentSetting->spi_d->clk_id) { switch (_currentSetting->spi_d->clk_id) {
@ -527,7 +527,7 @@ void SPIClass::onReceive(void(*callback)(void)) {
} }
} }
void SPIClass::onTransmit(void(*callback)(void)) { void SPIClass::onTransmit(void(*callback)()) {
_currentSetting->transmitCallback = callback; _currentSetting->transmitCallback = callback;
if (callback) { if (callback) {
switch (_currentSetting->spi_d->clk_id) { switch (_currentSetting->spi_d->clk_id) {

View File

@ -137,8 +137,8 @@ private:
spi_dev *spi_d; spi_dev *spi_d;
dma_channel spiRxDmaChannel, spiTxDmaChannel; dma_channel spiRxDmaChannel, spiTxDmaChannel;
dma_dev* spiDmaDev; dma_dev* spiDmaDev;
void (*receiveCallback)(void) = NULL; void (*receiveCallback)() = NULL;
void (*transmitCallback)(void) = NULL; void (*transmitCallback)() = NULL;
friend class SPIClass; friend class SPIClass;
}; };
@ -213,8 +213,8 @@ public:
* onTransmit used to set the callback in case of dmaSend (tx only). That function * onTransmit used to set the callback in case of dmaSend (tx only). That function
* will NOT be called in case of TX/RX * will NOT be called in case of TX/RX
*/ */
void onReceive(void(*)(void)); void onReceive(void(*)());
void onTransmit(void(*)(void)); void onTransmit(void(*)());
/* /*
* I/O * I/O
@ -327,7 +327,7 @@ public:
* @brief Get a pointer to the underlying libmaple spi_dev for * @brief Get a pointer to the underlying libmaple spi_dev for
* this HardwareSPI instance. * this HardwareSPI instance.
*/ */
spi_dev* c_dev(void) { return _currentSetting->spi_d; } spi_dev* c_dev() { return _currentSetting->spi_d; }
spi_dev* dev() { return _currentSetting->spi_d; } spi_dev* dev() { return _currentSetting->spi_d; }

View File

@ -148,7 +148,7 @@ void libServo::move(const int32_t value) {
} }
#ifdef SERVO0_TIMER_NUM #ifdef SERVO0_TIMER_NUM
extern "C" void Servo_IRQHandler(void) { extern "C" void Servo_IRQHandler() {
static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
uint16_t SR = timer_get_status(tdev); uint16_t SR = timer_get_status(tdev);
if (SR & TIMER_SR_CC1IF) { // channel 1 off if (SR & TIMER_SR_CC1IF) { // channel 1 off

View File

@ -113,7 +113,7 @@ uint8_t u8g_com_stm32duino_fsmc_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, voi
#define __ASM __asm #define __ASM __asm
#define __STATIC_INLINE static inline #define __STATIC_INLINE static inline
__attribute__((always_inline)) __STATIC_INLINE void __DSB(void) { __attribute__((always_inline)) __STATIC_INLINE void __DSB() {
__ASM volatile ("dsb 0xF":::"memory"); __ASM volatile ("dsb 0xF":::"memory");
} }

View File

@ -50,9 +50,9 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); } void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) { void setup_endstop_interrupts() {
#if HAS_X_MAX #if HAS_X_MAX
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
#endif #endif

View File

@ -128,7 +128,7 @@ static int wait_ready ( /* 1:Ready, 0:Timeout */
/* Deselect card and release SPI */ /* Deselect card and release SPI */
/*-----------------------------------------------------------------------*/ /*-----------------------------------------------------------------------*/
static void deselect(void) { static void deselect() {
CS_HIGH(); /* CS = H */ CS_HIGH(); /* CS = H */
xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */ xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */
} }
@ -137,7 +137,7 @@ static void deselect(void) {
/* Select card and wait for ready */ /* Select card and wait for ready */
/*-----------------------------------------------------------------------*/ /*-----------------------------------------------------------------------*/
static int select(void) { /* 1:OK, 0:Timeout */ static int select() { /* 1:OK, 0:Timeout */
CS_LOW(); /* CS = L */ CS_LOW(); /* CS = L */
xchg_spi(0xFF); /* Dummy clock (force DO enabled) */ xchg_spi(0xFF); /* Dummy clock (force DO enabled) */
@ -151,7 +151,7 @@ static int select(void) { /* 1:OK, 0:Timeout */
/* Control SPI module (Platform dependent) */ /* Control SPI module (Platform dependent) */
/*-----------------------------------------------------------------------*/ /*-----------------------------------------------------------------------*/
static void power_on(void) { /* Enable SSP module and attach it to I/O pads */ static void power_on() { /* Enable SSP module and attach it to I/O pads */
ONBOARD_SD_SPI.setModule(ON_BOARD_SPI_DEVICE); ONBOARD_SD_SPI.setModule(ON_BOARD_SPI_DEVICE);
ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.begin();
ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setBitOrder(MSBFIRST);
@ -159,7 +159,7 @@ static void power_on(void) { /* Enable SSP module and attach it to I/O pads */
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */ OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */
} }
static void power_off(void) { /* Disable SPI function */ static void power_off() { /* Disable SPI function */
select(); /* Wait for card ready */ select(); /* Wait for card ready */
deselect(); deselect();
} }

View File

@ -33,7 +33,7 @@
SDIO_CardInfoTypeDef SdCard; SDIO_CardInfoTypeDef SdCard;
bool SDIO_Init(void) { bool SDIO_Init() {
uint32_t count = 0U; uint32_t count = 0U;
SdCard.CardType = SdCard.CardVersion = SdCard.Class = SdCard.RelCardAdd = SdCard.BlockNbr = SdCard.BlockSize = SdCard.LogBlockNbr = SdCard.LogBlockSize = 0; SdCard.CardType = SdCard.CardVersion = SdCard.Class = SdCard.RelCardAdd = SdCard.BlockNbr = SdCard.BlockSize = SdCard.LogBlockNbr = SdCard.LogBlockSize = 0;
@ -167,21 +167,21 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
return false; return false;
} }
inline uint32_t SDIO_GetCardState(void) { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; } inline uint32_t SDIO_GetCardState() { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; }
// ------------------------ // ------------------------
// SD Commands and Responses // SD Commands and Responses
// ------------------------ // ------------------------
void SDIO_SendCommand(uint16_t command, uint32_t argument) { SDIO->ARG = argument; SDIO->CMD = (uint32_t)(SDIO_CMD_CPSMEN | command); } void SDIO_SendCommand(uint16_t command, uint32_t argument) { SDIO->ARG = argument; SDIO->CMD = (uint32_t)(SDIO_CMD_CPSMEN | command); }
uint8_t SDIO_GetCommandResponse(void) { return (uint8_t)(SDIO->RESPCMD); } uint8_t SDIO_GetCommandResponse() { return (uint8_t)(SDIO->RESPCMD); }
uint32_t SDIO_GetResponse(uint32_t response) { return SDIO->RESP[response]; } uint32_t SDIO_GetResponse(uint32_t response) { return SDIO->RESP[response]; }
bool SDIO_CmdGoIdleState(void) { SDIO_SendCommand(CMD0_GO_IDLE_STATE, 0); return SDIO_GetCmdError(); } bool SDIO_CmdGoIdleState() { SDIO_SendCommand(CMD0_GO_IDLE_STATE, 0); return SDIO_GetCmdError(); }
bool SDIO_CmdSendCID(void) { SDIO_SendCommand(CMD2_ALL_SEND_CID, 0); return SDIO_GetCmdResp2(); } bool SDIO_CmdSendCID() { SDIO_SendCommand(CMD2_ALL_SEND_CID, 0); return SDIO_GetCmdResp2(); }
bool SDIO_CmdSetRelAdd(uint32_t *rca) { SDIO_SendCommand(CMD3_SET_REL_ADDR, 0); return SDIO_GetCmdResp6(SDMMC_CMD_SET_REL_ADDR, rca); } bool SDIO_CmdSetRelAdd(uint32_t *rca) { SDIO_SendCommand(CMD3_SET_REL_ADDR, 0); return SDIO_GetCmdResp6(SDMMC_CMD_SET_REL_ADDR, rca); }
bool SDIO_CmdSelDesel(uint32_t address) { SDIO_SendCommand(CMD7_SEL_DESEL_CARD, address); return SDIO_GetCmdResp1(SDMMC_CMD_SEL_DESEL_CARD); } bool SDIO_CmdSelDesel(uint32_t address) { SDIO_SendCommand(CMD7_SEL_DESEL_CARD, address); return SDIO_GetCmdResp1(SDMMC_CMD_SEL_DESEL_CARD); }
bool SDIO_CmdOperCond(void) { SDIO_SendCommand(CMD8_HS_SEND_EXT_CSD, SDMMC_CHECK_PATTERN); return SDIO_GetCmdResp7(); } bool SDIO_CmdOperCond() { SDIO_SendCommand(CMD8_HS_SEND_EXT_CSD, SDMMC_CHECK_PATTERN); return SDIO_GetCmdResp7(); }
bool SDIO_CmdSendCSD(uint32_t argument) { SDIO_SendCommand(CMD9_SEND_CSD, argument); return SDIO_GetCmdResp2(); } bool SDIO_CmdSendCSD(uint32_t argument) { SDIO_SendCommand(CMD9_SEND_CSD, argument); return SDIO_GetCmdResp2(); }
bool SDIO_CmdSendStatus(uint32_t argument) { SDIO_SendCommand(CMD13_SEND_STATUS, argument); return SDIO_GetCmdResp1(SDMMC_CMD_SEND_STATUS); } bool SDIO_CmdSendStatus(uint32_t argument) { SDIO_SendCommand(CMD13_SEND_STATUS, argument); return SDIO_GetCmdResp1(SDMMC_CMD_SEND_STATUS); }
bool SDIO_CmdReadSingleBlock(uint32_t address) { SDIO_SendCommand(CMD17_READ_SINGLE_BLOCK, address); return SDIO_GetCmdResp1(SDMMC_CMD_READ_SINGLE_BLOCK); } bool SDIO_CmdReadSingleBlock(uint32_t address) { SDIO_SendCommand(CMD17_READ_SINGLE_BLOCK, address); return SDIO_GetCmdResp1(SDMMC_CMD_READ_SINGLE_BLOCK); }
@ -212,7 +212,7 @@ bool SDIO_CmdAppSetClearCardDetect(uint32_t rsa) {
do { if (!--count) return false; } while (!SDIO_GET_FLAG(FLAGS)); \ do { if (!--count) return false; } while (!SDIO_GET_FLAG(FLAGS)); \
}while(0) }while(0)
bool SDIO_GetCmdError(void) { bool SDIO_GetCmdError() {
SDIO_WAIT(SDIO_STA_CMDSENT); SDIO_WAIT(SDIO_STA_CMDSENT);
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS); SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
@ -232,7 +232,7 @@ bool SDIO_GetCmdResp1(uint8_t command) {
return (SDIO_GetResponse(SDIO_RESP1) & SDMMC_OCR_ERRORBITS) == SDMMC_ALLZERO; return (SDIO_GetResponse(SDIO_RESP1) & SDMMC_OCR_ERRORBITS) == SDMMC_ALLZERO;
} }
bool SDIO_GetCmdResp2(void) { bool SDIO_GetCmdResp2() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT); SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT)) { if (SDIO_GET_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT)) {
@ -244,7 +244,7 @@ bool SDIO_GetCmdResp2(void) {
return true; return true;
} }
bool SDIO_GetCmdResp3(void) { bool SDIO_GetCmdResp3() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT); SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) { if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) {
@ -272,7 +272,7 @@ bool SDIO_GetCmdResp6(uint8_t command, uint32_t *rca) {
return true; return true;
} }
bool SDIO_GetCmdResp7(void) { bool SDIO_GetCmdResp7() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT); SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) { if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) {

View File

@ -121,13 +121,13 @@ typedef struct {
// Public functions // Public functions
// ------------------------ // ------------------------
inline uint32_t SDIO_GetCardState(void); inline uint32_t SDIO_GetCardState();
bool SDIO_CmdGoIdleState(void); bool SDIO_CmdGoIdleState();
bool SDIO_CmdSendCID(void); bool SDIO_CmdSendCID();
bool SDIO_CmdSetRelAdd(uint32_t *rca); bool SDIO_CmdSetRelAdd(uint32_t *rca);
bool SDIO_CmdSelDesel(uint32_t address); bool SDIO_CmdSelDesel(uint32_t address);
bool SDIO_CmdOperCond(void); bool SDIO_CmdOperCond();
bool SDIO_CmdSendCSD(uint32_t argument); bool SDIO_CmdSendCSD(uint32_t argument);
bool SDIO_CmdSendStatus(uint32_t argument); bool SDIO_CmdSendStatus(uint32_t argument);
bool SDIO_CmdReadSingleBlock(uint32_t address); bool SDIO_CmdReadSingleBlock(uint32_t address);
@ -139,11 +139,11 @@ bool SDIO_CmdAppOperCommand(uint32_t sdType);
bool SDIO_CmdAppSetClearCardDetect(uint32_t rsa); bool SDIO_CmdAppSetClearCardDetect(uint32_t rsa);
void SDIO_SendCommand(uint16_t command, uint32_t argument); void SDIO_SendCommand(uint16_t command, uint32_t argument);
uint8_t SDIO_GetCommandResponse(void); uint8_t SDIO_GetCommandResponse();
uint32_t SDIO_GetResponse(uint32_t response); uint32_t SDIO_GetResponse(uint32_t response);
bool SDIO_GetCmdError(void); bool SDIO_GetCmdError();
bool SDIO_GetCmdResp1(uint8_t command); bool SDIO_GetCmdResp1(uint8_t command);
bool SDIO_GetCmdResp2(void); bool SDIO_GetCmdResp2();
bool SDIO_GetCmdResp3(void); bool SDIO_GetCmdResp3();
bool SDIO_GetCmdResp6(uint8_t command, uint32_t *rca); bool SDIO_GetCmdResp6(uint8_t command, uint32_t *rca);
bool SDIO_GetCmdResp7(void); bool SDIO_GetCmdResp7();

View File

@ -86,11 +86,11 @@ timer_dev* get_timer_dev(int number);
// TODO change this // TODO change this
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler(void) #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler(void) #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
extern "C" void tempTC_Handler(void); extern "C" void tempTC_Handler();
extern "C" void stepTC_Handler(void); extern "C" void stepTC_Handler();
// ------------------------ // ------------------------
// Public Variables // Public Variables

View File

@ -40,7 +40,7 @@ void watchdog_reset() {
iwdg_feed(); iwdg_feed();
} }
void watchdogSetup(void) { void watchdogSetup() {
// do whatever. don't remove this function. // do whatever. don't remove this function.
} }
@ -51,7 +51,7 @@ void watchdogSetup(void) {
* *
* @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0) * @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0)
*/ */
void watchdog_init(void) { void watchdog_init() {
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD); //iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
} }

View File

@ -39,15 +39,15 @@ uint16_t HAL_adc_result;
/* VGPV Done with defines /* VGPV Done with defines
// disable interrupts // disable interrupts
void cli(void) { noInterrupts(); } void cli() { noInterrupts(); }
// enable interrupts // enable interrupts
void sei(void) { interrupts(); } void sei() { interrupts(); }
*/ */
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
uint8_t HAL_get_reset_source(void) { uint8_t HAL_get_reset_source() {
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG; if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE; if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL; if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
@ -91,6 +91,6 @@ extern "C" {
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result(void) { return HAL_adc_result; } uint16_t HAL_adc_get_result() { return HAL_adc_result; }
#endif // STM32GENERIC && (STM32F4 || STM32F7) #endif // STM32GENERIC && (STM32F4 || STM32F7)

View File

@ -150,19 +150,19 @@ extern uint16_t HAL_adc_result;
// Memory related // Memory related
#define __bss_end __bss_end__ #define __bss_end __bss_end__
inline void HAL_init(void) { } inline void HAL_init() { }
// Clear reset reason // Clear reset reason
void HAL_clear_reset_source(void); void HAL_clear_reset_source();
// Reset reason // Reset reason
uint8_t HAL_get_reset_source(void); uint8_t HAL_get_reset_source();
void _delay_ms(const int delay); void _delay_ms(const int delay);
/* /*
extern "C" { extern "C" {
int freeMemory(void); int freeMemory();
} }
*/ */
@ -179,7 +179,7 @@ int freeMemory() {
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
static inline int freeMemory(void) { static inline int freeMemory() {
volatile char top; volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0)); return &top - reinterpret_cast<char*>(_sbrk(0));
} }
@ -205,14 +205,14 @@ void eeprom_update_block (const void *__src, void *__dst, size_t __n);
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
inline void HAL_adc_init(void) {} inline void HAL_adc_init() {}
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result #define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true #define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result();
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin

View File

@ -71,7 +71,7 @@ static SPISettings spiConfig;
* *
* @details Only configures SS pin since libmaple creates and initialize the SPI object * @details Only configures SS pin since libmaple creates and initialize the SPI object
*/ */
void spiBegin(void) { void spiBegin() {
#if !defined(SS_PIN) || SS_PIN < 0 #if !defined(SS_PIN) || SS_PIN < 0
#error SS_PIN not defined! #error SS_PIN not defined!
#endif #endif
@ -103,7 +103,7 @@ void spiInit(uint8_t spiRate) {
* *
* @details * @details
*/ */
uint8_t spiRec(void) { uint8_t spiRec() {
SPI.beginTransaction(spiConfig); SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF); uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction(); SPI.endTransaction();

View File

@ -82,10 +82,10 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
} }
extern "C" void TIM5_IRQHandler() { extern "C" void TIM5_IRQHandler() {
((void(*)(void))TimerHandle[0].callback)(); ((void(*)())TimerHandle[0].callback)();
} }
extern "C" void TIM7_IRQHandler() { extern "C" void TIM7_IRQHandler() {
((void(*)(void))TimerHandle[1].callback)(); ((void(*)())TimerHandle[1].callback)();
} }
void HAL_timer_enable_interrupt(const uint8_t timer_num) { void HAL_timer_enable_interrupt(const uint8_t timer_num) {

Some files were not shown because too many files have changed in this diff Show More