mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-26 17:46:14 +01:00
RP2040 now works, but is unoptimized.
This commit is contained in:
parent
c2d5e55a40
commit
09c2c032cc
1
.gitignore
vendored
1
.gitignore
vendored
|
@ -13,3 +13,4 @@ myFilter.cpp
|
|||
my*.h
|
||||
!my*.example.h
|
||||
compile_commands.json
|
||||
*.yaml
|
||||
|
|
|
@ -69,6 +69,11 @@
|
|||
void setup()
|
||||
{
|
||||
// The main sketch has responsibilities during setup()
|
||||
pinMode(LED_BUILTIN, OUTPUT);
|
||||
digitalWrite(LED_BUILTIN, LOW);
|
||||
|
||||
while(!Serial)
|
||||
delay(100);
|
||||
|
||||
// Responsibility 1: Start the usb connection for diagnostics
|
||||
// This is normally Serial but uses SerialUSB on a SAMD processor
|
||||
|
|
|
@ -42,11 +42,26 @@ INTERRUPT_CALLBACK interruptHandler=0;
|
|||
#define ALARM_NUM 0
|
||||
#define ALARM_IRQ TIMER_IRQ_0
|
||||
|
||||
static uint32_t dcc_signal_time = 0;
|
||||
|
||||
static void alarm_irq(void) {
|
||||
// Clear the alarm irq
|
||||
hw_clear_bits(&timer_hw->intr, 1u << ALARM_NUM);
|
||||
// Reload timer
|
||||
uint64_t target = timer_hw->timerawl + dcc_signal_time;
|
||||
timer_hw->alarm[ALARM_NUM] = (uint32_t) target;
|
||||
|
||||
if (interruptHandler)
|
||||
interruptHandler();
|
||||
}
|
||||
|
||||
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
||||
interruptHandler = callback;
|
||||
dcc_signal_time = DCC_SIGNAL_TIME;
|
||||
// Enable the interrupt for our alarm (the timer outputs 4 alarm irqs)
|
||||
hw_set_bits(&timer_hw->inte, 1u << ALARM_NUM);
|
||||
// Set irq handler for alarm irq
|
||||
irq_set_exclusive_handler(ALARM_IRQ, callback);
|
||||
irq_set_exclusive_handler(ALARM_IRQ, alarm_irq);
|
||||
// Enable the alarm irq
|
||||
irq_set_enabled(ALARM_IRQ, true);
|
||||
// Enable interrupt in block and at processor
|
||||
|
@ -54,7 +69,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
|||
// Alarm is only 32 bits so if trying to delay more
|
||||
// than that need to be careful and keep track of the upper
|
||||
// bits
|
||||
uint64_t target = timer_hw->timerawl + DCC_SIGNAL_TIME;
|
||||
uint64_t target = timer_hw->timerawl + dcc_signal_time;
|
||||
|
||||
// Write the lower 32 bits of the target time to the alarm which
|
||||
// will arm it
|
||||
|
@ -148,4 +163,3 @@ void ADCee::begin() {
|
|||
}
|
||||
|
||||
#endif // RP2040
|
||||
|
||||
|
|
|
@ -62,7 +62,7 @@ const bool signalTransform[]={
|
|||
/* WAVE_PENDING (should not happen) -> */ LOW};
|
||||
|
||||
void DCCWaveform::begin() {
|
||||
DCCTimer::begin(DCCWaveform::interruptHandler);
|
||||
DCCTimer::begin(DCCWaveform::interruptHandler);
|
||||
}
|
||||
|
||||
void DCCWaveform::loop() {
|
||||
|
@ -71,7 +71,10 @@ void DCCWaveform::loop() {
|
|||
|
||||
#pragma GCC push_options
|
||||
#pragma GCC optimize ("-O3")
|
||||
static uint32_t blinker = 0;
|
||||
void DCCWaveform::interruptHandler() {
|
||||
if (!(blinker++ % 25000))
|
||||
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
|
||||
// call the timer edge sensitive actions for progtrack and maintrack
|
||||
// member functions would be cleaner but have more overhead
|
||||
byte sigMain=signalTransform[mainTrack.state];
|
||||
|
|
|
@ -91,7 +91,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
|||
}
|
||||
}
|
||||
else dualSignal=false;
|
||||
|
||||
|
||||
if (brake_pin!=UNUSED_PIN){
|
||||
invertBrake=brake_pin < 0;
|
||||
if (invertBrake)
|
||||
|
@ -446,8 +446,6 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
|
|||
PortGroup *port = digitalPinToPort(pin);
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
GPIO_TypeDef *port = digitalPinToPort(pin);
|
||||
#elif defined(ARDUINO_ARCH_RP2040)
|
||||
volatile uint32_t port = 0;
|
||||
#else
|
||||
uint8_t port = digitalPinToPort(pin);
|
||||
#endif
|
||||
|
|
|
@ -61,6 +61,10 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
|||
#define PORTC GPIOC->ODR
|
||||
#define HAVE_PORTC(X) X
|
||||
#endif
|
||||
#if defined(ARDUINO_ARCH_RP2040)
|
||||
#define HAVE_PORTA(X) X
|
||||
#define PORTA (sio_hw->gpio_out)
|
||||
#endif
|
||||
|
||||
// if macros not defined as pass-through we define
|
||||
// them here as someting that is valid as a
|
||||
|
|
|
@ -59,7 +59,21 @@
|
|||
|
||||
// Arduino STANDARD Motor Shield, used on different architectures:
|
||||
|
||||
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
||||
#if defined(ARDUINO_ARCH_RP2040)
|
||||
// Standard Motor Shield definition for RP2040
|
||||
// This setup is for the iLabs Challenger NB RP2040 WiFi board. Other boards likely need
|
||||
// a separate setup.
|
||||
#define STANDARD_MOTOR_SHIELD "STANDARD_MOTOR_SHIELD", \
|
||||
new MotorDriver(D17, D16, UNUSED_PIN, D15, A0, 0.488, 1500, UNUSED_PIN), \
|
||||
new MotorDriver(D14, D13, UNUSED_PIN, D12, A1, 0.488, 1500, UNUSED_PIN)
|
||||
#define RP2040_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
|
||||
|
||||
// EX 8874 based shield connected to a 3V3 system with 12-bit (4096) ADC
|
||||
#define EX8874_SHIELD "EX8874", \
|
||||
new MotorDriver(D17, D16, UNUSED_PIN, D15, A0, 1.27, 5000, A4), \
|
||||
new MotorDriver(D14, D13, UNUSED_PIN, D12, A1, 1.27, 5000, A5)
|
||||
|
||||
#elif defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
||||
// Standard Motor Shield definition for 3v3 processors (other than the ESP32)
|
||||
// Setup for SAMD21 Sparkfun DEV board MUST use Arduino Motor Shield R3 (MUST be R3
|
||||
// for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using
|
||||
|
|
Loading…
Reference in New Issue
Block a user