Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
Diffstat (limited to 'src/Hardware/SAM4E')
-rw-r--r--src/Hardware/SAM4E/Devices.cpp76
-rw-r--r--src/Hardware/SAM4E/Devices.h29
-rw-r--r--src/Hardware/SAM4E/Main.cpp26
-rw-r--r--src/Hardware/SAM4E/PinDescription.h49
-rw-r--r--src/Hardware/SAM4E/sam4e8e_flash.ld152
5 files changed, 332 insertions, 0 deletions
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);
+}