diff options
Diffstat (limited to 'src/Hardware')
-rw-r--r-- | src/Hardware/ExceptionHandlers.cpp | 7 | ||||
-rw-r--r-- | src/Hardware/IoPorts.cpp | 24 | ||||
-rw-r--r-- | src/Hardware/IoPorts.h | 10 | ||||
-rw-r--r-- | src/Hardware/NonVolatileMemory.cpp | 6 | ||||
-rw-r--r-- | src/Hardware/SAM4E/Devices.cpp | 76 | ||||
-rw-r--r-- | src/Hardware/SAM4E/Devices.h | 29 | ||||
-rw-r--r-- | src/Hardware/SAM4E/Main.cpp | 26 | ||||
-rw-r--r-- | src/Hardware/SAM4E/PinDescription.h | 49 | ||||
-rw-r--r-- | src/Hardware/SAM4E/sam4e8e_flash.ld | 152 | ||||
-rw-r--r-- | src/Hardware/SAM4S/Devices.cpp | 77 | ||||
-rw-r--r-- | src/Hardware/SAM4S/Devices.h | 30 | ||||
-rw-r--r-- | src/Hardware/SAM4S/Main.cpp | 28 | ||||
-rw-r--r-- | src/Hardware/SAM4S/PinDescription.h | 49 | ||||
-rw-r--r-- | src/Hardware/SAM4S/sam4s8c_flash.ld | 152 | ||||
-rw-r--r-- | src/Hardware/SAME70/CanDriver.cpp | 833 | ||||
-rw-r--r-- | src/Hardware/SAME70/CanDriver.h | 1152 | ||||
-rw-r--r-- | src/Hardware/SAME70/Devices.cpp | 77 | ||||
-rw-r--r-- | src/Hardware/SAME70/Devices.h | 26 | ||||
-rw-r--r-- | src/Hardware/SAME70/Main.cpp | 16 | ||||
-rw-r--r-- | src/Hardware/SAME70/PinDescription.h | 49 | ||||
-rw-r--r-- | src/Hardware/SAME70/same70q20b_flash.ld | 184 | ||||
-rw-r--r-- | src/Hardware/SharedSpi/SharedSpiDevice.cpp | 9 |
22 files changed, 1048 insertions, 2013 deletions
diff --git a/src/Hardware/ExceptionHandlers.cpp b/src/Hardware/ExceptionHandlers.cpp index ce6d81bc..1dda86ee 100644 --- a/src/Hardware/ExceptionHandlers.cpp +++ b/src/Hardware/ExceptionHandlers.cpp @@ -10,6 +10,9 @@ #include <Platform.h> #include <Hardware/NonVolatileMemory.h> #include <Cache.h> +#if SAME70 || SAM4S || SAM4E +# include <Reset.h> +#endif // Perform a software reset. 'stk' points to the exception stack (r0 r1 r2 r3 r12 lr pc xPSR) if the cause is an exception, otherwise it is nullptr. [[noreturn]] void SoftwareReset(SoftwareResetReason initialReason, const uint32_t *stk) noexcept @@ -17,8 +20,8 @@ cpu_irq_disable(); // disable interrupts before we call any flash functions. We don't enable them again. WatchdogReset(); // kick the watchdog -#if SAM4E || SAME70 - rswdt_restart(RSWDT); // kick the secondary watchdog +#if SAME70 || SAM4E + WatchdogResetSecondary(); // kick the secondary watchdog #endif Cache::Disable(); diff --git a/src/Hardware/IoPorts.cpp b/src/Hardware/IoPorts.cpp index 8e85fc83..9417cf36 100644 --- a/src/Hardware/IoPorts.cpp +++ b/src/Hardware/IoPorts.cpp @@ -15,12 +15,16 @@ # include "DuetNG/DueXn.h" #endif +#include <AnalogOut.h> +#include <Interrupts.h> +#include <AnalogIn.h> +using #if SAME5x -# include <AnalogIn.h> -using AnalogIn::AdcBits; -# include <AnalogOut.h> -# include <Interrupts.h> + AnalogIn +#else + LegacyAnalogIn #endif + ::AdcBits; #if SUPPORT_CAN_EXPANSION # include <CanId.h> @@ -172,7 +176,7 @@ void IoPort::Release() noexcept } // Attach an interrupt to the pin. Nor permitted if we allocated the pin in shared input mode. -bool IoPort::AttachInterrupt(StandardCallbackFunction callback, enum InterruptMode mode, CallbackParameter param) const noexcept +bool IoPort::AttachInterrupt(StandardCallbackFunction callback, InterruptMode mode, CallbackParameter param) const noexcept { return IsValid() && !isSharedInput && attachInterrupt(GetPinNoCheck(), callback, mode, param); } @@ -623,20 +627,16 @@ uint16_t IoPort::ReadAnalog() const noexcept /*static*/ void IoPort::WriteAnalog(Pin pin, float pwm, uint16_t freq) noexcept { -#if SAME5x - AnalogOut::Write(pin, pwm, freq); -#elif defined(DUET_NG) +#if defined(DUET_NG) if (pin >= DueXnExpansionStart) { DuetExpansion::AnalogOut(pin, pwm); } else +#endif { - AnalogOut(pin, pwm, freq); + AnalogOut::Write(pin, pwm, freq); } -#else - AnalogOut(pin, pwm, freq); -#endif } // Members of class PwmPort diff --git a/src/Hardware/IoPorts.h b/src/Hardware/IoPorts.h index f775e935..5866ae3a 100644 --- a/src/Hardware/IoPorts.h +++ b/src/Hardware/IoPorts.h @@ -10,10 +10,8 @@ #include <RepRapFirmware.h> -#if SAME5x -# include <Interrupts.h> -# include <AnalogIn.h> -#endif +#include <Interrupts.h> +#include <AnalogIn.h> // Class to represent a port class IoPort @@ -79,12 +77,8 @@ protected: // Get the physical pin without checking the validity of the logical pin Pin GetPinNoCheck() const noexcept { -#if SAME5x // New-style pin table is indexed by pin number return logicalPin; -#else - return PinTable[logicalPin].pin; -#endif } static const char* TranslatePinAccess(PinAccess access) noexcept; diff --git a/src/Hardware/NonVolatileMemory.cpp b/src/Hardware/NonVolatileMemory.cpp index d36e6dae..45aee49e 100644 --- a/src/Hardware/NonVolatileMemory.cpp +++ b/src/Hardware/NonVolatileMemory.cpp @@ -27,7 +27,7 @@ void NonVolatileMemory::EnsureRead() noexcept # error //TODO #elif SAM4E || SAM4S || SAME70 const bool cacheEnabled = Cache::Disable(); - flash_read_user_signature(reinterpret_cast<uint32_t*>(&buffer), sizeof(buffer)/sizeof(uint32_t)); + Flash::ReadUserSignature(reinterpret_cast<uint32_t*>(&buffer), sizeof(buffer)/sizeof(uint32_t)); if (cacheEnabled) { Cache::Enable(); @@ -66,7 +66,7 @@ void NonVolatileMemory::EnsureWritten() noexcept { // Erase the page # if SAM4E || SAM4S || SAME70 - flash_erase_user_signature(); + Flash::EraseUserSignature(); # elif defined(__LPC17xx__) LPC_EraseSoftwareResetDataSlots(); // erase the last flash sector # endif @@ -77,7 +77,7 @@ void NonVolatileMemory::EnsureWritten() noexcept { # if SAM4E || SAM4S || SAME70 const bool cacheEnabled = Cache::Disable(); - flash_write_user_signature(reinterpret_cast<const uint32_t*>(&buffer)); + Flash::WriteUserSignature(reinterpret_cast<const uint32_t*>(&buffer)); if (cacheEnabled) { Cache::Enable(); diff --git a/src/Hardware/SAM4E/Devices.cpp b/src/Hardware/SAM4E/Devices.cpp new file mode 100644 index 00000000..ca3ec53a --- /dev/null +++ b/src/Hardware/SAM4E/Devices.cpp @@ -0,0 +1,76 @@ +/* + * Devices.cpp + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#include "Devices.h" +#include <RepRapFirmware.h> +#include <AnalogIn.h> +#include <AnalogOut.h> +#include <pmc/pmc.h> + +AsyncSerial Serial (UART0, UART0_IRQn, ID_UART0, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +AsyncSerial Serial1(UART1, UART1_IRQn, ID_UART1, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +SerialCDC SerialUSB; + +void UART0_Handler(void) noexcept +{ + Serial.IrqHandler(); +} + +void UART1_Handler(void) noexcept +{ + Serial1.IrqHandler(); +} + +void SerialInit() noexcept +{ + SetPinFunction(APIN_Serial0_RXD, Serial0PeriphMode); + SetPinFunction(APIN_Serial0_TXD, Serial0PeriphMode); + SetPullup(APIN_Serial0_RXD, true); + + SetPinFunction(APIN_Serial1_RXD, Serial1PeriphMode); + SetPinFunction(APIN_Serial1_TXD, Serial1PeriphMode); + SetPullup(APIN_Serial1_RXD, true); +} + +void SdhcInit() noexcept +{ + SetPinFunction(HsmciClockPin, HsmciPinsFunction); + for (Pin p : HsmciOtherPins) + { + SetPinFunction(p, HsmciPinsFunction); + SetPullup(p, true); + } +} + +void WireInit() noexcept +{ + pmc_enable_periph_clk(WIRE_INTERFACE_ID); + SetPinFunction(TWI_Data, TWIPeriphMode); + SetPinFunction(TWI_CK, TWIPeriphMode); + + NVIC_DisableIRQ(WIRE_ISR_ID); + NVIC_ClearPendingIRQ(WIRE_ISR_ID); +} + +TwoWire Wire(WIRE_INTERFACE, WireInit); + + +// Device initialisation +void DeviceInit() noexcept +{ + LegacyAnalogIn::AnalogInInit(); + AnalogOut::Init(); + + SerialInit(); + SdhcInit(); +} + +void StopAnalogTask() noexcept +{ +} + +// End diff --git a/src/Hardware/SAM4E/Devices.h b/src/Hardware/SAM4E/Devices.h new file mode 100644 index 00000000..bff883c9 --- /dev/null +++ b/src/Hardware/SAM4E/Devices.h @@ -0,0 +1,29 @@ +/* + * Devices.h + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAM4E_DEVICES_H_ +#define SRC_HARDWARE_SAM4E_DEVICES_H_ + +#include <AsyncSerial.h> +typedef AsyncSerial UARTClass; +#include <USARTClass.h> + +extern AsyncSerial Serial; +extern AsyncSerial Serial1; + +#define SUPPORT_USB 1 // needed by SerialCDC.h +#include <SerialCDC.h> + +extern SerialCDC SerialUSB; + +#include <Wire.h> +extern TwoWire Wire; + +void DeviceInit() noexcept; +void StopAnalogTask() noexcept; + +#endif /* SRC_HARDWARE_SAM4E_DEVICES_H_ */ diff --git a/src/Hardware/SAM4E/Main.cpp b/src/Hardware/SAM4E/Main.cpp new file mode 100644 index 00000000..355443b4 --- /dev/null +++ b/src/Hardware/SAM4E/Main.cpp @@ -0,0 +1,26 @@ +/* + * Main.cpp + * Program entry point + * Created on: 11 Jul 2020 + * Author: David + * License: GNU GPL version 3 + */ + +#include <CoreIO.h> +#include <RepRapFirmware.h> + +// Program initialisation +void AppInit() noexcept +{ + // When the reset button is pressed on pre-production Duet WiFi boards, if the TMC2660 drivers were previously enabled then we get + // uncommanded motor movements if the STEP lines pick up any noise. Try to reduce that by initialising the pins that control the drivers early here. + // On the production boards the ENN line is pulled high by an external pullup resistor and that prevents motor movements. + for (size_t drive = 0; drive < MaxSmartDrivers; ++drive) + { + pinMode(STEP_PINS[drive], OUTPUT_LOW); + pinMode(DIRECTION_PINS[drive], OUTPUT_LOW); + pinMode(ENABLE_PINS[drive], OUTPUT_HIGH); + } +} + +// End diff --git a/src/Hardware/SAM4E/PinDescription.h b/src/Hardware/SAM4E/PinDescription.h new file mode 100644 index 00000000..d08e16de --- /dev/null +++ b/src/Hardware/SAM4E/PinDescription.h @@ -0,0 +1,49 @@ +/* + * PinDescription.h + * + * Created on: 10 Jul 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAM4E_PINDESCRIPTION_H_ +#define SRC_HARDWARE_SAM4E_PINDESCRIPTION_H_ + +#include <CoreIO.h> + +// Enum to represent allowed types of pin access +// We don't have a separate bit for servo, because Duet PWM-capable ports can be used for servos if they are on the Duet main board +enum class PinCapability: uint8_t +{ + // Individual capabilities + none = 0, + read = 1, + ain = 2, + write = 4, + pwm = 8, + + // Combinations + ainr = 1|2, + rw = 1|4, + wpwm = 4|8, + rwpwm = 1|4|8, + ainrw = 1|2|4, + ainrwpwm = 1|2|4|8 +}; + +constexpr inline PinCapability operator|(PinCapability a, PinCapability b) noexcept +{ + return (PinCapability)((uint8_t)a | (uint8_t)b); +} + +// The pin description says what functions are available on each pin, filtered to avoid allocating the same function to more than one pin.. +// It is a struct not a class so that it can be direct initialised in read-only memory. +struct PinDescription : public PinDescriptionBase +{ + PinCapability cap; + const char* pinNames; + + PinCapability GetCapability() const noexcept { return cap; } + const char* GetNames() const noexcept { return pinNames; } +}; + +#endif /* SRC_HARDWARE_SAM4E_PINDESCRIPTION_H_ */ diff --git a/src/Hardware/SAM4E/sam4e8e_flash.ld b/src/Hardware/SAM4E/sam4e8e_flash.ld new file mode 100644 index 00000000..fcb4cfc0 --- /dev/null +++ b/src/Hardware/SAM4E/sam4e8e_flash.ld @@ -0,0 +1,152 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00400000, LENGTH = 0x00080000 + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00020000 +} + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + .ARM.exidx : + { + __exidx_start = .; + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + __exidx_end = .; + } > rom + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + . = ALIGN(4); + _eramfunc = .; + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + _firmware_crc = _etext + (_erelocate - _srelocate); /* We append the CRC32 to the binary file. This is its offset in memory. */ + + /* .bss section which is used for uninitialized data */ + .bss ALIGN(4) (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + . = ALIGN(4); + _end = . ; + + /* .stack_dummy section doesn't contains any symbols. It is only + used for linker to calculate size of stack sections, and assign + values to stack symbols later */ + .stack_dummy : + { + *(.stack*) + } > ram + + /* Set stack top to end of ram, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(ram) + LENGTH(ram); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(_sstack = __StackLimit); + PROVIDE(_estack = __StackTop); +} diff --git a/src/Hardware/SAM4S/Devices.cpp b/src/Hardware/SAM4S/Devices.cpp new file mode 100644 index 00000000..b388d6b7 --- /dev/null +++ b/src/Hardware/SAM4S/Devices.cpp @@ -0,0 +1,77 @@ +/* + * Devices.cpp + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#include "Devices.h" +#include <RepRapFirmware.h> +#include <AnalogIn.h> +#include <AnalogOut.h> +#include <pmc/pmc.h> +#include <matrix/matrix.h> + +#ifndef PCCB +AsyncSerial Serial (UART1, UART1_IRQn, ID_UART1, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); + +void UART1_Handler(void) noexcept +{ + Serial.IrqHandler(); +} + +void SerialInit() noexcept +{ + SetPinFunction(APIN_Serial0_RXD, Serial0PeriphMode); + SetPinFunction(APIN_Serial0_TXD, Serial0PeriphMode); + SetPullup(APIN_Serial0_RXD, true); +} +#endif + +SerialCDC SerialUSB; + +void SdhcInit() noexcept +{ + SetPinFunction(HsmciClockPin, HsmciPinsFunction); + for (Pin p : HsmciOtherPins) + { + SetPinFunction(p, HsmciPinsFunction); + SetPullup(p, true); + } +} + +void WireInit() noexcept +{ + pmc_enable_periph_clk(WIRE_INTERFACE_ID); + SetPinFunction(TWI_Data, TWIPeriphMode); + SetPinFunction(TWI_CK, TWIPeriphMode); + + NVIC_DisableIRQ(WIRE_ISR_ID); + NVIC_ClearPendingIRQ(WIRE_ISR_ID); +} + +TwoWire Wire(WIRE_INTERFACE, WireInit); + + +// Device initialisation +void DeviceInit() noexcept +{ + LegacyAnalogIn::AnalogInInit(); + AnalogOut::Init(); + +#ifndef PCCB + SerialInit(); +#endif + SdhcInit(); + +#ifndef PCCB + // Set up PB4..PB7 as normal I/O, not JTAG + matrix_set_system_io(CCFG_SYSIO_SYSIO4 | CCFG_SYSIO_SYSIO5 | CCFG_SYSIO_SYSIO6 | CCFG_SYSIO_SYSIO7); +#endif +} + +void StopAnalogTask() noexcept +{ +} + +// End diff --git a/src/Hardware/SAM4S/Devices.h b/src/Hardware/SAM4S/Devices.h new file mode 100644 index 00000000..a53ca0e3 --- /dev/null +++ b/src/Hardware/SAM4S/Devices.h @@ -0,0 +1,30 @@ +/* + * Devices.h + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAM4S_DEVICES_H_ +#define SRC_HARDWARE_SAM4S_DEVICES_H_ + +#ifndef PCCB +# include <AsyncSerial.h> +typedef AsyncSerial UARTClass; +# include <USARTClass.h> + +extern AsyncSerial Serial; +#endif + +#define SUPPORT_USB 1 // needed by SerialCDC.h +#include <SerialCDC.h> + +extern SerialCDC SerialUSB; + +#include <Wire.h> +extern TwoWire Wire; + +void DeviceInit() noexcept; +void StopAnalogTask() noexcept; + +#endif /* SRC_HARDWARE_SAM4S_DEVICES_H_ */ diff --git a/src/Hardware/SAM4S/Main.cpp b/src/Hardware/SAM4S/Main.cpp new file mode 100644 index 00000000..6398b7b9 --- /dev/null +++ b/src/Hardware/SAM4S/Main.cpp @@ -0,0 +1,28 @@ +/* + * Main.cpp + * Program entry point + * Created on: 11 Jul 2020 + * Author: David + * License: GNU GPL version 3 + */ + +#include <CoreIO.h> +#include <RepRapFirmware.h> + +// Program initialisation +void AppInit() noexcept +{ +#if defined(DUET_M) + // The prototype boards don't have a pulldown on LCD_BEEP, which causes a hissing sound from the beeper on the 12864 display until the pin is initialised + pinMode(LcdBeepPin, OUTPUT_LOW); + + // Set the 12864 display CS pin low to prevent it from receiving garbage due to other SPI traffic + pinMode(LcdCSPin, OUTPUT_LOW); + + // On the prototype boards the stepper driver expansion ports don't have external pullup resistors on their enable pins + pinMode(ENABLE_PINS[5], OUTPUT_HIGH); + pinMode(ENABLE_PINS[6], OUTPUT_HIGH); +#endif +} + +// End diff --git a/src/Hardware/SAM4S/PinDescription.h b/src/Hardware/SAM4S/PinDescription.h new file mode 100644 index 00000000..6f552cff --- /dev/null +++ b/src/Hardware/SAM4S/PinDescription.h @@ -0,0 +1,49 @@ +/* + * PinDescription.h + * + * Created on: 10 Jul 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAM4S_PINDESCRIPTION_H_ +#define SRC_HARDWARE_SAM4S_PINDESCRIPTION_H_ + +#include <CoreIO.h> + +// Enum to represent allowed types of pin access +// We don't have a separate bit for servo, because Duet PWM-capable ports can be used for servos if they are on the Duet main board +enum class PinCapability: uint8_t +{ + // Individual capabilities + none = 0, + read = 1, + ain = 2, + write = 4, + pwm = 8, + + // Combinations + ainr = 1|2, + rw = 1|4, + wpwm = 4|8, + rwpwm = 1|4|8, + ainrw = 1|2|4, + ainrwpwm = 1|2|4|8 +}; + +constexpr inline PinCapability operator|(PinCapability a, PinCapability b) noexcept +{ + return (PinCapability)((uint8_t)a | (uint8_t)b); +} + +// The pin description says what functions are available on each pin, filtered to avoid allocating the same function to more than one pin.. +// It is a struct not a class so that it can be direct initialised in read-only memory. +struct PinDescription : public PinDescriptionBase +{ + PinCapability cap; + const char* pinNames; + + PinCapability GetCapability() const noexcept { return cap; } + const char* GetNames() const noexcept { return pinNames; } +}; + +#endif /* SRC_HARDWARE_SAM4S_PINDESCRIPTION_H_ */ diff --git a/src/Hardware/SAM4S/sam4s8c_flash.ld b/src/Hardware/SAM4S/sam4s8c_flash.ld new file mode 100644 index 00000000..0ab61146 --- /dev/null +++ b/src/Hardware/SAM4S/sam4s8c_flash.ld @@ -0,0 +1,152 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00400000, LENGTH = 0x00080000 + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00020000 +} + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + .ARM.exidx : + { + __exidx_start = .; + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + __exidx_end = .; + } > rom + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + . = ALIGN(4); + _eramfunc = .; + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + _firmware_crc = _etext + (_erelocate - _srelocate); /* We append the CRC32 to the binary file. This is its offset in memory. */ + + /* .bss section which is used for uninitialized data */ + .bss ALIGN(4) (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + . = ALIGN(4); + _end = . ; + + /* .stack_dummy section doesn't contains any symbols. It is only + used for linker to calculate size of stack sections, and assign + values to stack symbols later */ + .stack_dummy : + { + *(.stack*) + } > ram + + /* Set stack top to end of ram, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(ram) + LENGTH(ram); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(_sstack = __StackLimit); + PROVIDE(_estack = __StackTop); +} diff --git a/src/Hardware/SAME70/CanDriver.cpp b/src/Hardware/SAME70/CanDriver.cpp deleted file mode 100644 index f25d60f2..00000000 --- a/src/Hardware/SAME70/CanDriver.cpp +++ /dev/null @@ -1,833 +0,0 @@ -/** - * \file - * - * \brief SAM Control Area Network (MCAN) Low Level Driver - * - * Copyright (c) 2015-2019 Microchip Technology Inc. and its subsidiaries. - * - * \asf_license_start - * - * \page License - * - * Subject to your compliance with these terms, you may use Microchip - * software and any derivatives exclusively with Microchip products. - * It is your responsibility to comply with third party license terms applicable - * to your use of third party software (including open source software) that - * may accompany Microchip software. - * - * THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES, - * WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE, - * INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY, - * AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT WILL MICROCHIP BE - * LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR CONSEQUENTIAL - * LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE - * SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE - * POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT - * ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY - * RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY, - * THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE. - * - * \asf_license_stop - * - */ -/* - * Support and FAQ: visit <a href="https://www.microchip.com/support/">Microchip Support</a> - */ - -#include "CanDriver.h" - -#if SUPPORT_CAN_EXPANSION - -#include <sam/drivers/pmc/pmc.h> -#include <cstring> - -// Values from conf_mcan.h - -/* - * Below is the message RAM setting, it will be stored in the system RAM. - * Please adjust the message size according to your application. - */ -/** Range: 1..64 */ -#define CONF_MCAN0_RX_FIFO_0_NUM 16 -/** Range: 1..64 */ -#define CONF_MCAN0_RX_FIFO_1_NUM 16 -/** Range: 1..64 */ -#define CONF_MCAN0_RX_BUFFER_NUM 4 -/** Range: 1..16 */ -#define CONF_MCAN0_TX_BUFFER_NUM 6 -/** Range: 1..16 */ -#define CONF_MCAN0_TX_FIFO_QUEUE_NUM 8 -/** Range: 1..32 */ -#define CONF_MCAN0_TX_EVENT_FIFO 16 -/** Range: 1..128 */ -#define CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM 1 -/** Range: 1..64 */ -#define CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM 3 -/** Range: 1..64 */ -#define CONF_MCAN1_RX_FIFO_0_NUM 16 -/** Range: 1..64 */ -#define CONF_MCAN1_RX_FIFO_1_NUM 16 -/** Range: 1..64 */ -#define CONF_MCAN1_RX_BUFFER_NUM 4 -/** Range: 1..16 */ -#define CONF_MCAN1_TX_BUFFER_NUM 6 -/** Range: 1..16 */ -#define CONF_MCAN1_TX_FIFO_QUEUE_NUM 8 -/** Range: 1..32 */ -#define CONF_MCAN1_TX_EVENT_FIFO 16 -/** Range: 1..128 */ -#define CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM 1 -/** Range: 1..64 */ -#define CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM 3 - -/** - * The setting of the nominal bit rate is based on the PCK5 which is 48M which you can - * change in the conf_clock.h. Below is the default configuration. The - * time quanta is 48MHz. And each bit is (1 + NTSEG1 + 1 + NTSEG2 + 1) = 48 time - * quanta which means the bit rate is 48MHz/49 = 1Mbps. - */ -/** Nominal bit Baud Rate Prescaler */ -#define CONF_MCAN_NBTP_NBRP_VALUE (1 - 1) -/** Nominal bit (Re)Synchronization Jump Width */ -#define CONF_MCAN_NBTP_NSJW_VALUE (8 - 1) -/** Nominal bit Time segment before sample point */ -#define CONF_MCAN_NBTP_NTSEG1_VALUE (26 - 1) -/** Nominal bit Time segment after sample point */ -#define CONF_MCAN_NBTP_NTSEG2_VALUE (21 - 1) - -/* - * The setting of the data bit rate is based on the PCK5 which is 48M which you can - * change. Below is the default configuration. The - * time quanta is 48MHz / (0+1) = 48MHz. And each bit is (1 + FTSEG1 + 1 + FTSEG2 + 1) = 12 time - * quanta which means the bit rate is 48MHz/12=4MHz. - */ -/** Data bit Baud Rate Prescaler */ -#define CONF_MCAN_FBTP_FBRP_VALUE (1 - 1) -/** Data bit (Re)Synchronization Jump Width */ -#define CONF_MCAN_FBTP_FSJW_VALUE (3 - 1) -/** Data bit Time segment before sample point */ -#define CONF_MCAN_FBTP_FTSEG1_VALUE (8 - 1) -/** Data bit Time segment after sample point */ -#define CONF_MCAN_FBTP_FTSEG2_VALUE (3 - 1) - - -/* PCK5 ID assigned to MCAN module */ -#define PMC_PCK_5 5 -/* Get a value of 2 to 15 bit. */ -#define BIT_2_TO_15_MASK 0x0000fffc - -/* Message ram definition. */ -#define CanMemory __attribute__ ((section (".CanMessage"))) -alignas(4) CanMemory static struct mcan_rx_element mcan0_rx_buffer[CONF_MCAN0_RX_BUFFER_NUM]; -alignas(4) CanMemory static struct mcan_rx_element mcan0_rx_fifo_0[CONF_MCAN0_RX_FIFO_0_NUM]; -alignas(4) CanMemory static struct mcan_rx_element mcan0_rx_fifo_1[CONF_MCAN0_RX_FIFO_1_NUM]; -alignas(4) CanMemory static struct mcan_tx_element mcan0_tx_buffer[CONF_MCAN0_TX_BUFFER_NUM + CONF_MCAN0_TX_FIFO_QUEUE_NUM]; -alignas(4) CanMemory static struct mcan_tx_event_element mcan0_tx_event_fifo[CONF_MCAN0_TX_EVENT_FIFO]; -alignas(4) CanMemory static struct mcan_standard_message_filter_element mcan0_rx_standard_filter[CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM]; -alignas(4) CanMemory static struct mcan_extended_message_filter_element mcan0_rx_extended_filter[CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM]; - -alignas(4) CanMemory static struct mcan_rx_element mcan1_rx_buffer[CONF_MCAN1_RX_BUFFER_NUM]; -alignas(4) CanMemory static struct mcan_rx_element mcan1_rx_fifo_0[CONF_MCAN1_RX_FIFO_0_NUM]; -alignas(4) CanMemory static struct mcan_rx_element mcan1_rx_fifo_1[CONF_MCAN1_RX_FIFO_1_NUM]; -alignas(4) CanMemory static struct mcan_tx_element mcan1_tx_buffer[CONF_MCAN1_TX_BUFFER_NUM + CONF_MCAN1_TX_FIFO_QUEUE_NUM]; -alignas(4) CanMemory static struct mcan_tx_event_element mcan1_tx_event_fifo[CONF_MCAN1_TX_EVENT_FIFO]; -alignas(4) CanMemory static struct mcan_standard_message_filter_element mcan1_rx_standard_filter[CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM]; -alignas(4) CanMemory static struct mcan_extended_message_filter_element mcan1_rx_extended_filter[CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM]; - -static constexpr uint8_t dlc2len[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64}; - -/** - * \brief initialize MCAN memory . - * - * \param hw Base address of the MCAN - * - */ -static void _mcan_message_memory_init(Mcan *hw) noexcept -{ - if (hw == MCAN0) { - hw->MCAN_SIDFC = ((uint32_t)mcan0_rx_standard_filter & BIT_2_TO_15_MASK) | - MCAN_SIDFC_LSS(CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM); - hw->MCAN_XIDFC = ((uint32_t)mcan0_rx_extended_filter & BIT_2_TO_15_MASK) | - MCAN_XIDFC_LSE(CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM); - hw->MCAN_RXF0C = ((uint32_t)mcan0_rx_fifo_0 & BIT_2_TO_15_MASK) | - MCAN_RXF0C_F0S(CONF_MCAN0_RX_FIFO_0_NUM); - hw->MCAN_RXF1C = ((uint32_t)mcan0_rx_fifo_1 & BIT_2_TO_15_MASK) | - MCAN_RXF1C_F1S(CONF_MCAN0_RX_FIFO_1_NUM); - hw->MCAN_RXBC = ((uint32_t)mcan0_rx_buffer & BIT_2_TO_15_MASK); - hw->MCAN_TXBC = ((uint32_t)mcan0_tx_buffer & BIT_2_TO_15_MASK) | - MCAN_TXBC_NDTB(CONF_MCAN0_TX_BUFFER_NUM) | - MCAN_TXBC_TFQS(CONF_MCAN0_TX_FIFO_QUEUE_NUM); - hw->MCAN_TXEFC = ((uint32_t)mcan0_tx_event_fifo & BIT_2_TO_15_MASK) | - MCAN_TXEFC_EFS(CONF_MCAN0_TX_EVENT_FIFO); - } else if (hw == MCAN1) { - hw->MCAN_SIDFC = ((uint32_t)mcan1_rx_standard_filter & BIT_2_TO_15_MASK) | - MCAN_SIDFC_LSS(CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM); - hw->MCAN_XIDFC = ((uint32_t)mcan1_rx_extended_filter & BIT_2_TO_15_MASK) | - MCAN_XIDFC_LSE(CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM); - hw->MCAN_RXF0C = ((uint32_t)mcan1_rx_fifo_0 & BIT_2_TO_15_MASK) | - MCAN_RXF0C_F0S(CONF_MCAN1_RX_FIFO_0_NUM); - hw->MCAN_RXF1C = ((uint32_t)mcan1_rx_fifo_1 & BIT_2_TO_15_MASK) | - MCAN_RXF1C_F1S(CONF_MCAN1_RX_FIFO_1_NUM); - hw->MCAN_RXBC = ((uint32_t)mcan1_rx_buffer & BIT_2_TO_15_MASK); - hw->MCAN_TXBC = ((uint32_t)mcan1_tx_buffer & BIT_2_TO_15_MASK) | - MCAN_TXBC_NDTB(CONF_MCAN1_TX_BUFFER_NUM) | - MCAN_TXBC_TFQS(CONF_MCAN1_TX_FIFO_QUEUE_NUM); - hw->MCAN_TXEFC = ((uint32_t)mcan1_tx_event_fifo & BIT_2_TO_15_MASK) | - MCAN_TXEFC_EFS(CONF_MCAN1_TX_EVENT_FIFO); - } - - /** - * The data size in conf_mcan.h should be 8/12/16/20/24/32/48/64, - * The corresponding setting value in register is 0/1//2/3/4/5/6/7. - * To simplify the calculation, separate to two group 8/12/16/20/24 which - * increased with 4 and 32/48/64 which increased with 16. - */ - if (CONF_MCAN_ELEMENT_DATA_SIZE <= 24) { - hw->MCAN_RXESC = MCAN_RXESC_RBDS((CONF_MCAN_ELEMENT_DATA_SIZE - 8) / 4) | - MCAN_RXESC_F0DS((CONF_MCAN_ELEMENT_DATA_SIZE - 8) / 4) | - MCAN_RXESC_F1DS((CONF_MCAN_ELEMENT_DATA_SIZE - 8) / 4); - hw->MCAN_TXESC = MCAN_TXESC_TBDS((CONF_MCAN_ELEMENT_DATA_SIZE - 8) / 4); - } else { - hw->MCAN_RXESC = MCAN_RXESC_RBDS((CONF_MCAN_ELEMENT_DATA_SIZE - 32) / 16 + 5) | - MCAN_RXESC_F0DS((CONF_MCAN_ELEMENT_DATA_SIZE - 32) / 16 + 5) | - MCAN_RXESC_F1DS((CONF_MCAN_ELEMENT_DATA_SIZE - 32) / 16 + 5); - hw->MCAN_TXESC = MCAN_TXESC_TBDS((CONF_MCAN_ELEMENT_DATA_SIZE - 32) / 16 + 5); - } -} - -/** - * \brief set default configuration when initialization. - * - * \param hw Base address of the MCAN - * \param config default configuration parameters. - */ -static void _mcan_set_configuration(Mcan *hw, mcan_config *config) noexcept -{ -#if (SAMV71B || SAME70B || SAMV70B) - /* Timing setting for Rev B */ - hw->MCAN_NBTP = MCAN_NBTP_NBRP(CONF_MCAN_NBTP_NBRP_VALUE) | - MCAN_NBTP_NSJW(CONF_MCAN_NBTP_NSJW_VALUE) | - MCAN_NBTP_NTSEG1(CONF_MCAN_NBTP_NTSEG1_VALUE) | - MCAN_NBTP_NTSEG2(CONF_MCAN_NBTP_NTSEG2_VALUE); - hw->MCAN_DBTP = MCAN_DBTP_DBRP(CONF_MCAN_FBTP_FBRP_VALUE) | - MCAN_DBTP_DSJW(CONF_MCAN_FBTP_FSJW_VALUE) | - MCAN_DBTP_DTSEG1(CONF_MCAN_FBTP_FTSEG1_VALUE) | - MCAN_DBTP_DTSEG2(CONF_MCAN_FBTP_FTSEG2_VALUE); - - hw->MCAN_TDCR = MCAN_TDCR_TDCO(config->delay_compensation_offset) | - MCAN_TDCR_TDCF(config->delay_compensation_filter_window_length); - - if (config->tdc_enable) { - hw->MCAN_DBTP |= MCAN_DBTP_TDC_ENABLED; - } -#else - /* Timing setting. */ - hw->MCAN_BTP = MCAN_BTP_BRP(CONF_MCAN_NBTP_NBRP_VALUE) | - MCAN_BTP_SJW(CONF_MCAN_NBTP_NSJW_VALUE) | - MCAN_BTP_TSEG1(CONF_MCAN_NBTP_NTSEG1_VALUE) | - MCAN_BTP_TSEG2(CONF_MCAN_NBTP_NTSEG2_VALUE); - hw->MCAN_FBTP = MCAN_FBTP_FBRP(CONF_MCAN_FBTP_FBRP_VALUE) | - MCAN_FBTP_FSJW(CONF_MCAN_FBTP_FSJW_VALUE) | - MCAN_FBTP_FTSEG1(CONF_MCAN_FBTP_FTSEG1_VALUE) | - MCAN_FBTP_FTSEG2(CONF_MCAN_FBTP_FTSEG2_VALUE) | - MCAN_FBTP_TDCO(config->delay_compensation_offset); - - if (config->tdc_enable) { - hw->MCAN_FBTP |= MCAN_FBTP_TDC_ENABLED; - } -#endif - hw->MCAN_RWD |= MCAN_RWD_WDC(config->watchdog_configuration); - - if (config->transmit_pause) { - hw->MCAN_CCCR |= MCAN_CCCR_TXP; - } - - if (!config->automatic_retransmission) { - hw->MCAN_CCCR |= MCAN_CCCR_DAR; - } - - if (config->clock_stop_request) { - hw->MCAN_CCCR |= MCAN_CCCR_CSR; - } - -#if 1 // DC - hw->MCAN_TSCC = MCAN_TSCC_TSS_EXT_TIMESTAMP; // use external timestamp counter -#else - hw->MCAN_TSCC = MCAN_TSCC_TCP(config->timestamp_prescaler) | - MCAN_TSCC_TSS_TCP_INC; -#endif - - hw->MCAN_TOCC = MCAN_TOCC_TOP(config->timeout_period) | - config->timeout_mode | config->timeout_enable; - - hw->MCAN_GFC = MCAN_GFC_ANFS(config->nonmatching_frames_action_standard) | - MCAN_GFC_ANFE(config->nonmatching_frames_action_extended); - if (config->remote_frames_standard_reject) { - hw->MCAN_GFC |= MCAN_GFC_RRFS; - } - if (config->remote_frames_extended_reject) { - hw->MCAN_GFC|= MCAN_GFC_RRFE; - } - - hw->MCAN_XIDAM = config->extended_id_mask; - - if (config->rx_fifo_0_overwrite) { - hw->MCAN_RXF0C |= MCAN_RXF0C_F0OM; - } - hw->MCAN_RXF0C |= MCAN_RXF0C_F0WM(config->rx_fifo_0_watermark); - - if (config->rx_fifo_1_overwrite) { - hw->MCAN_RXF1C |= MCAN_RXF1C_F1OM; - } - hw->MCAN_RXF1C |= MCAN_RXF1C_F1WM(config->rx_fifo_1_watermark); - - if (config->tx_queue_mode) { - hw->MCAN_TXBC |= MCAN_TXBC_TFQM; - } - - hw->MCAN_TXEFC |= MCAN_TXEFC_EFWM(config->tx_event_fifo_watermark); -} - -/** - * \brief enable can module clock. - * - * \param module_inst MCAN instance - * - */ -static void _mcan_enable_peripheral_clock(mcan_module *const module_inst) noexcept -{ - if (module_inst->hw == MCAN0) { - /* Turn on the digital interface clock. */ - pmc_enable_periph_clk(ID_MCAN0); - } else if (module_inst->hw == MCAN1) { - /* Turn on the digital interface clock. */ - pmc_enable_periph_clk(ID_MCAN1); - } -} - -// One-time initialisation. Do not call this to reset after a bus_off condition. -void mcan_init_once(mcan_module *const module_inst, Mcan *hw) noexcept -{ - /* Associate the software module instance with the hardware module */ - module_inst->hw = hw; - module_inst->taskWaitingOnFifo[0] = module_inst->taskWaitingOnFifo[1] = nullptr; - - pmc_disable_pck(PMC_PCK_5); - - // Use UPLL so the MCAN clock is independent of the CPU clock frequency - pmc_switch_pck_to_upllck(PMC_PCK_5, PMC_PCK_PRES(9)); // run PCLK5 at 48MHz - pmc_enable_pck(PMC_PCK_5); - - /* Enable peripheral clock */ - _mcan_enable_peripheral_clock(module_inst); -} - -/** - * \brief initialize can module. - * - * \param module_inst MCAN instance - * \param hw Base address of MCAN. - * \param config default configuration . - */ -void mcan_init(mcan_module *const module_inst, struct mcan_config *config) noexcept -{ - Mcan * const hw = module_inst->hw; - - /* Configuration Change Enable. */ - hw->MCAN_CCCR |= MCAN_CCCR_CCE; - - /* Initialize the message memory address. */ - _mcan_message_memory_init(hw); - - /* Set the configuration. */ - _mcan_set_configuration(hw, config); - - /* Enable the interrupt setting which no need change. */ - hw->MCAN_ILE = MCAN_ILE_EINT0 | MCAN_ILE_EINT1; - hw->MCAN_TXBTIE = 0xFFFFFFFFul; - hw->MCAN_TXBCIE = 0xFFFFFFFFul; -} - -/** - * \brief start can module after initialization. - * - * \param module_inst MCAN instance - * - */ -void mcan_start(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT); -} - -/** - * \brief stop mcan module when bus off occurs - * - * \param module_inst MCAN instance - * - */ -void mcan_stop(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); -} - -/** - * \brief switch mcan module into fd mode. - * - * \param module_inst MCAN instance - * - */ -void mcan_enable_fd_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE; -#if (SAMV71B || SAME70B || SAMV70B) - module_inst->hw->MCAN_CCCR |= (MCAN_CCCR_FDOE | MCAN_CCCR_BRSE); -#else - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CME(2); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CMR(2); -#endif -} - -/** - * \brief disable fd mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_disable_fd_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE; -#if (SAMV71B || SAME70B || SAMV70B) - module_inst->hw->MCAN_CCCR &= MCAN_CCCR_FDOE; -#else - module_inst->hw->MCAN_CCCR &= MCAN_CCCR_CME(MCAN_CCCR_CME_ISO11898_1); -#endif -} - -/** - * \brief enable restricted mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_enable_restricted_operation_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE; - - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_ASM; -} - -/** - * \brief disable restricted mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_disable_restricted_operation_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_ASM; -} - -/** - * \brief enable bus monitor mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_enable_bus_monitor_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE; - - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_MON; -} - -/** - * \brief disable bus monitor mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_disable_bus_monitor_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_MON; -} - -/** - * \brief enable sleep mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_enable_sleep_mode(mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CSR; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_CSA)); -} - -/** - * \brief disable sleep mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_disable_sleep_mode(struct mcan_module *const module_inst) noexcept -{ - /* Enable peripheral clock */ - _mcan_enable_peripheral_clock(module_inst); - - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_CSR; - while ((module_inst->hw->MCAN_CCCR & MCAN_CCCR_CSA)); -} - -/** - * \brief enable test mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_enable_test_mode(struct mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_INIT; - /* Wait for the sync. */ - while (!(module_inst->hw->MCAN_CCCR & MCAN_CCCR_INIT)); - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE; - - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_TEST; - module_inst->hw->MCAN_TEST |= MCAN_TEST_LBCK; -} - -/** - * \brief disable test mode of mcan module. - * - * \param module_inst MCAN instance - * - */ -void mcan_disable_test_mode(struct mcan_module *const module_inst) noexcept -{ - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_TEST; -} - -/** - * \brief set standard receive CAN ID. - * - * \param module_inst MCAN instance - * \param sd_filter structure of CAN ID - * \param index CAN messages memory index for different CAN ID - * - * \return status code. - */ -status_code mcan_set_rx_standard_filter(struct mcan_module *const module_inst, struct mcan_standard_message_filter_element *sd_filter, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - mcan0_rx_standard_filter[index].S0.reg = sd_filter->S0.reg; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - mcan1_rx_standard_filter[index].S0.reg = sd_filter->S0.reg; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief set extended receive CAN ID. - * - * \param module_inst MCAN instance - * \param sd_filter structure of extended CAN ID - * \param index CAN messages memory index for different CAN ID - * - * \return status code. - */ -status_code mcan_set_rx_extended_filter(struct mcan_module *const module_inst, struct mcan_extended_message_filter_element *et_filter, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - mcan0_rx_extended_filter[index].F0.reg = et_filter->F0.reg; - mcan0_rx_extended_filter[index].F1.reg = et_filter->F1.reg; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - mcan1_rx_extended_filter[index].F0.reg = et_filter->F0.reg; - mcan1_rx_extended_filter[index].F1.reg = et_filter->F1.reg; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief get dedicated rx buffer element . - * - * \param module_inst MCAN instance - * \param rx_element structure of element - * \param index CAN messages memory index for receiving CAN ID - * - * \return status code. - */ -status_code mcan_get_rx_buffer_element(struct mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - *rx_element = mcan0_rx_buffer[index]; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - *rx_element = mcan1_rx_buffer[index]; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief get FIFO rx buffer element . - * - * \param module_inst MCAN instance - * \param rx_element structure of element - * \param index CAN messages memory index for receiving CAN ID - * - * \return status code. - */ -status_code mcan_get_rx_fifo_0_element(struct mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - *rx_element = mcan0_rx_fifo_0[index]; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - *rx_element = mcan1_rx_fifo_0[index]; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief get FIFO rx buffer element . - * - * \param module_inst MCAN instance - * \param rx_element structure of element - * \param index CAN messages memory index for receiving CAN ID - * - * \return status code. - */ -status_code mcan_get_rx_fifo_1_element(struct mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - *rx_element = mcan0_rx_fifo_1[index]; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - *rx_element = mcan1_rx_fifo_1[index]; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief set dedicated transmit buffer element . - * - * \param module_inst MCAN instance - * \param tx_element structure of element - * \param index CAN messages memory index for transmitting CAN ID - * - * \return status code. - */ -status_code mcan_set_tx_buffer_element(struct mcan_module *const module_inst, struct mcan_tx_element *tx_element, uint32_t index) noexcept -{ - uint32_t i; - if (module_inst->hw == MCAN0) { - mcan0_tx_buffer[index].T0.reg = tx_element->T0.reg; - mcan0_tx_buffer[index].T1.reg = tx_element->T1.reg; - for (i = 0; i < CONF_MCAN_ELEMENT_DATA_SIZE; i++) { - mcan0_tx_buffer[index].data[i] = tx_element->data[i]; - } - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - mcan1_tx_buffer[index].T0.reg = tx_element->T0.reg; - mcan1_tx_buffer[index].T1.reg = tx_element->T1.reg; - for (i = 0; i < CONF_MCAN_ELEMENT_DATA_SIZE; i++) { - mcan1_tx_buffer[index].data[i] = tx_element->data[i]; - } - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -/** - * \brief set FIFO transmit buffer element . - * - * \param module_inst MCAN instance - * \param tx_element structure of element - * \param index CAN messages memory index for transmitting CAN ID - * - * \return status code. - */ -status_code mcan_get_tx_event_fifo_element(struct mcan_module *const module_inst, struct mcan_tx_event_element *tx_event_element, uint32_t index) noexcept -{ - if (module_inst->hw == MCAN0) { - tx_event_element->E0.reg = mcan0_tx_event_fifo[index].E0.reg; - tx_event_element->E1.reg = mcan0_tx_event_fifo[index].E1.reg; - return STATUS_OK; - } else if (module_inst->hw == MCAN1) { - tx_event_element->E0.reg = mcan1_tx_event_fifo[index].E0.reg; - tx_event_element->E1.reg = mcan1_tx_event_fifo[index].E1.reg; - return STATUS_OK; - } - return ERR_INVALID_ARG; -} - -// Send extended CAN message in FD mode using a dedicated transmit buffer. The transmit buffer must already be free. -status_code mcan_fd_send_ext_message_no_wait(mcan_module *const module_inst, uint32_t id_value, const uint8_t *data, size_t dataLength, uint32_t whichTxBuffer, bool bitRateSwitch, uint8_t marker) noexcept -{ - const uint32_t dlc = (dataLength <= 8) ? dataLength - : (dataLength <= 24) ? ((dataLength + 3) >> 2) + 6 - : ((dataLength + 15) >> 4) + 11; - mcan_tx_element tx_element; - tx_element.T0.reg = MCAN_TX_ELEMENT_T0_EXTENDED_ID(id_value) | MCAN_TX_ELEMENT_T0_XTD; - tx_element.T1.reg = MCAN_TX_ELEMENT_T1_DLC(dlc) - | MCAN_TX_ELEMENT_T1_EFC - | MCAN_TX_ELEMENT_T1_FDF - | MCAN_TX_ELEMENT_T1_MM(marker) - | ((bitRateSwitch) ? MCAN_TX_ELEMENT_T1_BRS : 0) - | ((marker != 0) ? MCAN_TX_ELEMENT_T1_EFC : 0); - - memcpy(tx_element.data, data, dataLength); - - // Set any extra data we will be sending to zero - const size_t roundedUpLength = dlc2len[dlc]; - memset(tx_element.data + dataLength, 0, roundedUpLength - dataLength); - - status_code rc = mcan_set_tx_buffer_element(module_inst, &tx_element, whichTxBuffer); - if (rc == STATUS_OK) - { - rc = mcan_tx_transfer_request(module_inst, (uint32_t)1 << whichTxBuffer); - } - return rc; -} - -// Wait for a specified buffer to become free. If it's still not free after the timeout, cancel the pending transmission. -// Return true if we cancelled the pending transmission. -bool WaitForTxBufferFree(mcan_module *const module_inst, uint32_t whichTxBuffer, uint32_t maxWait) noexcept -{ - const uint32_t trigMask = (uint32_t)1 << whichTxBuffer; - if ((module_inst->hw->MCAN_TXBRP & trigMask) != 0) - { - // Wait for the timeout period for the message to be sent - const uint32_t startTime = millis(); - do - { - delay(1); - if ((module_inst->hw->MCAN_TXBRP & trigMask) == 0) - { - return false; - } - } while (millis() - startTime < maxWait); - - // The last message still hasn't been sent, so cancel it - module_inst->hw->MCAN_TXBCR = trigMask; - while ((module_inst->hw->MCAN_TXBRP & trigMask) != 0) - { - delay(1); - } - return true; - } - return false; -} - -// Get a message from a FIFO with timeout. Return true if successful, false if we timed out -bool GetMessageFromFifo(mcan_module *const module_inst, CanMessageBuffer *buf, unsigned int fifoNumber, uint32_t timeout) noexcept -{ - volatile uint32_t* const fifoRegisters = &(module_inst->hw->MCAN_RXF0S) + (4 * fifoNumber); // pointer to FIFO status register followed by FIFO acknowledge register - module_inst->taskWaitingOnFifo[fifoNumber] = TaskBase::GetCallerTaskHandle(); - while (true) - { - const uint32_t status = fifoRegisters[0]; // get FIFO status - if ((status & MCAN_RXF0S_F0FL_Msk) != 0) // if there are any messages - { - const uint32_t getIndex = (status & MCAN_RXF0S_F0GI_Msk) >> MCAN_RXF0S_F0GI_Pos; - mcan_rx_element elem; - if (fifoNumber == 1) - { - mcan_get_rx_fifo_1_element(module_inst, &elem, getIndex); // copy the data (TODO use our own driver, avoid double copying) - } - else - { - mcan_get_rx_fifo_0_element(module_inst, &elem, getIndex); // copy the data (TODO use our own driver, avoid double copying) - } - fifoRegisters[1] = getIndex; // acknowledge it, release the FIFO entry - - if (elem.R0.bit.XTD == 1 && elem.R0.bit.RTR != 1) // if extended address and not a remote frame - { - // Copy the message and accompanying data to our buffer - buf->id.SetReceivedId(elem.R0.bit.ID); - buf->dataLength = dlc2len[elem.R1.bit.DLC]; - memcpy(buf->msg.raw, elem.data, buf->dataLength); - module_inst->taskWaitingOnFifo[fifoNumber] = nullptr; - return true; - } - } - else if (!TaskBase::Take(timeout)) - { - module_inst->taskWaitingOnFifo[fifoNumber] = nullptr; - return false; - } - } -} - -void GetLocalCanTiming(mcan_module *const module_inst, CanTiming& timing) noexcept -{ - const uint32_t nbtp = module_inst->hw->MCAN_NBTP; - const uint32_t tseg1 = (nbtp & MCAN_NBTP_NTSEG1_Msk) >> MCAN_NBTP_NTSEG1_Pos; - const uint32_t tseg2 = (nbtp & MCAN_NBTP_NTSEG2_Msk) >> MCAN_NBTP_NTSEG2_Pos; - const uint32_t jw = (nbtp & MCAN_NBTP_NSJW_Msk) >> MCAN_NBTP_NSJW_Pos; - const uint32_t brp = (nbtp & MCAN_NBTP_NBRP_Msk) >> MCAN_NBTP_NBRP_Pos; - timing.period = (tseg1 + tseg2 + 3) * (brp + 1); - timing.tseg1 = (tseg1 + 1) * (brp + 1); - timing.jumpWidth = (jw + 1) * (brp + 1); -} - -void ChangeLocalCanTiming(mcan_module *const module_inst, const CanTiming& timing) noexcept -{ - // Sort out the bit timing - uint32_t period = timing.period; - uint32_t tseg1 = timing.tseg1; - uint32_t jumpWidth = timing.jumpWidth; - uint32_t prescaler = 1; // 48MHz main clock - uint32_t tseg2; - - for (;;) - { - tseg2 = period - tseg1 - 1; - if (tseg1 <= 32 && tseg2 <= 16 && jumpWidth <= 16) - { - break; - } - prescaler <<= 1; - period >>= 1; - tseg1 >>= 1; - jumpWidth >>= 1; - } - - //TODO stop transmissions in an orderly fashion, or postpone initialising CAN until we have the timing data - module_inst->hw->MCAN_CCCR |= MCAN_CCCR_CCE | MCAN_CCCR_INIT; - module_inst->hw->MCAN_NBTP = ((tseg1 - 1) << MCAN_NBTP_NTSEG1_Pos) - | ((tseg2 - 1) << MCAN_NBTP_NTSEG2_Pos) - | ((jumpWidth - 1) << MCAN_NBTP_NSJW_Pos) - | ((prescaler - 1) << MCAN_NBTP_NBRP_Pos); - module_inst->hw->MCAN_CCCR &= ~MCAN_CCCR_CCE; -} - - -#endif // SUPPORT_CAN_EXPANSION - -// End - diff --git a/src/Hardware/SAME70/CanDriver.h b/src/Hardware/SAME70/CanDriver.h deleted file mode 100644 index 3ff425f3..00000000 --- a/src/Hardware/SAME70/CanDriver.h +++ /dev/null @@ -1,1152 +0,0 @@ -/** - * \file - * - * \brief SAM Control Area Network (MCAN) Low Level Driver - * - * Copyright (c) 2015-2018 Microchip Technology Inc. and its subsidiaries. - * - * \asf_license_start - * - * \page License - * - * Subject to your compliance with these terms, you may use Microchip - * software and any derivatives exclusively with Microchip products. - * It is your responsibility to comply with third party license terms applicable - * to your use of third party software (including open source software) that - * may accompany Microchip software. - * - * THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES, - * WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE, - * INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY, - * AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT WILL MICROCHIP BE - * LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR CONSEQUENTIAL - * LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE - * SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE - * POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT - * ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY - * RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY, - * THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE. - * - * \asf_license_stop - * - */ -/* - * Support and FAQ: visit <a href="https://www.microchip.com/support/">Microchip Support</a> - */ - - -#ifndef SRC_HARDWARE_CANDRIVER_H_ -#define SRC_HARDWARE_CANDRIVER_H_ - -#include <RepRapFirmware.h> - -#if SUPPORT_CAN_EXPANSION - -#include <CanSettings.h> -#include <CanMessageBuffer.h> -#include <RTOSIface/RTOSIface.h> -#include <status_codes.h> - -/** The value should be 8/12/16/20/24/32/48/64. */ -#define CONF_MCAN_ELEMENT_DATA_SIZE 64 - -/* -------- MCAN_RX_ELEMENT_R0 : (MCAN RX element: 0x00) (R/W 32) Rx Element R0 Configuration -------- */ -typedef union { - struct { - /* bit: 0..28 Identifier */ - uint32_t ID:29; - /* bit: 29 Remote Transmission Request */ - uint32_t RTR:1; - /* bit: 30 Extended Identifier */ - uint32_t XTD:1; - /* bit: 31 Error State Indicator */ - uint32_t ESI:1; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_RX_ELEMENT_R0_Type; - -#define MCAN_RX_ELEMENT_R0_ID_Pos 0 -#define MCAN_RX_ELEMENT_R0_ID_Msk (0x1FFFFFFFul << MCAN_RX_ELEMENT_R0_ID_Pos) -#define MCAN_RX_ELEMENT_R0_ID(value) ((MCAN_RX_ELEMENT_R0_ID_Msk & ((value) << MCAN_RX_ELEMENT_R0_ID_Pos))) -#define MCAN_RX_ELEMENT_R0_RTR_Pos 29 -#define MCAN_RX_ELEMENT_R0_RTR (0x1ul << MCAN_RX_ELEMENT_R0_RTR_Pos) -#define MCAN_RX_ELEMENT_R0_XTD_Pos 30 -#define MCAN_RX_ELEMENT_R0_XTD (0x1ul << MCAN_RX_ELEMENT_R0_XTD_Pos) -#define MCAN_RX_ELEMENT_R0_ESI_Pos 31 -#define MCAN_RX_ELEMENT_R0_ESI (0x1ul << MCAN_RX_ELEMENT_R0_ESI_Pos) - -/* -------- MCAN_RX_ELEMENT_R1 : (MCAN RX element: 0x01) (R/W 32) Rx Element R1 Configuration -------- */ -typedef union { - struct { - /* bit: 0..15 Rx Timestamp */ - uint32_t RXTS:16; - /* bit: 16..19 Data Length Code */ - uint32_t DLC:4; - /* bit: 20 Bit Rate Switch */ - uint32_t BRS:1; - /* bit: 21 FD Format */ - uint32_t EDL:1; - /* bit: 22..23 Reserved */ - uint32_t :2; - /* bit: 24..30 Filter Index */ - uint32_t FIDX:7; - /* bit: 31 Accepted Non-matching Frame */ - uint32_t ANMF:1; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_RX_ELEMENT_R1_Type; - -#define MCAN_RX_ELEMENT_R1_RXTS_Pos 0 -#define MCAN_RX_ELEMENT_R1_RXTS_Msk (0xFFFFul << MCAN_RX_ELEMENT_R1_RXTS_Pos) -#define MCAN_RX_ELEMENT_R1_RXTS(value) ((MCAN_RX_ELEMENT_R1_RXTS_Msk & ((value) << MCAN_RX_ELEMENT_R1_RXTS_Pos))) -#define MCAN_RX_ELEMENT_R1_DLC_Pos 16 -#define MCAN_RX_ELEMENT_R1_DLC_Msk (0xFul << MCAN_RX_ELEMENT_R1_DLC_Pos) -#define MCAN_RX_ELEMENT_R1_DLC(value) ((MCAN_RX_ELEMENT_R1_DLC_Msk & ((value) << MCAN_RX_ELEMENT_R1_DLC_Pos))) -#define MCAN_RX_ELEMENT_R1_BRS_Pos 20 -#define MCAN_RX_ELEMENT_R1_BRS (0x1ul << MCAN_RX_ELEMENT_R1_BRS_Pos) -#define MCAN_RX_ELEMENT_R1_FDF_Pos 21 -#define MCAN_RX_ELEMENT_R1_FDF (0x1ul << MCAN_RX_ELEMENT_R1_FDF_Pos) -#define MCAN_RX_ELEMENT_R1_FIDX_Pos 24 -#define MCAN_RX_ELEMENT_R1_FIDX_Msk (0x7Ful << MCAN_RX_ELEMENT_R1_FIDX_Pos) -#define MCAN_RX_ELEMENT_R1_FIDX(value) ((MCAN_RX_ELEMENT_R1_FIDX_Msk & ((value) << MCAN_RX_ELEMENT_R1_FIDX_Pos))) -#define MCAN_RX_ELEMENT_R1_ANMF_Pos 31 -#define MCAN_RX_ELEMENT_R1_ANMF (0x1ul << MCAN_RX_ELEMENT_R1_ANMF_Pos) - -//TODO there is no need for these 3 structs to be different -/** - * \brief MCAN receive element structure for buffer. - */ -struct mcan_rx_element { - __IO MCAN_RX_ELEMENT_R0_Type R0; - __IO MCAN_RX_ELEMENT_R1_Type R1; - uint8_t data[CONF_MCAN_ELEMENT_DATA_SIZE]; - - mcan_rx_element& operator=(const mcan_rx_element& other) - { - R0.reg = other.R0.reg; - R1.reg = other.R1.reg; - memcpy(data, other.data, sizeof(data)); - return *this; - } -}; - -/* -------- MCAN_TX_ELEMENT_T0 : (MCAN TX element: 0x00) (R/W 32) Tx Element T0 Configuration -------- */ -typedef union { - struct { - /* bit: 0..28 Identifier */ - uint32_t ID:29; - /* bit: 29 Remote Transmission Request */ - uint32_t RTR:1; - /* bit: 30 Extended Identifier */ - uint32_t XTD:1; -#if (SAMV71B || SAME70B || SAMV70B) - /* bit: 31 Error State Indicator */ - uint32_t ESI:1; -#else - /* bit: 31 Reserved */ - uint32_t :1; -#endif - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_TX_ELEMENT_T0_Type; - -#define MCAN_TX_ELEMENT_T0_EXTENDED_ID_Pos 0 -#define MCAN_TX_ELEMENT_T0_EXTENDED_ID_Msk (0x1FFFFFFFul << MCAN_TX_ELEMENT_T0_EXTENDED_ID_Pos) -#define MCAN_TX_ELEMENT_T0_EXTENDED_ID(value) ((MCAN_TX_ELEMENT_T0_EXTENDED_ID_Msk & ((value) << MCAN_TX_ELEMENT_T0_EXTENDED_ID_Pos))) -#define MCAN_TX_ELEMENT_T0_STANDARD_ID_Pos 18 -#define MCAN_TX_ELEMENT_T0_STANDARD_ID_Msk (0x7FFul << MCAN_TX_ELEMENT_T0_STANDARD_ID_Pos) -#define MCAN_TX_ELEMENT_T0_STANDARD_ID(value) ((MCAN_TX_ELEMENT_T0_STANDARD_ID_Msk & ((value) << MCAN_TX_ELEMENT_T0_STANDARD_ID_Pos))) -#define MCAN_TX_ELEMENT_T0_RTR_Pos 29 -#define MCAN_TX_ELEMENT_T0_RTR (0x1ul << MCAN_TX_ELEMENT_T0_RTR_Pos) -#define MCAN_TX_ELEMENT_T0_XTD_Pos 30 -#define MCAN_TX_ELEMENT_T0_XTD (0x1ul << MCAN_TX_ELEMENT_T0_XTD_Pos) -#if (SAMV71B || SAME70B || SAMV70B) -#define MCAN_TX_ELEMENT_T0_ESI_Pos 31 -#define MCAN_TX_ELEMENT_T0_ESI (0x1ul << MCAN_TX_ELEMENT_T0_ESI_Pos) -#endif - -/* -------- MCAN_TX_ELEMENT_T1 : (MCAN TX element: 0x01) (R/W 32) Tx Element T1 Configuration -------- */ -typedef union { - struct { - /* bit: 0..15 Reserved */ - uint32_t :16; - /* bit: 16..19 Data Length Code */ - uint32_t DLC:4; -#if (SAMV71B || SAME70B || SAMV70B) - /* bit: 20 Bit Rate Switch */ - uint32_t BRS:1; - /* bit: 21 FD Format */ - uint32_t FDF:1; - /* bit: 22 Reserved */ - uint32_t :1; -#else - /* bit: 20..22 Reserved */ - uint32_t :3; -#endif - /* bit: 23 Event FIFO Control */ - uint32_t EFCC:1; - /* bit: 24..31 Message Marker */ - uint32_t MM:8; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_TX_ELEMENT_T1_Type; - -#define MCAN_TX_ELEMENT_T1_DLC_Pos 16 -#define MCAN_TX_ELEMENT_T1_DLC_Msk (0xFul << MCAN_TX_ELEMENT_T1_DLC_Pos) -#define MCAN_TX_ELEMENT_T1_DLC(value) ((MCAN_TX_ELEMENT_T1_DLC_Msk & ((value) << MCAN_TX_ELEMENT_T1_DLC_Pos))) -/**< \brief (MCAN_RXESC) 8 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA8_Val 0x8ul -/**< \brief (MCAN_RXESC) 12 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA12_Val 0x9ul -/**< \brief (MCAN_RXESC) 16 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA16_Val 0xAul -/**< \brief (MCAN_RXESC) 20 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA20_Val 0xBul -/**< \brief (MCAN_RXESC) 24 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA24_Val 0xCul -/**< \brief (MCAN_RXESC) 32 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA32_Val 0xDul -/**< \brief (MCAN_RXESC) 48 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA48_Val 0xEul -/**< \brief (MCAN_RXESC) 64 byte data field */ -#define MCAN_TX_ELEMENT_T1_DLC_DATA64_Val 0xFul -#if (SAMV71B || SAME70B || SAMV70B) -#define MCAN_TX_ELEMENT_T1_BRS_Pos 20 -#define MCAN_TX_ELEMENT_T1_BRS (0x1ul << MCAN_TX_ELEMENT_T1_BRS_Pos) -#define MCAN_TX_ELEMENT_T1_FDF_Pos 21 -#define MCAN_TX_ELEMENT_T1_FDF (0x1ul << MCAN_TX_ELEMENT_T1_FDF_Pos) -#endif -#define MCAN_TX_ELEMENT_T1_EFC_Pos 23 -#define MCAN_TX_ELEMENT_T1_EFC (0x1ul << MCAN_TX_ELEMENT_T1_EFC_Pos) -#define MCAN_TX_ELEMENT_T1_MM_Pos 24 -#define MCAN_TX_ELEMENT_T1_MM_Msk (0xFFul << MCAN_TX_ELEMENT_T1_MM_Pos) -#define MCAN_TX_ELEMENT_T1_MM(value) ((MCAN_TX_ELEMENT_T1_MM_Msk & ((value) << MCAN_TX_ELEMENT_T1_MM_Pos))) - -/** - * \brief MCAN transfer element structure. - * - * Common element structure for transfer buffer and FIFO/QUEUE. - */ -struct mcan_tx_element { - __IO MCAN_TX_ELEMENT_T0_Type T0; - __IO MCAN_TX_ELEMENT_T1_Type T1; - uint8_t data[CONF_MCAN_ELEMENT_DATA_SIZE]; -}; - -/* -------- MCAN_TX_EVENT_ELEMENT_E0 : (MCAN TX event element: 0x00) (R/W 32) Tx Event Element E0 Configuration -------- */ -typedef union { - struct { - /* bit: 0..28 Identifier */ - uint32_t ID:29; - /* bit: 29 Remote Transmission Request */ - uint32_t RTR:1; - /* bit: 30 Extended Identifier */ - uint32_t XTD:1; - /* bit: 31 Error State Indicator */ - uint32_t ESI:1; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_TX_EVENT_ELEMENT_E0_Type; - -#define MCAN_TX_EVENT_ELEMENT_E0_ID_Pos 0 -#define MCAN_TX_EVENT_ELEMENT_E0_ID_Msk (0x1FFFFFFFul << MCAN_TX_EVENT_ELEMENT_E0_ID_Pos) -#define MCAN_TX_EVENT_ELEMENT_E0_ID(value) ((MCAN_TX_EVENT_ELEMENT_E0_ID_Msk & ((value) << MCAN_TX_EVENT_ELEMENT_E0_ID_Pos))) -#define MCAN_TX_EVENT_ELEMENT_E0_RTR_Pos 29 -#define MCAN_TX_EVENT_ELEMENT_E0_RTR (0x1ul << MCAN_TX_EVENT_ELEMENT_E0_RTR_Pos) -#define MCAN_TX_EVENT_ELEMENT_E0_XTD_Pos 30 -#define MCAN_TX_EVENT_ELEMENT_E0_XTD (0x1ul << MCAN_TX_EVENT_ELEMENT_E0_XTD_Pos) -#define MCAN_TX_EVENT_ELEMENT_E0_ESI_Pos 31 -#define MCAN_TX_EVENT_ELEMENT_E0_ESI (0x1ul << MCAN_TX_EVENT_ELEMENT_E0_ESI_Pos) - -/* -------- MCAN_TX_EVENT_ELEMENT_E1 : (MCAN TX event element: 0x01) (R/W 32) Tx Event Element E1 Configuration -------- */ -typedef union { - struct { - /* bit: 0..15 Tx Timestamp */ - uint32_t TXTS:16; - /* bit: 16..19 Data Length Code */ - uint32_t DLC:4; - /* bit: 20 Bit Rate Switch */ - uint32_t BRS:1; - /* bit: 21 FD Format */ - uint32_t EDL:1; - /* bit: 22..23 Event Type */ - uint32_t ET:2; - /* bit: 24..31 Message Marker */ - uint32_t MM:8; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_TX_EVENT_ELEMENT_E1_Type; - -#define MCAN_TX_EVENT_ELEMENT_E1_TXTS_Pos 0 -#define MCAN_TX_EVENT_ELEMENT_E1_TXTS_Msk (0xFFFFul << MCAN_TX_EVENT_ELEMENT_E1_TXTS_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_TXTS(value) ((MCAN_TX_EVENT_ELEMENT_E1_TXTS_Msk & ((value) << MCAN_TX_EVENT_ELEMENT_E1_TXTS_Pos))) -#define MCAN_TX_EVENT_ELEMENT_E1_DLC_Pos 16 -#define MCAN_TX_EVENT_ELEMENT_E1_DLC_Msk (0xFul << MCAN_TX_EVENT_ELEMENT_E1_DLC_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_DLC(value) ((MCAN_TX_EVENT_ELEMENT_E1_DLC_Msk & ((value) << MCAN_TX_EVENT_ELEMENT_E1_DLC_Pos))) -#define MCAN_TX_EVENT_ELEMENT_E1_BRS_Pos 20 -#define MCAN_TX_EVENT_ELEMENT_E1_BRS (0x1ul << MCAN_TX_EVENT_ELEMENT_E1_BRS_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_FDF_Pos 21 -#define MCAN_TX_EVENT_ELEMENT_E1_FDF (0x1ul << MCAN_TX_EVENT_ELEMENT_E1_FDF_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_ET_Pos 22 -#define MCAN_TX_EVENT_ELEMENT_E1_ET_Msk (0x3ul << MCAN_TX_EVENT_ELEMENT_E1_ET_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_ET(value) ((MCAN_TX_EVENT_ELEMENT_E1_ET_Msk & ((value) << MCAN_TX_EVENT_ELEMENT_E1_ET_Pos))) -#define MCAN_TX_EVENT_ELEMENT_E1_MM_Pos 24 -#define MCAN_TX_EVENT_ELEMENT_E1_MM_Msk (0xFFul << MCAN_TX_EVENT_ELEMENT_E1_MM_Pos) -#define MCAN_TX_EVENT_ELEMENT_E1_MM(value) ((MCAN_TX_EVENT_ELEMENT_E1_MM_Msk & ((value) << MCAN_TX_EVENT_ELEMENT_E1_MM_Pos))) - -/** - * \brief MCAN transfer event FIFO element structure. - * - * Common element structure for transfer event FIFO. - */ -struct mcan_tx_event_element { - __IO MCAN_TX_EVENT_ELEMENT_E0_Type E0; - __IO MCAN_TX_EVENT_ELEMENT_E1_Type E1; -}; - -/* -------- MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0 : (MCAN standard message ID filter element: 0x00) (R/W 32) Standard Message ID Filter Element S0 Configuration -------- */ -typedef union { - struct { - /* bit: 0..10 Standard Filter ID 2 */ - uint32_t SFID2:11; - /* bit: 11..15 Reserved */ - uint32_t :5; - /* bit: 16..26 Standard Filter ID 1 */ - uint32_t SFID1:11; - /* bit: 27..29 Standard Filter Element Configuration */ - uint32_t SFEC:3; - /* bit: 30..31 Standard Filter Type */ - uint32_t SFT:2; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_Type; - -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Pos 0 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Msk (0x7FFul << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Pos) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2(value) ((MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Msk & ((value) << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Pos))) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1_Pos 16 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1_Msk (0x7FFul << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1_Pos) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1(value) ((MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1_Msk & ((value) << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1_Pos))) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_Pos 27 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_Msk (0x7ul << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_Pos) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC(value) ((MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_Msk & ((value) << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_Pos))) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_DISABLE_Val 0 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_STF0M_Val 1 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_STF1M_Val 2 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_REJECT_Val 3 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_PRIORITY_Val 4 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_PRIF0M_Val 5 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_PRIF1M_Val 6 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_STRXBUF_Val 7 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_Pos 30 -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_Msk (0x3ul << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_Pos) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT(value) ((MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_Msk & ((value) << MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_Pos))) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_RANGE MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT(0) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_DUAL MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT(1) -#define MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_CLASSIC MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT(2) - -/** - * \brief MCAN standard message ID filter element structure. - * - * Common element structure for standard message ID filter element. - */ -struct mcan_standard_message_filter_element { - __IO MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_Type S0; -}; - -/* -------- MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0 : (MCAN extended message ID filter element: 0x00) (R/W 32) Extended Message ID Filter Element F0 Configuration -------- */ -typedef union { - struct { - /* bit: 0..28 Extended Filter ID 1 */ - uint32_t EFID1:29; - /* bit: 29..31 Extended Filter Element Configuration */ - uint32_t EFEC:3; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_Type; - -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1_Pos 0 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1_Msk (0x1FFFFFFFul << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1_Pos) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1(value) ((MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1_Msk & ((value) << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1_Pos))) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_Pos 29 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_Msk (0x7ul << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_Pos) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC(value) ((MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_Msk & ((value) << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_Pos))) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_DISABLE_Val 0 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_STF0M_Val 1 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_STF1M_Val 2 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_REJECT_Val 3 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_PRIORITY_Val 4 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_PRIF0M_Val 5 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_PRIF1M_Val 6 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_STRXBUF_Val 7 - -/* -------- MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1 : (MCAN extended message ID filter element: 0x01) (R/W 32) Extended Message ID Filter Element F1 Configuration -------- */ -typedef union { - struct { - /* bit: 0..28 Extended Filter ID 2 */ - uint32_t EFID2:29; - /* bit: 29 Reserved */ - uint32_t :1; - /* bit: 30..31 Extended Filter Type */ - uint32_t EFT:2; - } bit; - /* Type used for register access */ - uint32_t reg; -} MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_Type; - -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Pos 0 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Msk (0x1FFFFFFFul << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Pos) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2(value) ((MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Msk & ((value) << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Pos))) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_Pos 30 -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_Msk (0x3ul << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_Pos) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT(value) ((MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_Msk & ((value) << MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_Pos))) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_RANGEM MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT(0) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_DUAL MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT(1) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_CLASSIC MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT(2) -#define MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_RANGE MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT(3) - -/** - * \brief MCAN extended message ID filter element structure. - * - * Common element structure for extended message ID filter element. - */ -struct mcan_extended_message_filter_element { - __IO MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_Type F0; - __IO MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_Type F1; -}; -/** @} */ - -/** - * \defgroup asfdoc_sam_mcan_group SAM Control Area Network (MCAN) Low Level Driver - * - * This driver for AtmelĀ® | SMART SAM devices provides an low level - * interface for the configuration and management of the device's - * Control Area Network functionality. - * - * \note Since "The Control Area Network (CAN) performs communication according - * to ISO 11898-1 (Bosch CAN specification 2.0 part A,B) and to Bosch CAN FD - * specification V1.0", the driver is focus on the MAC layer and try to offer - * the APIs which can be used by upper application layer. - * - * For storage of Rx/Tx messages and for storage of the filter configuration, - * a message RAM is needed to the CAN module. In this driver, the message RAM - * is static allocated, the related setting is defined and can be changed in - * the module configuration file "conf_mcan.h". - * - * The following peripherals are used by this module: - * - CAN (Control Area Network) - * - * The following devices can use this module: - * - SAMV71 - * - * The outline of this documentation is as follows: - * - \ref asfdoc_sam_mcan_prerequisites - * - \ref asfdoc_sam_mcan_module_overview - * - \ref asfdoc_sam_mcan_special_considerations - * - \ref asfdoc_sam_mcan_extra_info - * - \ref asfdoc_sam_mcan_examples - * - \ref asfdoc_sam_mcan_api_overview - * - * - * \section asfdoc_sam_mcan_prerequisites Prerequisites - * - * There are no prerequisites for this module. - * - * - * \section asfdoc_sam_mcan_module_overview Module Overview - * - * This driver provides an interface for the Control Area Network Controller - * functions on the device. - * - * - * \section asfdoc_sam_mcan_special_considerations Special Considerations - * - * There are no special considerations for this module. - * - * - * \section asfdoc_sam_mcan_extra_info Extra Information - * - * For extra information see \ref asfdoc_sam_mcan_extra. This includes: - * - \ref asfdoc_sam_mcan_extra_acronyms - * - \ref asfdoc_sam_mcan_extra_dependencies - * - \ref asfdoc_sam_mcan_extra_errata - * - \ref asfdoc_sam_mcan_extra_history - * - * - * \section asfdoc_sam_mcan_examples Examples - * - * For a list of examples related to this driver, see - * \ref asfdoc_sam_mcan_exqsg. - * - * - * \section asfdoc_sam_mcan_api_overview API Overview - * @{ - */ - -/** - * \name Module Setting - * @{ - */ - -/** - * \brief Can time out modes. - */ -enum mcan_timeout_mode { - /** Continuous operation. */ - MCAN_TIMEOUT_CONTINUES = MCAN_TOCC_TOS_CONTINUOUS, - /** Timeout controlled by TX Event FIFO. */ - MCAN_TIMEOUT_TX_EVEN_FIFO = MCAN_TOCC_TOS_TX_EV_TIMEOUT, - /** Timeout controlled by Rx FIFO 0. */ - MCAN_TIMEOUT_RX_FIFO_0 = MCAN_TOCC_TOS_RX0_EV_TIMEOUT, - /** Timeout controlled by Rx FIFO 1. */ - MCAN_TIMEOUT_RX_FIFO_1 = MCAN_TOCC_TOS_RX1_EV_TIMEOUT, -}; - -/** - * \brief Can nonmatching frames action. - */ -enum mcan_nonmatching_frames_action { - /** Accept in Rx FIFO 0. */ - MCAN_NONMATCHING_FRAMES_FIFO_0, - /** Accept in Rx FIFO 1. */ - MCAN_NONMATCHING_FRAMES_FIFO_1, - /** Reject. */ - MCAN_NONMATCHING_FRAMES_REJECT, -}; - -/** - * \brief MCAN software device instance structure. - * - * MCAN software instance structure, used to retain software state information - * of an associated hardware module instance. - * - * \note The fields of this structure should not be altered by the user - * application; they are reserved for module-internal use only. - */ -struct mcan_module -{ - Mcan *hw; - volatile TaskHandle taskWaitingOnFifo[2]; -}; - -/** - * \brief MCAN configuration structure. - * - * Configuration structure for an MCAN instance. This structure should be - * initialized by the \ref mcan_get_config_defaults() - * function before being modified by the user application. - */ -struct mcan_config { - /** MCAN run in standby control. */ - bool run_in_standby; - /** Start value of the Message RAM Watchdog Counter */ - uint8_t watchdog_configuration; - /** Transmit Pause. */ - bool transmit_pause; - /** Edge Filtering during Bus Integration. */ - bool edge_filtering; - /** Protocol Exception Handling. */ - bool protocol_exception_handling; - /** Automatic Retransmission. */ - bool automatic_retransmission; - /** Clock Stop Request. */ - bool clock_stop_request; - /** Clock Stop Acknowledge. */ - bool clock_stop_acknowledge; - /** Timestamp Counter Prescaler: 0x0-0xF */ - uint8_t timestamp_prescaler; - /** Timeout Period. */ - uint16_t timeout_period; - /** Timeout Mode. */ - enum mcan_timeout_mode timeout_mode; - /** Timeout enable. */ - bool timeout_enable; - /** Transceiver Delay Compensation enable. */ - bool tdc_enable; - /** Transmitter Delay Compensation Offset : 0x0-0x7F */ - uint8_t delay_compensation_offset; -#if (SAMV71B || SAME70B || SAMV70B) - /** Transmitter Delay Compensation Filter Window Length : 0x0-0x7F */ - uint8_t delay_compensation_filter_window_length; -#endif - /** Nonmatching frames action for standard frames. */ - enum mcan_nonmatching_frames_action nonmatching_frames_action_standard; - /** Nonmatching frames action for extended frames. */ - enum mcan_nonmatching_frames_action nonmatching_frames_action_extended; - /** Reject Remote Standard Frames. */ - bool remote_frames_standard_reject; - /** Reject Remote Extended Frames. */ - bool remote_frames_extended_reject; - /** Extended ID Mask: 0x0-0x1FFFFFFF. */ - uint32_t extended_id_mask; - /** Rx FIFO 0 Operation Mode. */ - bool rx_fifo_0_overwrite; - /** Rx FIFO 0 Watermark: 1-64, other value disable it. */ - uint8_t rx_fifo_0_watermark; - /** Rx FIFO 1 Operation Mode. */ - bool rx_fifo_1_overwrite; - /** Rx FIFO 1 Watermark: 1-64, other value disable it. */ - uint8_t rx_fifo_1_watermark; - /** Tx FIFO/Queue Mode, 0 for FIFO and 1 for Queue. */ - bool tx_queue_mode; - /** Tx Event FIFO Watermark: 1-32, other value disable it. */ - uint8_t tx_event_fifo_watermark; -}; - -/** - * \brief Initializes an MCAN configuration structure to defaults - * - * Initializes a given MCAN configuration struct to a set of known default - * values. This function should be called on any new instance of the - * configuration struct before being modified by the user application. - * - * The default configuration is as follows: - * \li Not run in standby mode - * \li Disable Watchdog - * \li Transmit pause enabled - * \li Edge filtering during bus integration enabled - * \li Protocol exception handling enabled - * \li Automatic retransmission enabled - * \li Clock stop request disabled - * \li Clock stop acknowledge disabled - * \li Timestamp Counter Prescaler 1 - * \li Timeout Period with 0xFFFF - * \li Timeout Mode: Continuous operation - * \li Disable Timeout - * \li Transmitter Delay Compensation Offset is 0 - * \li Transmitter Delay Compensation Filter Window Length is 0 - * \li Reject nonmatching standard frames - * \li Reject nonmatching extended frames - * \li Reject remote standard frames - * \li Reject remote extended frames - * \li Extended ID Mask is 0x1FFFFFFF - * \li Rx FIFO 0 Operation Mode: overwrite - * \li Disable Rx FIFO 0 Watermark - * \li Rx FIFO 1 Operation Mode: overwrite - * \li Disable Rx FIFO 1 Watermark - * \li Tx FIFO/Queue Mode: FIFO - * \li Disable Tx Event FIFO Watermark - * - * \param[out] config Pointer to configuration struct to initialize to - * default values - */ -static inline void mcan_get_config_defaults(struct mcan_config *const config) noexcept -{ - /* Sanity check arguments */ - Assert(config); - - /* Default configuration values */ - config->run_in_standby = false; - config->watchdog_configuration = 0x00; - config->transmit_pause = true; - config->edge_filtering = true; - config->protocol_exception_handling = true; - config->automatic_retransmission = true; - config->clock_stop_request = false; - config->clock_stop_acknowledge = false; - config->timestamp_prescaler = 0; - config->timeout_period = 0xFFFF; - config->timeout_mode = MCAN_TIMEOUT_CONTINUES; - config->timeout_enable = false; - config->tdc_enable = false; - config->delay_compensation_offset = 0; -#if (SAMV71B || SAME70B || SAMV70B) - config->delay_compensation_filter_window_length = 0; -#endif - config->nonmatching_frames_action_standard = MCAN_NONMATCHING_FRAMES_REJECT; - config->nonmatching_frames_action_extended = MCAN_NONMATCHING_FRAMES_REJECT; - config->remote_frames_standard_reject = true; - config->remote_frames_extended_reject = true; - config->extended_id_mask = 0x1FFFFFFF; - config->rx_fifo_0_overwrite = false; - config->rx_fifo_0_watermark = 0; - config->rx_fifo_1_overwrite = false; - config->rx_fifo_1_watermark = 0; - config->tx_queue_mode = false; - config->tx_event_fifo_watermark = 0; -} - -void mcan_init_once(mcan_module *const module_inst, Mcan *hw) noexcept; -void mcan_init(mcan_module *const module_inst, mcan_config *config) noexcept; -void mcan_start(mcan_module *const module_inst) noexcept; -void mcan_stop(mcan_module *const module_inst) noexcept; -void mcan_enable_fd_mode(mcan_module *const module_inst) noexcept; -void mcan_disable_fd_mode(mcan_module *const module_inst) noexcept; -void mcan_enable_restricted_operation_mode(mcan_module *const module_inst) noexcept; -void mcan_disable_restricted_operation_mode(mcan_module *const module_inst) noexcept; - -void mcan_enable_bus_monitor_mode(mcan_module *const module_inst) noexcept; -void mcan_disable_bus_monitor_mode(mcan_module *const module_inst) noexcept; -void mcan_enable_sleep_mode(mcan_module *const module_inst) noexcept; -void mcan_disable_sleep_mode(mcan_module *const module_inst) noexcept; -void mcan_enable_test_mode(mcan_module *const module_inst) noexcept; -void mcan_disable_test_mode(mcan_module *const module_inst) noexcept; - -// Send extended CAN message in FD mode using a dedicated transmit buffer. The transmit buffer must already be free. -status_code mcan_fd_send_ext_message_no_wait(mcan_module *const module_inst, uint32_t id_value, const uint8_t *data, size_t dataLength, uint32_t whichTxBuffer, bool bitRateSwitch, uint8_t marker) noexcept; - -// Wait for a specified buffer to become free. If it's still not free after the timeout, cancel the pending transmission. -// Return true if we cancelled the pending transmission. -bool WaitForTxBufferFree(mcan_module *const module_inst, uint32_t whichTxBuffer, uint32_t maxWait) noexcept; - -// Get a message from a FIFO with timeout. Return true if successful, false if we timed out -bool GetMessageFromFifo(mcan_module *const module_inst, CanMessageBuffer *buf, unsigned int fifoNumber, uint32_t timeout) noexcept; - -void GetLocalCanTiming(mcan_module *const module_inst, CanTiming& timing) noexcept; -void ChangeLocalCanTiming(mcan_module *const module_inst, const CanTiming& timing) noexcept; - -/** - * \brief Can read timestamp count value. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Timestamp count value. - */ -static inline uint16_t mcan_read_timestamp_count_value(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TSCV; -} - -/** - * \brief Can read timeout count value. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Timeout count value. - */ -static inline uint16_t mcan_read_timeout_count_value(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TOCV; -} - -/** - * \brief Can read error count. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Error count value. - */ -static inline uint32_t mcan_read_error_count(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_ECR; -} - -/** - * \brief Can read protocol status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return protocol status value. - */ -static inline uint32_t mcan_read_protocal_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_PSR; -} - -/** @} */ - -/** - * \name Rx Handling - * @{ - */ - -/** - * \brief Read high priority message status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return High priority message status value. - */ -static inline uint32_t mcan_read_high_priority_message_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_HPMS; -} - -/** - * \brief Get Rx buffer status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] index Index offset in Rx buffer - * - * \return Rx buffer status value. - * - * \retval true Rx Buffer updated from new message. - * \retval false Rx Buffer not updated. - */ -static inline bool mcan_rx_get_buffer_status(mcan_module *const module_inst, uint32_t index) noexcept -{ - if (index < 32) { - if (module_inst->hw->MCAN_NDAT1 & (1 << index)) { - return true; - } else { - return false; - } - } else { - index -= 32; - if (module_inst->hw->MCAN_NDAT2 & (1 << index)) { - return true; - } else { - return false; - } - } -} - -/** - * \brief Clear Rx buffer status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] index Index offset in Rx buffer - * - */ -static inline void mcan_rx_clear_buffer_status(mcan_module *const module_inst, uint32_t index) noexcept -{ - if (index < 32) { - module_inst->hw->MCAN_NDAT1 = (1 << index); - } else { - index -= 32; - module_inst->hw->MCAN_NDAT2 = (1 << index); - } -} - -/** - * \brief Get Rx FIFO status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] fifo_number Rx FIFO 0 or 1 - * - * \return Rx FIFO status value. - */ -static inline uint32_t mcan_rx_get_fifo_status(mcan_module *const module_inst, bool fifo_number) noexcept -{ - if (!fifo_number) { - return module_inst->hw->MCAN_RXF0S; - } else { - return module_inst->hw->MCAN_RXF1S; - } -} - -/** - * \brief Set Rx acknowledge. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] fifo_number Rx FIFO 0 or 1 - * \param[in] index Index offset in FIFO - */ -static inline void mcan_rx_fifo_acknowledge(mcan_module *const module_inst, bool fifo_number, uint32_t index) noexcept -{ - if (!fifo_number) { - module_inst->hw->MCAN_RXF0A = MCAN_RXF0A_F0AI(index); - } else { - module_inst->hw->MCAN_RXF1A = MCAN_RXF1A_F1AI(index); - } -} - -/** - * \brief Get the standard message filter default value. - * - * The default configuration is as follows: - * \li Classic filter: SFID1 = filter, SFID2 = mask - * \li Store in Rx FIFO 0 if filter matches - * \li SFID2 = 0x7FFul - * \li SFID1 = 0x0ul - * - * \param[out] sd_filter Pointer to standard filter element struct to initialize to default values - */ -static inline void mcan_get_standard_message_filter_element_default(mcan_standard_message_filter_element *sd_filter) noexcept -{ - sd_filter->S0.reg = MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID2_Msk | - MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFID1(0) | - MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC( - MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFEC_STF0M_Val) | - MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_SFT_CLASSIC; -} - -status_code mcan_set_rx_standard_filter(mcan_module *const module_inst, mcan_standard_message_filter_element *sd_filter, uint32_t index) noexcept; - -/** - * \brief Get the extended message filter default value. - * - * The default configuration is as follows: - * \li Classic filter: SFID1 = filter, SFID2 = mask - * \li Store in Rx FIFO 1 if filter matches - * \li SFID2 = 0x1FFFFFFFul - * \li SFID1 = 0x0ul - * - * \param[out] et_filter Pointer to extended filter element struct to initialize to default values - */ -static inline void mcan_get_extended_message_filter_element_default(mcan_extended_message_filter_element *et_filter) noexcept -{ - et_filter->F0.reg = MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFID1(0) | - MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC( - MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_EFEC_STF1M_Val); - et_filter->F1.reg = MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFID2_Msk | - MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_EFT_CLASSIC; -} - -status_code mcan_set_rx_extended_filter(mcan_module *const module_inst, struct mcan_extended_message_filter_element *et_filter, uint32_t index) noexcept; - -status_code mcan_get_rx_buffer_element(mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept; - -status_code mcan_get_rx_fifo_0_element(struct mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept; - -status_code mcan_get_rx_fifo_1_element(struct mcan_module *const module_inst, struct mcan_rx_element *rx_element, uint32_t index) noexcept; - -/** - * \brief Get Tx FIFO/Queue status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Tx FIFO/Queue status value. - */ -static inline uint32_t mcan_tx_get_fifo_queue_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TXFQS; -} - -/** - * \brief Get Tx buffer request pending status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Bit mask of Tx buffer request pending status value. - */ -static inline uint32_t mcan_tx_get_pending_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TXBRP; -} - -/** - * \brief Tx buffer add transfer request. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] trig_mask The mask value to trigger transfer buffer - * - * \return Status of the result. - * - * \retval STATUS_OK Set the transfer request. - * \retval STATUS_ERR_BUSY The module is in configuration. - */ -static inline enum status_code mcan_tx_transfer_request(mcan_module *const module_inst, uint32_t trig_mask) noexcept -{ - if (module_inst->hw->MCAN_CCCR & MCAN_CCCR_CCE) { - return ERR_BUSY; - } - module_inst->hw->MCAN_TXBAR = trig_mask; - return STATUS_OK; -} - -/** - * \brief Set Tx Queue operation. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] trig_mask The mask value to cancel transfer buffer - * - * \return Status of the result. - * - * \retval STATUS_OK Set the transfer request. - * \retval STATUS_BUSY The module is in configuration. - */ -static inline enum status_code mcan_tx_cancel_request(mcan_module *const module_inst, uint32_t trig_mask) noexcept -{ - if (module_inst->hw->MCAN_CCCR & MCAN_CCCR_CCE) { - return STATUS_ERR_BUSY; - } - module_inst->hw->MCAN_TXBCR = trig_mask; - return STATUS_OK; -} - -/** - * \brief Get Tx transmission status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Bit mask of Tx transmission status value. - */ -static inline uint32_t mcan_tx_get_transmission_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TXBTO; -} - -/** - * \brief Get Tx cancellation status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Bit mask of Tx cancellation status value. - */ -static inline uint32_t mcan_tx_get_cancellation_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TXBCF; -} - -/** - * \brief Get Tx event FIFO status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * - * \return Tx event FIFO status value. - */ -static inline uint32_t mcan_tx_get_event_fifo_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_TXEFS; -} - -/** - * \brief Set Tx Queue operation. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] index Index for the transfer FIFO - */ -static inline void mcan_tx_event_fifo_acknowledge(mcan_module *const module_inst, uint32_t index) noexcept -{ - module_inst->hw->MCAN_TXEFA = MCAN_TXEFA_EFAI(index); -} - -/** - * \brief Get the default transfer buffer element. - * - * The default configuration is as follows: - * \li 11-bit standard identifier - * \li Transmit data frame - * \li ID = 0x0ul - * \li Store Tx events - * \li Frame transmitted in Classic MCAN format - * \li Data Length Code is 8 - * - * \param[out] tx_element Pointer to transfer element struct to initialize to default values - */ -static inline void mcan_get_tx_buffer_element_defaults(mcan_tx_element *tx_element) noexcept -{ - tx_element->T0.reg = 0; - tx_element->T1.reg = MCAN_TX_ELEMENT_T1_EFC | - MCAN_TX_ELEMENT_T1_DLC(MCAN_TX_ELEMENT_T1_DLC_DATA8_Val); -} - -status_code mcan_set_tx_buffer_element(mcan_module *const module_inst, mcan_tx_element *tx_element, uint32_t index) noexcept; - -status_code mcan_get_tx_event_fifo_element(mcan_module *const module_inst, mcan_tx_event_element *tx_event_element, uint32_t index) noexcept; - -/** - * \brief Can module interrupt source. - * - * Enum for the interrupt source. - */ -enum mcan_interrupt_source { - /** Rx FIFO 0 New Message Interrupt Enable. */ - MCAN_RX_FIFO_0_NEW_MESSAGE = MCAN_IE_RF0NE, - /** Rx FIFO 0 Watermark Reached Interrupt Enable. */ - MCAN_RX_FIFO_0_WATERMARK = MCAN_IE_RF0WE, - /** Rx FIFO 0 Full Interrupt Enable. */ - MCAN_RX_FIFO_0_FULL = MCAN_IE_RF0FE, - /** Rx FIFO 0 Message Lost Interrupt Enable. */ - MCAN_RX_FIFO_0_LOST_MESSAGE = MCAN_IE_RF0LE, - /** Rx FIFO 1 New Message Interrupt Enable. */ - MCAN_RX_FIFO_1_NEW_MESSAGE = MCAN_IE_RF1NE, - /** Rx FIFO 1 Watermark Reached Interrupt Enable. */ - MCAN_RX_FIFO_1_WATERMARK = MCAN_IE_RF1WE, - /** Rx FIFO 1 Full Interrupt Enable. */ - MCAN_RX_FIFO_1_FULL = MCAN_IE_RF1FE, - /** Rx FIFO 1 Message Lost Interrupt Enable. */ - MCAN_RX_FIFO_1_MESSAGE_LOST = MCAN_IE_RF1LE, - /** High Priority Message Interrupt Enable. */ - MCAN_RX_HIGH_PRIORITY_MESSAGE = MCAN_IE_HPME, - /** Transmission Completed Interrupt Enable. */ - MCAN_TIMESTAMP_COMPLETE = MCAN_IE_TCE, - /** Transmission Cancellation Finished Interrupt Enable. */ - MCAN_TX_CANCELLATION_FINISH = MCAN_IE_TCFE, - /** Tx FIFO Empty Interrupt Enable. */ - MCAN_TX_FIFO_EMPTY = MCAN_IE_TFEE, - /** Tx Event FIFO New Entry Interrupt Enable. */ - MCAN_TX_EVENT_FIFO_NEW_ENTRY = MCAN_IE_TEFNE, - /** Tx Event FIFO Watermark Reached Interrupt Enable. */ - MCAN_TX_EVENT_FIFO_WATERMARK = MCAN_IE_TEFWE, - /** Tx Event FIFO Full Interrupt Enable. */ - MCAN_TX_EVENT_FIFO_FULL = MCAN_IE_TEFFE, - /** Tx Event FIFO Element Lost Interrupt Enable. */ - MCAN_TX_EVENT_FIFO_ELEMENT_LOST = MCAN_IE_TEFLE, - /** Timestamp Wraparound Interrupt Enable. */ - MCAN_TIMESTAMP_WRAPAROUND = MCAN_IE_TSWE, - /** Message RAM Access Failure Interrupt Enable. */ - MCAN_MESSAGE_RAM_ACCESS_FAILURE = MCAN_IE_MRAFE, - /** Timeout Occurred Interrupt Enable. */ - MCAN_TIMEOUT_OCCURRED = MCAN_IE_TOOE, - /** Message stored to Dedicated Rx Buffer Interrupt Enable. */ - MCAN_RX_BUFFER_NEW_MESSAGE = MCAN_IE_DRXE, - /** Error Logging Overflow Interrupt Enable. */ - MCAN_ERROR_LOGGING_OVERFLOW = MCAN_IE_ELOE, - /** Error Passive Interrupt Enable. */ - MCAN_ERROR_PASSIVE = MCAN_IE_EPE, - /** Warning Status Interrupt Enable. */ - MCAN_WARNING_STATUS = MCAN_IE_EWE, - /** Bus_Off Status Interrupt Enable. */ - MCAN_BUS_OFF = MCAN_IE_BOE, - /** Watchdog Interrupt Enable. */ - MCAN_WATCHDOG = MCAN_IE_WDIE, - /**CRC Error Interrupt Enable */ - MCAN_CRC_ERROR = MCAN_IE_CRCEE, - /** Bit Error Interrupt Enable. */ - MCAN_BIT_ERROR = MCAN_IE_BEE, - /** Acknowledge Error Interrupt Enable . */ - MCAN_ACKNOWLEDGE_ERROR = MCAN_IE_ACKEE, - /** Format Error Interrupt Enable */ - MCAN_FORMAT_ERROR = MCAN_IE_FOEE, - /** Stuff Error Interrupt Enable */ - MCAN_STUFF_ERROR = MCAN_IE_STEE -}; - -/** - * \brief Enable MCAN interrupt. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] source Interrupt source type - */ -static inline void mcan_enable_interrupt(mcan_module *const module_inst, const mcan_interrupt_source source) noexcept -{ - module_inst->hw->MCAN_IE |= source; -} - -/** - * \brief Disable MCAN interrupt. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] source Interrupt source type - */ -static inline void mcan_disable_interrupt(mcan_module *const module_inst, const mcan_interrupt_source source) noexcept -{ - module_inst->hw->MCAN_IE &= ~source; -} - -/** - * \brief Get MCAN interrupt status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - */ -static inline uint32_t mcan_read_interrupt_status(mcan_module *const module_inst) noexcept -{ - return module_inst->hw->MCAN_IR; -} - -/** - * \brief Clear MCAN interrupt status. - * - * \param[in] module_inst Pointer to the MCAN software instance struct - * \param[in] source Interrupt source type - * - * \return Bit mask of interrupt status value. - */ -static inline void mcan_clear_interrupt_status(mcan_module *const module_inst, const mcan_interrupt_source source) noexcept -{ - module_inst->hw->MCAN_IR = source; -} - -#endif - -#endif /* SRC_HARDWARE_CANDRIVER_H_ */ diff --git a/src/Hardware/SAME70/Devices.cpp b/src/Hardware/SAME70/Devices.cpp new file mode 100644 index 00000000..1b26e627 --- /dev/null +++ b/src/Hardware/SAME70/Devices.cpp @@ -0,0 +1,77 @@ +/* + * Devices.cpp + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#include "Devices.h" +#include <RepRapFirmware.h> +#include <AnalogIn.h> +#include <AnalogOut.h> +#include <matrix/matrix.h> + +AsyncSerial Serial(UART2, UART2_IRQn, ID_UART2, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +USARTClass Serial1(USART2, USART2_IRQn, ID_USART2, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +SerialCDC SerialUSB; + +void UART2_Handler(void) noexcept +{ + Serial.IrqHandler(); +} + +void USART2_Handler(void) noexcept +{ + Serial1.IrqHandler(); +} + +void SerialInit() noexcept +{ + SetPinFunction(APIN_Serial0_RXD, Serial0PinFunction); + SetPinFunction(APIN_Serial0_TXD, Serial0PinFunction); + SetPullup(APIN_Serial0_RXD, true); + + SetPinFunction(APIN_Serial1_RXD, Serial1PinFunction); + SetPinFunction(APIN_Serial1_TXD, Serial1PinFunction); + SetPullup(APIN_Serial1_RXD, true); +} + +void SdhcInit() noexcept +{ + SetPinFunction(HsmciMclkPin, HsmciMclkPinFunction); + for (Pin p : HsmciOtherPins) + { + SetPinFunction(p, HsmciOtherPinsFunction); + SetPullup(p, true); + } +} + +void EthernetInit() noexcept +{ + // Initialize Ethernet pins + pinMode(EthernetPhyInterruptPin, INPUT_PULLUP); + for (Pin p : EthernetPhyOtherPins) + { + SetPinFunction(p, EthernetPhyOtherPinsFunction); + } +} + +// Device initialisation +void DeviceInit() noexcept +{ + LegacyAnalogIn::AnalogInInit(); + AnalogOut::Init(); + + SerialInit(); + SdhcInit(); + EthernetInit(); + + // Set up PB4..PB5 as normal I/O, not JTAG + matrix_set_system_io(CCFG_SYSIO_SYSIO4 | CCFG_SYSIO_SYSIO5); +} + +void StopAnalogTask() noexcept +{ +} + +// End diff --git a/src/Hardware/SAME70/Devices.h b/src/Hardware/SAME70/Devices.h new file mode 100644 index 00000000..4a924d9b --- /dev/null +++ b/src/Hardware/SAME70/Devices.h @@ -0,0 +1,26 @@ +/* + * Devices.h + * + * Created on: 11 Aug 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAME70_DEVICES_H_ +#define SRC_HARDWARE_SAME70_DEVICES_H_ + +#include <AsyncSerial.h> +typedef AsyncSerial UARTClass; +#include <USARTClass.h> + +extern AsyncSerial Serial; +extern USARTClass Serial1; + +#define SUPPORT_USB 1 // needed by SerialCDC.h +#include "SerialCDC.h" + +extern SerialCDC SerialUSB; + +void DeviceInit() noexcept; +void StopAnalogTask() noexcept; + +#endif /* SRC_HARDWARE_SAME70_DEVICES_H_ */ diff --git a/src/Hardware/SAME70/Main.cpp b/src/Hardware/SAME70/Main.cpp new file mode 100644 index 00000000..4d26da64 --- /dev/null +++ b/src/Hardware/SAME70/Main.cpp @@ -0,0 +1,16 @@ +/* + * Main.cpp + * Program entry point + * Created on: 11 Jul 2020 + * Author: David + * License: GNU GPL version 3 + */ + +#include <CoreIO.h> + +// Program initialisation +void AppInit() noexcept +{ +} + +// End diff --git a/src/Hardware/SAME70/PinDescription.h b/src/Hardware/SAME70/PinDescription.h new file mode 100644 index 00000000..77c80971 --- /dev/null +++ b/src/Hardware/SAME70/PinDescription.h @@ -0,0 +1,49 @@ +/* + * PinDescription.h + * + * Created on: 10 Jul 2020 + * Author: David + */ + +#ifndef SRC_HARDWARE_SAME70_PINDESCRIPTION_H_ +#define SRC_HARDWARE_SAME70_PINDESCRIPTION_H_ + +#include <CoreIO.h> + +// Enum to represent allowed types of pin access +// We don't have a separate bit for servo, because Duet PWM-capable ports can be used for servos if they are on the Duet main board +enum class PinCapability: uint8_t +{ + // Individual capabilities + none = 0, + read = 1, + ain = 2, + write = 4, + pwm = 8, + + // Combinations + ainr = 1|2, + rw = 1|4, + wpwm = 4|8, + rwpwm = 1|4|8, + ainrw = 1|2|4, + ainrwpwm = 1|2|4|8 +}; + +constexpr inline PinCapability operator|(PinCapability a, PinCapability b) noexcept +{ + return (PinCapability)((uint8_t)a | (uint8_t)b); +} + +// The pin description says what functions are available on each pin, filtered to avoid allocating the same function to more than one pin.. +// It is a struct not a class so that it can be direct initialised in read-only memory. +struct PinDescription : public PinDescriptionBase +{ + PinCapability cap; + const char* pinNames; + + PinCapability GetCapability() const noexcept { return cap; } + const char* GetNames() const noexcept { return pinNames; } +}; + +#endif /* SRC_HARDWARE_SAME70_PINDESCRIPTION_H_ */ diff --git a/src/Hardware/SAME70/same70q20b_flash.ld b/src/Hardware/SAME70/same70q20b_flash.ld new file mode 100644 index 00000000..5cfabe2f --- /dev/null +++ b/src/Hardware/SAME70/same70q20b_flash.ld @@ -0,0 +1,184 @@ +/** + * \file + * + * Copyright (c) 2015 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/*------------------------------------------------------------------------------ + * Linker script for running in internal FLASH on the ATSAME70Q20 + *----------------------------------------------------------------------------*/ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +/* We put the non-cached RAM at the start of RAM because the CAN buffers must be within the first 64kb. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00400000, LENGTH = 0x00100000 + ram_not_cached (rw) : ORIGIN = 0x20400000, LENGTH = 0x00018000 /* we currently allocate 96kb of non-cached RAM */ + ram (rwx) : ORIGIN = 0x20418000, LENGTH = 0x00048000 /* that leaves 288Kb of cached RAM */ +} + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + .ARM.exidx : + { + __exidx_start = .; + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + __exidx_end = .; + } > rom + + . = ALIGN(4); + _etext = .; + + .ram_nocache (NOLOAD) : + { + . = ALIGN(4); + _szero_nocache = .; + *(.CanMessage .CanMessage.*) + *(.ram_nocache .ram_nocache.*) + . = ALIGN(4); + _ezero_nocache = .; + } > ram_not_cached + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + . = ALIGN(4); + _eramfunc = .; + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + _firmware_crc = _etext + (_erelocate - _srelocate); /* We append the CRC32 to the binary file. This is its offset in memory. */ + + /* .bss section which is used for uninitialized data */ + .bss ALIGN(4) (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + . = ALIGN(4); + _end = . ; + + /* .stack_dummy section doesn't contains any symbols. It is only + used for linker to calculate size of stack sections, and assign + values to stack symbols later */ + .stack_dummy : + { + *(.stack*) + } > ram + + /* Set stack top to end of ram, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(ram) + LENGTH(ram); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(_sstack = __StackLimit); + PROVIDE(_estack = __StackTop); + + PROVIDE(_nocache_ram_start = ORIGIN(ram_not_cached)); + PROVIDE(_nocache_ram_end = ORIGIN(ram_not_cached) + LENGTH(ram_not_cached)); +} + diff --git a/src/Hardware/SharedSpi/SharedSpiDevice.cpp b/src/Hardware/SharedSpi/SharedSpiDevice.cpp index 31b9bebf..a52486c1 100644 --- a/src/Hardware/SharedSpi/SharedSpiDevice.cpp +++ b/src/Hardware/SharedSpi/SharedSpiDevice.cpp @@ -15,6 +15,9 @@ # include <peripheral_clk_config.h> # include <hri_sercom_e54.h> #elif USART_SPI +# if SAME70 || SAM4E || SAM4S +# include <pmc/pmc.h> +# endif # include <usart/usart.h> #else # include <spi/spi.h> @@ -344,9 +347,9 @@ void SharedSpiDevice::Init() noexcept SetPinFunction(SharedSpiSclkPin, SharedSpiPinFunction); mainSharedSpiDevice = new SharedSpiDevice(SharedSpiSercomNumber); #elif USART_SPI - ConfigurePin(APIN_USART_SSPI_SCK); - ConfigurePin(APIN_USART_SSPI_MOSI); - ConfigurePin(APIN_USART_SSPI_MISO); + SetPinFunction(APIN_USART_SSPI_SCK, USARTSPISckPeriphMode); + SetPinFunction(APIN_USART_SSPI_MOSI, USARTSPIMosiPeriphMode); + SetPinFunction(APIN_USART_SSPI_MISO, USARTSPIMisoPeriphMode); mainSharedSpiDevice = new SharedSpiDevice(0); #else ConfigurePin(g_APinDescription[APIN_SHARED_SPI_SCK]); |