From 83325ebf78d9f0e654cb5bf029126d1bfbea26ad Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Thu, 23 Mar 2023 08:44:25 +1100 Subject: [PATCH 01/83] Initial I2C native driver --- I2CManager_STM32.h | 322 ++++++++++++++++++++++++++++++++++----------- 1 file changed, 242 insertions(+), 80 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index a55fd2e..58a623d 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -38,7 +38,10 @@ * bus on the SAMD architecture ***************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) -void I2C1_IRQHandler() { +extern "C" void I2C1_EV_IRQHandler(void) { + I2CManager.handleInterrupt(); +} +extern "C" void I2C1_ER_IRQHandler(void) { I2CManager.handleInterrupt(); } #endif @@ -91,44 +94,60 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Use 10x the rise time spec to enable integer divide of 62.5ns clock period uint16_t t_rise; uint32_t ccr_freq; - if (i2cClockSpeed < 200000L) { - // i2cClockSpeed = 100000L; - t_rise = 0x11; // (1000ns /62.5ns) + 1; - } - else if (i2cClockSpeed < 800000L) + + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Disable the I2C device, as TRISE can only be programmed whilst disabled + s->CR1 &= ~(I2C_CR1_PE); // Disable I2C + // Software reset the I2C peripheral + // s->CR1 |= I2C_CR1_SWRST; // reset the I2C + // delay(1); + // Release reset + // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + + if (i2cClockSpeed > 100000L) { - i2cClockSpeed = 400000L; - t_rise = 0x06; // (300ns / 62.5ns) + 1; - // } else if (i2cClockSpeed < 1200000L) { - // i2cClockSpeed = 1000000L; - // t_rise = 120; + if (i2cClockSpeed > 400000L) + i2cClockSpeed = 400000L; + + t_rise = 0x06; // (300ns /62.5ns) + 1; } else { i2cClockSpeed = 100000L; t_rise = 0x11; // (1000ns /62.5ns) + 1; } + // Configure the rise time register + s->TRISE = t_rise; - // Enable the I2C master mode - s->CR1 &= ~(I2C_CR1_PE); // Enable I2C - // Software reset the I2C peripheral - // s->CR1 |= I2C_CR1_SWRST; // reset the I2C - // Release reset - // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation - - // Calculate baudrate - using a rise time appropriate for the speed + // DIAG(F("Setting I2C clock to: %d"), i2cClockSpeed); + // Calculate baudrate ccr_freq = I2C_BUSFREQ * 1000000 / i2cClockSpeed / 2; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = (uint16_t)ccr_freq; - - // Configure the rise time register - s->TRISE = t_rise; // 1000 ns / 62.5 ns = 16 + 1 + if (i2cClockSpeed > 100000L) + s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set + else + s->CCR = (uint16_t)ccr_freq; // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + digitalWrite(D13, HIGH); + DIAG(F("I2C: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -136,32 +155,46 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { ***************************************************************************/ void I2CManagerClass::I2C_init() { - //Setting up the clocks - RCC->APB1ENR |= (1<<21); // Enable I2C CLOCK - RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9 + // Setting up the clocks + RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK + // Reset the I2C1 peripheral to initial state + RCC->APB1RSTR |= RCC_APB1RSTR_I2C1RST; + RCC->APB1RSTR &= ~RCC_APB1RSTR_I2C1RST; // Standard I2C pins are SCL on PB8 and SDA on PB9 + RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9 // Bits (17:16)= 1:0 --> Alternate Function for Pin PB8; // Bits (19:18)= 1:0 --> Alternate Function for Pin PB9 + GPIOB->MODER &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all MODER bits for PB8 and PB9 GPIOB->MODER |= (2<<(8*2)) | (2<<(9*2)); // PB8 and PB9 set to ALT function GPIOB->OTYPER |= (1<<8) | (1<<9); // PB8 and PB9 set to open drain output capability GPIOB->OSPEEDR |= (3<<(8*2)) | (3<<(9*2)); // PB8 and PB9 set to High Speed mode + GPIOB->PUPDR &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all PUPDR bits for PB8 and PB9 GPIOB->PUPDR |= (1<<(8*2)) | (1<<(9*2)); // PB8 and PB9 set to pull-up capability // Alt Function High register routing pins PB8 and PB9 for I2C1: // Bits (3:2:1:0) = 0:1:0:0 --> AF4 for pin PB8 // Bits (7:6:5:4) = 0:1:0:0 --> AF4 for pin PB9 + GPIOB->AFR[1] &= ~((15<<0) | (15<<4)); // Clear all AFR bits for PB8 on low nibble, PB9 on next nibble up GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up - // Software reset the I2C peripheral + // // Software reset the I2C peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C - s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + asm("nop"); // wait a bit... suggestion from online! + s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + // Clear all bits in I2C CR2 register except reserved bits + s->CR2 &= 0xE000; // Program the peripheral input clock in CR2 Register in order to generate correct timings s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz + // set own address to 00 - not really used in master mode + I2C1->OAR1 |= (1 << 14); // bit 14 should be kept at 1 according to the datasheet + #if defined(I2C_USE_INTERRUPTS) // Setting NVIC - NVIC_SetPriority(I2C_IRQn, 1); // Match default priorities - NVIC_EnableIRQ(I2C_IRQn); + NVIC_SetPriority(I2C1_EV_IRQn, 1); // Match default priorities + NVIC_EnableIRQ(I2C1_EV_IRQn); + NVIC_SetPriority(I2C1_ER_IRQn, 1); // Match default priorities + NVIC_EnableIRQ(I2C1_ER_IRQn); // CR2 Interrupt Settings // Bit 15-13: reserved @@ -172,8 +205,8 @@ void I2CManagerClass::I2C_init() // Bit 8: ITERREN - Error interrupt enable // Bit 7-6: reserved // Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz) - // s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts - s->CR2 |= 0x0300; // Enable Event and Error interrupts + s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts + // s->CR2 |= 0x0300; // Enable Event and Error interrupts #endif // Calculate baudrate and set default rate for now @@ -181,14 +214,26 @@ void I2CManagerClass::I2C_init() // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = 0x0050; + s->CCR = 0x50; // Configure the rise time register - max allowed in 1000ns s->TRISE = 0x0011; // 1000 ns / 62.5 ns = 16 + 1 // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Setting bus idle mode and wait for sync + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + DIAG(F("I2C: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -198,49 +243,56 @@ void I2CManagerClass::I2C_sendStart() { // Set counters here in case this is a retry. rxCount = txCount = 0; - uint8_t temp; - - // On a single-master I2C bus, the start bit won't be sent until the bus - // state goes to IDLE so we can request it without waiting. On a - // multi-master bus, the bus may be BUSY under control of another master, + // On a single-master I2C bus, the start bit won't be sent until the bus + // state goes to IDLE so we can request it without waiting. On a + // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. - // If anything to send, initiate write. Otherwise initiate read. - if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) - { - // Send start for read operation - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 |= I2C_CR1_START; // Generate START - // Send address with read flag (1) or'd in - s->DR = (deviceAddress << 1) | 1; // send the address - while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set - // Special case for 1 byte reads! - if (bytesToReceive == 1) - { - s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit - temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition - s->CR1 |= I2C_CR1_STOP; // Stop I2C + // Send start for read operation + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; } - else - temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit } - else { - // Send start for write operation - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 |= I2C_CR1_START; // Generate START - // Send address with write flag (0) or'd in - s->DR = (deviceAddress << 1) | 0; // send the address - while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set - temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + if (timeout) { + DIAG(F("I2C_sendStart: SR2->BUSY timeout")); + // delay(1000); } + s->CR1 |= I2C_CR1_ACK; // Enable the ACK + s->CR1 &= ~(I2C_CR1_POS); // Reset the POS bit - only used for 2-byte reception + s->CR1 |= I2C_CR1_START; // Generate START } /*************************************************************************** * Initiate a stop bit for transmission (does not interrupt) ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { - s->CR1 |= I2C_CR1_STOP; // Stop I2C + uint32_t temp; + + s->CR1 |= I2C_CR1_STOP; // Stop I2C + temp = s->SR1 | s->SR2; // Read the status registers to clear them + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + DIAG(F("I2C_sendStop: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -252,9 +304,11 @@ void I2CManagerClass::I2C_close() { s->CR1 &= ~I2C_CR1_PE; // Disable I2C peripheral // Should never happen, but wait for up to 500us only. unsigned long startTime = micros(); - while ((s->CR1 && I2C_CR1_PE) != 0) { + while ((s->CR1 & I2C_CR1_PE) != 0) { if (micros() - startTime >= 500UL) break; } + NVIC_DisableIRQ(I2C1_EV_IRQn); + NVIC_DisableIRQ(I2C1_ER_IRQn); } /*************************************************************************** @@ -263,50 +317,158 @@ void I2CManagerClass::I2C_close() { * (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()). ***************************************************************************/ void I2CManagerClass::I2C_handleInterrupt() { + volatile uint16_t temp_sr1, temp_sr2, temp; + static bool led_lit = false; - if (s->SR1 && I2C_SR1_ARLO) { + temp_sr1 = s->SR1; + // if (temp_sr1 & I2C_SR1_ADDR) + // temp_sr2 = s->SR2; + + // Check to see if start bit sent - SB interrupt! + if (temp_sr1 & I2C_SR1_SB) + { + // If anything to send, initiate write. Otherwise initiate read. + if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) + { + // Send address with read flag (1) or'd in + s->DR = (deviceAddress << 1) | 1; // send the address + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // // // Special case for 1 byte reads! + // if (bytesToReceive == 1) + // { + // s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit + // temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition + // s->CR1 |= I2C_CR1_STOP; // Stop I2C + // } + // else + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else + { + // Send address with write flag (0) or'd in + s->DR = (deviceAddress << 1) | 0; // send the address + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else if (temp_sr1 & I2C_SR1_ADDR) { + // Receive 1 byte (AN2824 figure 2) + if (bytesToReceive == 1) { + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK final byte + // EV6_1 must be atomic operation (AN2824) + // noInterrupts(); + (void)s->SR2; // read SR2 to complete clearing the ADDR bit + I2C_sendStop(); // send stop + // interrupts(); + } + // Receive 2 bytes (AN2824 figure 2) + else if (bytesToReceive == 2) { + s->CR1 |= I2C_CR1_POS; // Set POS flag (NACK position next) + // EV6_1 must be atomic operation (AN2824) + // noInterrupts(); + (void)s->SR2; // read SR2 to complete clearing the ADDR bit + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK byte + // interrupts(); + } + else + temp = temp_sr1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else if (temp_sr1 & I2C_SR1_AF) + { + s->SR1 &= ~(I2C_SR1_AF); // Clear AF + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + while (s->SR1 & I2C_SR1_AF); // Check AF cleared + I2C_sendStop(); // Clear the bus + completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; + state = I2C_STATE_COMPLETED; + } + else if (temp_sr1 & I2C_SR1_ARLO) + { // Arbitration lost, restart - I2C_sendStart(); // Reinitiate request - } else if (s->SR1 && I2C_SR1_BERR) { + s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + I2C_sendStop(); + I2C_sendStart(); // Reinitiate request + // state = I2C_STATE_COMPLETED; + } + else if (temp_sr1 & I2C_SR1_BERR) + { // Bus error + s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + I2C_sendStop(); // Clear the bus completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; - } else if (s->SR1 && I2C_SR1_TXE) { + } + else if (temp_sr1 & I2C_SR1_TXE) + { + // temp_sr2 = s->SR2; // Master write completed - if (s->SR1 && (1<<10)) { - // Nacked, send stop. + if (temp_sr1 & I2C_SR1_AF) { + // Nacked + s->SR1 &= ~(I2C_SR1_AF); // Clear AF + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + // send stop. I2C_sendStop(); completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; state = I2C_STATE_COMPLETED; } else if (bytesToSend) { // Acked, so send next byte + while ((s->SR1 & I2C_SR1_BTF)); // Check BTF before proceeding s->DR = sendBuffer[txCount++]; bytesToSend--; - } else if (bytesToReceive) { - // Last sent byte acked and no more to send. Send repeated start, address and read bit. + // } else if (bytesToReceive) { + // // Last sent byte acked and no more to send. Send repeated start, address and read bit. + // s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + // I2C_sendStart(); // s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1; } else { + // No bytes left to send or receive // Check both TxE/BTF == 1 before generating stop - while (!(s->SR1 && I2C_SR1_TXE)); // Check TxE - while (!(s->SR1 && I2C_SR1_BTF)); // Check BTF + // while (!(s->SR1 & I2C_SR1_TXE)); // Check TxE + while ((s->SR1 & I2C_SR1_BTF)); // Check BTF // No more data to send/receive. Initiate a STOP condition and finish + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK I2C_sendStop(); + // completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } - } else if (s->SR1 && I2C_SR1_RXNE) { + } + else if (temp_sr1 & I2C_SR1_RXNE) + { // Master read completed without errors if (bytesToReceive == 1) { -// s->I2CM.CTRLB.bit.ACKACT = 1; // NAK final byte + s->CR1 &= ~I2C_CR1_ACK; // NAK final byte I2C_sendStop(); // send stop receiveBuffer[rxCount++] = s->DR; // Store received byte bytesToReceive = 0; + // completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; - } else if (bytesToReceive) { -// s->I2CM.CTRLB.bit.ACKACT = 0; // ACK all but final byte + } + else if (bytesToReceive == 2) + { + // Also needs to be atomic! + // noInterrupts(); + I2C_sendStop(); receiveBuffer[rxCount++] = s->DR; // Store received byte + // interrupts(); + } + else if (bytesToReceive) + { + s->CR1 &= ~(I2C_CR1_ACK); // ACK all but final byte + receiveBuffer[rxCount++] = s->DR; // Store received byte bytesToReceive--; } } + else + { + // DIAG(F("Unhandled I2C interrupt!")); + led_lit = ~led_lit; + digitalWrite(D13, led_lit); + // delay(1000); + } } #endif /* I2CMANAGER_STM32_H */ From cc2846d932461ace1c546d956812f943f78adaa0 Mon Sep 17 00:00:00 2001 From: Neil McKechnie <neilmck999@gmail.com> Date: Mon, 27 Mar 2023 00:20:59 +0100 Subject: [PATCH 02/83] STM32 Native I2C first working version Working for reads and writes, needs more testing and perhaps a polish. --- I2CManager.h | 3 +- I2CManager_STM32.h | 437 +++++++++++++++++++++------------------------ defines.h | 6 +- 3 files changed, 213 insertions(+), 233 deletions(-) diff --git a/I2CManager.h b/I2CManager.h index b1003e6..ede30cc 100644 --- a/I2CManager.h +++ b/I2CManager.h @@ -539,7 +539,8 @@ private: uint8_t deviceAddress; const uint8_t *sendBuffer; uint8_t *receiveBuffer; - + uint8_t transactionState = 0; + volatile uint32_t pendingClockSpeed = 0; void startTransaction(); diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 58a623d..5132640 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -49,7 +49,11 @@ extern "C" void I2C1_ER_IRQHandler(void) { // Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants I2C_TypeDef *s = I2C1; #define I2C_IRQn I2C1_EV_IRQn -#define I2C_BUSFREQ 16 + +// Peripheral Input Clock speed in MHz. +// For STM32F446RE, the speed is 45MHz. Ideally, this should be determined +// at run-time from the APB1 clock, as it can vary from STM32 family to family. +#define I2C_PERIPH_CLK 45 // I2C SR1 Status Register #1 bit definitions for convenience // #define I2C_SR1_SMBALERT (1<<15) // SMBus alert @@ -83,15 +87,20 @@ I2C_TypeDef *s = I2C1; // #define I2C_CR1_SMBUS (1<<1) // SMBus mode, 1=SMBus, 0=I2C // #define I2C_CR1_PE (1<<0) // I2C Peripheral enable +// States of the STM32 I2C driver state machine +enum {TS_IDLE,TS_START,TS_W_ADDR,TS_W_DATA,TS_W_STOP,TS_R_ADDR,TS_R_DATA,TS_R_STOP}; + + /*************************************************************************** * Set I2C clock speed register. This should only be called outside of * a transmission. The I2CManagerClass::_setClock() function ensures * that it is only called at the beginning of an I2C transaction. ***************************************************************************/ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { + return; // Calculate a rise time appropriate to the requested bus speed - // Use 10x the rise time spec to enable integer divide of 62.5ns clock period + // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; uint32_t ccr_freq; @@ -110,44 +119,31 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { if (i2cClockSpeed > 400000L) i2cClockSpeed = 400000L; - t_rise = 0x06; // (300ns /62.5ns) + 1; + t_rise = 300; // nanoseconds } else { i2cClockSpeed = 100000L; - t_rise = 0x11; // (1000ns /62.5ns) + 1; + t_rise = 1000; // nanoseconds } // Configure the rise time register - s->TRISE = t_rise; - - // DIAG(F("Setting I2C clock to: %d"), i2cClockSpeed); - // Calculate baudrate - ccr_freq = I2C_BUSFREQ * 1000000 / i2cClockSpeed / 2; + s->TRISE = t_rise * I2C_PERIPH_CLK / 1000UL + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode - // Bit 14: Duty, fast mode duty cycle - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - if (i2cClockSpeed > 100000L) + // Bit 14: Duty, fast mode duty cycle (use 2:1) + // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns + if (i2cClockSpeed > 100000L) { + // In fast mode, I2C period is 3 * CCR * TPCLK1. + ccr_freq = I2C_PERIPH_CLK * 1000000 / 3 / i2cClockSpeed; s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set - else + } else { + // In standard mode, I2C period is 2 * CCR * TPCLK1. + ccr_freq = I2C_PERIPH_CLK * 1000000 / 2 / i2cClockSpeed; s->CCR = (uint16_t)ccr_freq; + } // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - digitalWrite(D13, HIGH); - DIAG(F("I2C: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -176,18 +172,19 @@ void I2CManagerClass::I2C_init() GPIOB->AFR[1] &= ~((15<<0) | (15<<4)); // Clear all AFR bits for PB8 on low nibble, PB9 on next nibble up GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up - // // Software reset the I2C peripheral + // Software reset the I2C peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C asm("nop"); // wait a bit... suggestion from online! s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation // Clear all bits in I2C CR2 register except reserved bits s->CR2 &= 0xE000; - // Program the peripheral input clock in CR2 Register in order to generate correct timings - s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz - // set own address to 00 - not really used in master mode - I2C1->OAR1 |= (1 << 14); // bit 14 should be kept at 1 according to the datasheet + // Set I2C peripheral clock frequency + s->CR2 |= I2C_PERIPH_CLK; + + // set own address to 00 - not used in master mode + I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet #if defined(I2C_USE_INTERRUPTS) // Setting NVIC @@ -205,35 +202,21 @@ void I2CManagerClass::I2C_init() // Bit 8: ITERREN - Error interrupt enable // Bit 7-6: reserved // Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz) - s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts - // s->CR2 |= 0x0300; // Enable Event and Error interrupts + s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts #endif // Calculate baudrate and set default rate for now // Configure the Clock Control Register for 100KHz SCL frequency // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = 0x50; + // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) + s->CCR = I2C_PERIPH_CLK * 5; - // Configure the rise time register - max allowed in 1000ns - s->TRISE = 0x0011; // 1000 ns / 62.5 ns = 16 + 1 + // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. + s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -243,56 +226,27 @@ void I2CManagerClass::I2C_sendStart() { // Set counters here in case this is a retry. rxCount = txCount = 0; + // On a single-master I2C bus, the start bit won't be sent until the bus // state goes to IDLE so we can request it without waiting. On a // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. - // Send start for read operation - while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further - // writes to CR1 while STOP is being executed! - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C_sendStart: SR2->BUSY timeout")); - // delay(1000); - } - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 &= ~(I2C_CR1_POS); // Reset the POS bit - only used for 2-byte reception - s->CR1 |= I2C_CR1_START; // Generate START + // Check there's no STOP still in progress. If we OR the START bit into CR1 + // and the STOP bit is already set, we could output multiple STOP conditions. + while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset + + s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit + s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START + transactionState = TS_START; } /*************************************************************************** * Initiate a stop bit for transmission (does not interrupt) ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { - uint32_t temp; - s->CR1 |= I2C_CR1_STOP; // Stop I2C - temp = s->SR1 | s->SR2; // Read the status registers to clear them - while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further - // writes to CR1 while STOP is being executed! - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C_sendStop: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -317,157 +271,182 @@ void I2CManagerClass::I2C_close() { * (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()). ***************************************************************************/ void I2CManagerClass::I2C_handleInterrupt() { - volatile uint16_t temp_sr1, temp_sr2, temp; - static bool led_lit = false; + volatile uint16_t temp_sr1, temp_sr2; temp_sr1 = s->SR1; - // if (temp_sr1 & I2C_SR1_ADDR) - // temp_sr2 = s->SR2; - // Check to see if start bit sent - SB interrupt! - if (temp_sr1 & I2C_SR1_SB) - { - // If anything to send, initiate write. Otherwise initiate read. - if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) + // Check for errors first + if (temp_sr1 & (I2C_SR1_AF | I2C_SR1_ARLO | I2C_SR1_BERR)) { + // Check which error flag is set + if (temp_sr1 & I2C_SR1_AF) { - // Send address with read flag (1) or'd in - s->DR = (deviceAddress << 1) | 1; // send the address - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // // // Special case for 1 byte reads! - // if (bytesToReceive == 1) - // { - // s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit - // temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition - // s->CR1 |= I2C_CR1_STOP; // Stop I2C - // } - // else - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else - { - // Send address with write flag (0) or'd in - s->DR = (deviceAddress << 1) | 0; // send the address - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else if (temp_sr1 & I2C_SR1_ADDR) { - // Receive 1 byte (AN2824 figure 2) - if (bytesToReceive == 1) { - s->CR1 &= ~I2C_CR1_ACK; // Disable ACK final byte - // EV6_1 must be atomic operation (AN2824) - // noInterrupts(); - (void)s->SR2; // read SR2 to complete clearing the ADDR bit - I2C_sendStop(); // send stop - // interrupts(); - } - // Receive 2 bytes (AN2824 figure 2) - else if (bytesToReceive == 2) { - s->CR1 |= I2C_CR1_POS; // Set POS flag (NACK position next) - // EV6_1 must be atomic operation (AN2824) - // noInterrupts(); - (void)s->SR2; // read SR2 to complete clearing the ADDR bit - s->CR1 &= ~I2C_CR1_ACK; // Disable ACK byte - // interrupts(); - } - else - temp = temp_sr1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else if (temp_sr1 & I2C_SR1_AF) - { - s->SR1 &= ~(I2C_SR1_AF); // Clear AF - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - while (s->SR1 & I2C_SR1_AF); // Check AF cleared - I2C_sendStop(); // Clear the bus - completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; - state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_ARLO) - { - // Arbitration lost, restart - s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); - I2C_sendStart(); // Reinitiate request - // state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_BERR) - { - // Bus error - s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); // Clear the bus - completionStatus = I2C_STATUS_BUS_ERROR; - state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_TXE) - { - // temp_sr2 = s->SR2; - // Master write completed - if (temp_sr1 & I2C_SR1_AF) { - // Nacked s->SR1 &= ~(I2C_SR1_AF); // Clear AF - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - // send stop. - I2C_sendStop(); + I2C_sendStop(); // Clear the bus + transactionState = TS_IDLE; completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; state = I2C_STATE_COMPLETED; - } else if (bytesToSend) { - // Acked, so send next byte - while ((s->SR1 & I2C_SR1_BTF)); // Check BTF before proceeding - s->DR = sendBuffer[txCount++]; - bytesToSend--; - // } else if (bytesToReceive) { - // // Last sent byte acked and no more to send. Send repeated start, address and read bit. - // s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - // I2C_sendStart(); - // s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1; - } else { - // No bytes left to send or receive - // Check both TxE/BTF == 1 before generating stop - // while (!(s->SR1 & I2C_SR1_TXE)); // Check TxE - while ((s->SR1 & I2C_SR1_BTF)); // Check BTF - // No more data to send/receive. Initiate a STOP condition and finish - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); - // completionStatus = I2C_STATUS_OK; + } + else if (temp_sr1 & I2C_SR1_ARLO) + { + // Arbitration lost, restart + s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO + I2C_sendStart(); // Reinitiate request + transactionState = TS_START; + } + else if (temp_sr1 & I2C_SR1_BERR) + { + // Bus error + s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR + I2C_sendStop(); // Clear the bus + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; } - } - else if (temp_sr1 & I2C_SR1_RXNE) - { - // Master read completed without errors - if (bytesToReceive == 1) { - s->CR1 &= ~I2C_CR1_ACK; // NAK final byte - I2C_sendStop(); // send stop - receiveBuffer[rxCount++] = s->DR; // Store received byte - bytesToReceive = 0; - // completionStatus = I2C_STATUS_OK; - state = I2C_STATE_COMPLETED; + } else { + // No error flags, so process event according to current state. + switch (transactionState) { + case TS_START: + if (temp_sr1 & I2C_SR1_SB) { + // Event EV5 + // Start bit has been sent successfully and we have the bus. + // If anything to send, initiate write. Otherwise initiate read. + if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) { + // Send address with read flag (1) or'd in + s->DR = (deviceAddress << 1) | 1; // send the address + transactionState = TS_R_ADDR; + } else { + // Send address with write flag (0) or'd in + s->DR = (deviceAddress << 1) | 0; // send the address + transactionState = TS_W_ADDR; + } + } + // SB bit is cleared by writing to DR (already done). + break; + + case TS_W_ADDR: + if (temp_sr1 & I2C_SR1_ADDR) { + // Event EV6 + // Address sent successfully, device has ack'd in response. + if (!bytesToSend) { + I2C_sendStop(); + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } else { + transactionState = TS_W_DATA; + } + } + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + break; + + case TS_W_DATA: + if (temp_sr1 & I2C_SR1_TXE) { + // Event EV8_1/EV8/EV8_2 + // Transmitter empty, write a byte to it. + if (bytesToSend) { + s->DR = sendBuffer[txCount++]; + bytesToSend--; + } + // See if we're finished sending + if (!bytesToSend) { + // Wait for last byte to be sent. + transactionState = TS_W_STOP; + } + } + break; + + case TS_W_STOP: + if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { + // Event EV8_2 + // Write finished. + if (bytesToReceive) { + // Start a read operation by sending (re)start + I2C_sendStart(); + } else { + // Done. + I2C_sendStop(); + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } + } + break; + + case TS_R_ADDR: + if (temp_sr1 & I2C_SR1_ADDR) { + // Event EV6 + // Address sent for receive. + // The next bit is different depending on whether there are + // 1 byte, 2 bytes or >2 bytes to be received, in accordance with the + // Programmers Reference RM0390. + if (bytesToReceive == 1) { + // Receive 1 byte + s->CR1 &= ~I2C_CR1_ACK; // Disable ack + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_STOP; + // Next step will occur after a BTF interrupt + } else if (bytesToReceive == 2) { + // Receive 2 bytes + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK for final byte + s->CR1 |= I2C_CR1_POS; // set POS flag to delay effect of ACK flag + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_STOP; + } else { + // >2 bytes, just wait for bytes to come in and ack them for the time being + // (ack flag has already been set). + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_DATA; + } + } + break; + + case TS_R_DATA: + // Event EV7/EV7_1 + if (temp_sr1 & I2C_SR1_BTF) { + // Byte received in receiver - read next byte + if (bytesToReceive == 3) { + // Getting close to the last byte, so a specific sequence is recommended. + s->CR1 &= ~I2C_CR1_ACK; // Reset ack for next byte received. + transactionState = TS_R_STOP; + } + receiveBuffer[rxCount++] = s->DR; // Store received byte + bytesToReceive--; + } + break; + + case TS_R_STOP: + if (temp_sr1 & I2C_SR1_BTF) { + // Event EV7 (last one) + // When we've got here, the receiver has got the last two bytes + // (or one byte, if only one byte is being received), + // and NAK has already been sent, so we need to read from the receiver. + if (bytesToReceive) { + if (bytesToReceive > 1) + I2C_sendStop(); + while(bytesToReceive) { + receiveBuffer[rxCount++] = s->DR; // Store received byte(s) + bytesToReceive--; + } + // Finish. + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } + } else if (temp_sr1 & I2C_SR1_RXNE) { + if (bytesToReceive == 1) { + // One byte on a single-byte transfer. Ack has already been set. + I2C_sendStop(); + receiveBuffer[rxCount++] = s->DR; // Store received byte + bytesToReceive--; + // Finish. + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } else + s->SR1 &= I2C_SR1_RXNE; // Acknowledge interrupt + } + break; } - else if (bytesToReceive == 2) - { - // Also needs to be atomic! - // noInterrupts(); - I2C_sendStop(); - receiveBuffer[rxCount++] = s->DR; // Store received byte - // interrupts(); - } - else if (bytesToReceive) - { - s->CR1 &= ~(I2C_CR1_ACK); // ACK all but final byte - receiveBuffer[rxCount++] = s->DR; // Store received byte - bytesToReceive--; - } - } - else - { - // DIAG(F("Unhandled I2C interrupt!")); - led_lit = ~led_lit; - digitalWrite(D13, led_lit); - // delay(1000); } } diff --git a/defines.h b/defines.h index 5582e8b..ab9cf45 100644 --- a/defines.h +++ b/defines.h @@ -144,9 +144,9 @@ #define DISABLE_EEPROM #endif // STM32 support for native I2C is awaiting development - #ifndef I2C_USE_WIRE - #define I2C_USE_WIRE - #endif + // #ifndef I2C_USE_WIRE + // #define I2C_USE_WIRE + // #endif /* TODO when ready From 4f56837d28198e2cee8af66ad757f3d3c8040bb7 Mon Sep 17 00:00:00 2001 From: Neil McKechnie <neilmck999@gmail.com> Date: Tue, 28 Mar 2023 18:07:52 +0100 Subject: [PATCH 03/83] Fixes to timeout handling (due to STM32 micros() difference). --- I2CManager.cpp | 2 +- I2CManager.h | 4 ++-- I2CManager_NonBlocking.h | 13 ++++++---- I2CManager_STM32.h | 52 ++++++++++++++++++++++++++++++++-------- 4 files changed, 54 insertions(+), 17 deletions(-) diff --git a/I2CManager.cpp b/I2CManager.cpp index d0d8550..1d1387e 100644 --- a/I2CManager.cpp +++ b/I2CManager.cpp @@ -92,7 +92,7 @@ void I2CManagerClass::begin(void) { // Probe and list devices. Use standard mode // (clock speed 100kHz) for best device compatibility. _setClock(100000); - unsigned long originalTimeout = _timeout; + uint32_t originalTimeout = _timeout; setTimeout(1000); // use 1ms timeout for probes #if defined(I2C_EXTENDED_ADDRESS) diff --git a/I2CManager.h b/I2CManager.h index ede30cc..08d81d4 100644 --- a/I2CManager.h +++ b/I2CManager.h @@ -485,7 +485,7 @@ private: // When retries are enabled, the timeout applies to each // try, and failure from timeout does not get retried. // A value of 0 means disable timeout monitoring. - unsigned long _timeout = 100000UL; + uint32_t _timeout = 100000UL; // Finish off request block by waiting for completion and posting status. uint8_t finishRB(I2CRB *rb, uint8_t status); @@ -532,7 +532,7 @@ private: uint8_t bytesToSend = 0; uint8_t bytesToReceive = 0; uint8_t operation = 0; - unsigned long startTime = 0; + uint32_t startTime = 0; uint8_t muxPhase = 0; uint8_t muxAddress = 0; uint8_t muxData[1]; diff --git a/I2CManager_NonBlocking.h b/I2CManager_NonBlocking.h index fb5bae5..59bbcaf 100644 --- a/I2CManager_NonBlocking.h +++ b/I2CManager_NonBlocking.h @@ -172,6 +172,10 @@ void I2CManagerClass::startTransaction() { * Function to queue a request block and initiate operations. ***************************************************************************/ void I2CManagerClass::queueRequest(I2CRB *req) { + + if (((req->operation & OPERATION_MASK) == OPERATION_READ) && req->readLen == 0) + return; // Ignore null read + req->status = I2C_STATUS_PENDING; req->nextRequest = NULL; ATOMIC_BLOCK() { @@ -184,6 +188,7 @@ void I2CManagerClass::queueRequest(I2CRB *req) { } + /*************************************************************************** * Initiate a write to an I2C device (non-blocking operation) ***************************************************************************/ @@ -240,8 +245,8 @@ void I2CManagerClass::checkForTimeout() { I2CRB *t = queueHead; if (state==I2C_STATE_ACTIVE && t!=0 && t==currentRequest && _timeout > 0) { // Check for timeout - unsigned long elapsed = micros() - startTime; - if (elapsed > _timeout) { + int32_t elapsed = micros() - startTime; + if (elapsed > (int32_t)_timeout) { #ifdef DIAG_IO //DIAG(F("I2CManager Timeout on %s"), t->i2cAddress.toString()); #endif @@ -300,12 +305,12 @@ void I2CManagerClass::handleInterrupt() { // Check if current request has completed. If there's a current request // and state isn't active then state contains the completion status of the request. - if (state == I2C_STATE_COMPLETED && currentRequest != NULL) { + if (state == I2C_STATE_COMPLETED && currentRequest != NULL && currentRequest == queueHead) { // Operation has completed. if (completionStatus == I2C_STATUS_OK || ++retryCounter > MAX_I2C_RETRIES || currentRequest->operation & OPERATION_NORETRY) { - // Status is OK, or has failed and retry count exceeded, or retries disabled. + // Status is OK, or has failed and retry count exceeded, or failed and retries disabled. #if defined(I2C_EXTENDED_ADDRESS) if (muxPhase == MuxPhase_PROLOG ) { overallStatus = completionStatus; diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 5132640..eac331a 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -232,6 +232,7 @@ void I2CManagerClass::I2C_sendStart() { // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. + //while (s->SR2 & I2C_SR2_BUSY) {} // Check there's no STOP still in progress. If we OR the START bit into CR1 // and the STOP bit is already set, we could output multiple STOP conditions. @@ -247,6 +248,7 @@ void I2CManagerClass::I2C_sendStart() { ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { s->CR1 |= I2C_CR1_STOP; // Stop I2C + //while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset } /*************************************************************************** @@ -273,6 +275,9 @@ void I2CManagerClass::I2C_close() { void I2CManagerClass::I2C_handleInterrupt() { volatile uint16_t temp_sr1, temp_sr2; + pinMode(D2, OUTPUT); + digitalWrite(D2, 1); + temp_sr1 = s->SR1; // Check for errors first @@ -302,7 +307,8 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; } - } else { + } + else { // No error flags, so process event according to current state. switch (transactionState) { case TS_START: @@ -324,6 +330,7 @@ void I2CManagerClass::I2C_handleInterrupt() { break; case TS_W_ADDR: + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit if (temp_sr1 & I2C_SR1_ADDR) { // Event EV6 // Address sent successfully, device has ack'd in response. @@ -333,10 +340,25 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } else { - transactionState = TS_W_DATA; + if (bytesToSend <= 2) { + // After this interrupt, we will have no more data to send. + // Next event of interest will be the BTF interrupt, so disable TXE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; + transactionState = TS_W_STOP; + } else { + // More data to send, enable TXE interrupt. + s->CR2 |= I2C_CR2_ITBUFEN; + transactionState = TS_W_DATA; + } + // Put one or two bytes into DR to avoid interrupts + s->DR = sendBuffer[txCount++]; + bytesToSend--; + if (bytesToSend) { + s->DR = sendBuffer[txCount++]; + bytesToSend--; + } } } - temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit break; case TS_W_DATA: @@ -344,21 +366,24 @@ void I2CManagerClass::I2C_handleInterrupt() { // Event EV8_1/EV8/EV8_2 // Transmitter empty, write a byte to it. if (bytesToSend) { + if (bytesToSend == 1) { + // We will next need to wait for BTF. + // TXE becomes set one byte before BTF is set, so disable + // TXE interrupt while we're waiting for BTF, to suppress + // repeated interrupts during that period. + s->CR2 &= ~I2C_CR2_ITBUFEN; + transactionState = TS_W_STOP; + } s->DR = sendBuffer[txCount++]; bytesToSend--; } - // See if we're finished sending - if (!bytesToSend) { - // Wait for last byte to be sent. - transactionState = TS_W_STOP; - } } break; case TS_W_STOP: if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { // Event EV8_2 - // Write finished. + // All writes finished. if (bytesToReceive) { // Start a read operation by sending (re)start I2C_sendStart(); @@ -383,17 +408,22 @@ void I2CManagerClass::I2C_handleInterrupt() { // Receive 1 byte s->CR1 &= ~I2C_CR1_ACK; // Disable ack temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + // Next step will occur after a RXNE interrupt, so enable it + s->CR2 |= I2C_CR2_ITBUFEN; transactionState = TS_R_STOP; - // Next step will occur after a BTF interrupt } else if (bytesToReceive == 2) { // Receive 2 bytes s->CR1 &= ~I2C_CR1_ACK; // Disable ACK for final byte s->CR1 |= I2C_CR1_POS; // set POS flag to delay effect of ACK flag + // Next step will occur after a BTF interrupt, so disable RXNE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit transactionState = TS_R_STOP; } else { // >2 bytes, just wait for bytes to come in and ack them for the time being // (ack flag has already been set). + // Next step will occur after a BTF interrupt, so disable RXNE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit transactionState = TS_R_DATA; } @@ -448,6 +478,8 @@ void I2CManagerClass::I2C_handleInterrupt() { break; } } + delayMicroseconds(1); + digitalWrite(D2, 0); } #endif /* I2CMANAGER_STM32_H */ From 4f43a413b5aeeb709fe14e2cb298077ebbe38081 Mon Sep 17 00:00:00 2001 From: Neil McKechnie <neilmck999@gmail.com> Date: Thu, 30 Mar 2023 18:30:38 +0100 Subject: [PATCH 04/83] Update I2CManager_STM32.h Remove debug code (writing to pin D2). Update comments. Restructure. --- I2CManager_STM32.h | 73 +++++++++++++++++++++++++--------------------- 1 file changed, 39 insertions(+), 34 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index eac331a..f1d7e08 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -238,6 +238,8 @@ void I2CManagerClass::I2C_sendStart() { // and the STOP bit is already set, we could output multiple STOP conditions. while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset + s->CR2 |= (I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable interrupts + s->CR2 &= ~I2C_CR2_ITBUFEN; // Don't enable buffer interupts yet. s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START transactionState = TS_START; @@ -248,7 +250,6 @@ void I2CManagerClass::I2C_sendStart() { ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { s->CR1 |= I2C_CR1_STOP; // Stop I2C - //while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset } /*************************************************************************** @@ -261,7 +262,7 @@ void I2CManagerClass::I2C_close() { // Should never happen, but wait for up to 500us only. unsigned long startTime = micros(); while ((s->CR1 & I2C_CR1_PE) != 0) { - if (micros() - startTime >= 500UL) break; + if ((int32_t)(micros() - startTime) >= 500) break; } NVIC_DisableIRQ(I2C1_EV_IRQn); NVIC_DisableIRQ(I2C1_ER_IRQn); @@ -275,9 +276,6 @@ void I2CManagerClass::I2C_close() { void I2CManagerClass::I2C_handleInterrupt() { volatile uint16_t temp_sr1, temp_sr2; - pinMode(D2, OUTPUT); - digitalWrite(D2, 1); - temp_sr1 = s->SR1; // Check for errors first @@ -330,8 +328,8 @@ void I2CManagerClass::I2C_handleInterrupt() { break; case TS_W_ADDR: - temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit if (temp_sr1 & I2C_SR1_ADDR) { + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit // Event EV6 // Address sent successfully, device has ack'd in response. if (!bytesToSend) { @@ -340,60 +338,65 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } else { - if (bytesToSend <= 2) { - // After this interrupt, we will have no more data to send. - // Next event of interest will be the BTF interrupt, so disable TXE interrupt - s->CR2 &= ~I2C_CR2_ITBUFEN; - transactionState = TS_W_STOP; - } else { - // More data to send, enable TXE interrupt. - s->CR2 |= I2C_CR2_ITBUFEN; - transactionState = TS_W_DATA; - } - // Put one or two bytes into DR to avoid interrupts + // Put one byte into DR to load shift register. s->DR = sendBuffer[txCount++]; bytesToSend--; if (bytesToSend) { + // Put another byte to load DR s->DR = sendBuffer[txCount++]; bytesToSend--; } + if (!bytesToSend) { + // No more bytes to send. + // The TXE interrupt occurs when the DR is empty, and the BTF interrupt + // occurs when the shift register is also empty (one character later). + // To avoid repeated TXE interrupts during this time, we disable TXE interrupt. + s->CR2 &= ~I2C_CR2_ITBUFEN; // Wait for BTF interrupt, disable TXE interrupt + transactionState = TS_W_STOP; + } else { + // More data remaining to send after this interrupt, enable TXE interrupt. + s->CR2 |= I2C_CR2_ITBUFEN; + transactionState = TS_W_DATA; + } } } break; case TS_W_DATA: if (temp_sr1 & I2C_SR1_TXE) { - // Event EV8_1/EV8/EV8_2 + // Event EV8_1/EV8 // Transmitter empty, write a byte to it. if (bytesToSend) { - if (bytesToSend == 1) { - // We will next need to wait for BTF. - // TXE becomes set one byte before BTF is set, so disable - // TXE interrupt while we're waiting for BTF, to suppress - // repeated interrupts during that period. - s->CR2 &= ~I2C_CR2_ITBUFEN; - transactionState = TS_W_STOP; - } s->DR = sendBuffer[txCount++]; bytesToSend--; + if (!bytesToSend) { + s->CR2 &= ~I2C_CR2_ITBUFEN; // Disable TXE interrupt + transactionState = TS_W_STOP; + } } - } + } break; case TS_W_STOP: - if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { + if (temp_sr1 & I2C_SR1_BTF) { // Event EV8_2 - // All writes finished. + // Done, last character sent. Anything to receive? if (bytesToReceive) { - // Start a read operation by sending (re)start - I2C_sendStart(); + I2C_sendStart(); + // NOTE: Three redundant BTF interrupts take place between the + // first BTF interrupt and the START interrupt. I've tried all sorts + // of ways to eliminate them, and the only thing that worked for + // me was to loop until the BTF bit becomes reset. Either way, + // it's a waste of processor time. Anyone got a solution? + //while (s->SR1 && I2C_SR1_BTF) {} + transactionState = TS_START; } else { - // Done. I2C_sendStop(); transactionState = TS_IDLE; completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } + s->SR1 &= I2C_SR1_BTF; // Clear BTF interrupt } break; @@ -477,9 +480,11 @@ void I2CManagerClass::I2C_handleInterrupt() { } break; } + // If we've received an interrupt at any other time, we're not interested so clear it + // to prevent it recurring ad infinitum. + s->SR1 = 0; } - delayMicroseconds(1); - digitalWrite(D2, 0); + } #endif /* I2CMANAGER_STM32_H */ From e51f8e9c0a53e4de08699ac255b6f17cb42f18bd Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Tue, 11 Apr 2023 15:48:35 +0800 Subject: [PATCH 05/83] STM32 I2C Clock selection for 100/400KHz --- I2CManager_STM32.h | 75 ++++++++++++++++++++++++++-------------------- 1 file changed, 43 insertions(+), 32 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index f1d7e08..cde4f20 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -26,34 +26,42 @@ #include "I2CManager.h" #include "I2CManager_NonBlocking.h" // to satisfy intellisense -//#include <avr/io.h> -//#include <avr/interrupt.h> #include <wiring_private.h> +#include "stm32f4xx_hal_rcc.h" -/*************************************************************************** - * Interrupt handler. - * IRQ handler for SERCOM3 which is the default I2C definition for Arduino Zero - * compatible variants such as the Sparkfun SAMD21 Dev Breakout etc. - * Later we may wish to allow use of an alternate I2C bus, or more than one I2C - * bus on the SAMD architecture - ***************************************************************************/ +/***************************************************************************** + * STM32F4xx I2C native driver support + * + * Nucleo-64 and Nucleo-144 boards all use I2C1 as the default I2C peripheral + * Later we may wish to support other STM32 boards, allow use of an alternate + * I2C bus, or more than one I2C bus on the STM32 architecture + *****************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) +#if defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) +// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64 +// and Nucleo-144variants +I2C_TypeDef *s = I2C1; + +// In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz +uint32_t APB1clk1; // Peripheral Input Clock speed in Hz. +uint32_t i2c_MHz; // Peripheral Input Clock speed in MHz. + +// IRQ handler for I2C1, replacing the weak definition in the STM32 HAL extern "C" void I2C1_EV_IRQHandler(void) { I2CManager.handleInterrupt(); } extern "C" void I2C1_ER_IRQHandler(void) { I2CManager.handleInterrupt(); } +#else +#warning STM32 board selected is not yet supported - so I2C1 peripheral is not defined +#endif #endif - -// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants -I2C_TypeDef *s = I2C1; -#define I2C_IRQn I2C1_EV_IRQn // Peripheral Input Clock speed in MHz. // For STM32F446RE, the speed is 45MHz. Ideally, this should be determined // at run-time from the APB1 clock, as it can vary from STM32 family to family. -#define I2C_PERIPH_CLK 45 +// #define I2C_PERIPH_CLK 45 // I2C SR1 Status Register #1 bit definitions for convenience // #define I2C_SR1_SMBALERT (1<<15) // SMBus alert @@ -97,8 +105,6 @@ enum {TS_IDLE,TS_START,TS_W_ADDR,TS_W_DATA,TS_W_STOP,TS_R_ADDR,TS_R_DATA,TS_R_ST * that it is only called at the beginning of an I2C transaction. ***************************************************************************/ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { - return; - // Calculate a rise time appropriate to the requested bus speed // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; @@ -106,13 +112,9 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // writes to CR1 while STOP is being executed! + // Disable the I2C device, as TRISE can only be programmed whilst disabled s->CR1 &= ~(I2C_CR1_PE); // Disable I2C - // Software reset the I2C peripheral - // s->CR1 |= I2C_CR1_SWRST; // reset the I2C - // delay(1); - // Release reset - // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation if (i2cClockSpeed > 100000L) { @@ -127,19 +129,20 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { t_rise = 1000; // nanoseconds } // Configure the rise time register - s->TRISE = t_rise * I2C_PERIPH_CLK / 1000UL + 1; + s->TRISE = (t_rise / (1000 / i2c_MHz)) + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle (use 2:1) - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns + // Bit 11-0: FREQR if (i2cClockSpeed > 100000L) { // In fast mode, I2C period is 3 * CCR * TPCLK1. - ccr_freq = I2C_PERIPH_CLK * 1000000 / 3 / i2cClockSpeed; - s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set + //APB1clk1 / 3 / i2cClockSpeed = 38, but that results in 306KHz not 400! + ccr_freq = 30; // So 30 gives 396KHz or so! + s->CCR = (uint16_t)(ccr_freq | 0x8000); // We need Fast Mode set } else { - // In standard mode, I2C period is 2 * CCR * TPCLK1. - ccr_freq = I2C_PERIPH_CLK * 1000000 / 2 / i2cClockSpeed; - s->CCR = (uint16_t)ccr_freq; + // In standard mode, I2C period is 2 * CCR * TPCLK1 + ccr_freq = (APB1clk1 / 2 / i2cClockSpeed); // Should be 225 for 45Mhz APB1 clock + s->CCR |= (uint16_t)ccr_freq; } // Enable the I2C master mode @@ -151,7 +154,10 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { ***************************************************************************/ void I2CManagerClass::I2C_init() { - // Setting up the clocks + // Query the clockspeed from the STM32 HAL layer + APB1clk1 = HAL_RCC_GetPCLK1Freq(); + i2c_MHz = APB1clk1 / 1000000UL; + // Enable clocks RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK // Reset the I2C1 peripheral to initial state RCC->APB1RSTR |= RCC_APB1RSTR_I2C1RST; @@ -181,7 +187,8 @@ void I2CManagerClass::I2C_init() s->CR2 &= 0xE000; // Set I2C peripheral clock frequency - s->CR2 |= I2C_PERIPH_CLK; + // s->CR2 |= I2C_PERIPH_CLK; + s->CR2 |= i2c_MHz; // set own address to 00 - not used in master mode I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet @@ -210,10 +217,14 @@ void I2CManagerClass::I2C_init() // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) - s->CCR = I2C_PERIPH_CLK * 5; + // s->CCR = I2C_PERIPH_CLK * 5; + s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + s->CCR |= (APB1clk1 / 2 / 100000UL); // i2c_MHz * 5; + // s->CCR = i2c_MHz * 5; // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. - s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 + // s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 + s->TRISE = i2c_MHz + 1; // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C From 085762e80078e793abb57ae6313ae294631d7f6b Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Fri, 18 Aug 2023 18:52:34 +1000 Subject: [PATCH 06/83] Add OPCODE list to DCCEXParser.cpp --- DCCEXParser.cpp | 73 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 73 insertions(+) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aaf733c..7610d45 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -25,6 +25,79 @@ * You should have received a copy of the GNU General Public License * along with CommandStation. If not, see <https://www.gnu.org/licenses/>. */ + +/* +List of single character OPCODEs in use for reference. + +When determining a new OPCODE for a new feature, refer to this list as the source of truth. + +Once a new OPCODE is decided upon, update this list. + + Character, Usage + /, |EX-R| interactive commands + -, Remove from reminder table + =, |TM| configuration + !, Emergency stop + @, Reserved for future use - LCD messages to JMRI + #, Request number of supported cabs/locos; heartbeat + +, WiFi AT commands + ?, Reserved for future use + 0, Track power off + 1, Track power on + a, DCC accessory control + A, + b, Write CV bit on main + B, Write CV bit + c, Request current command + C, + d, + D, Diagnostic commands + e, Erase EEPROM + E, Store configuration in EEPROM + f, Loco decoder function control (deprecated) + F, Loco decoder function control + g, + G, + h, + H, Turnout state broadcast + i, Reserved for future use - Turntable object broadcast + I, Reserved for future use - Turntable object command and control + j, Throttle responses + J, Throttle queries + k, Reserved for future use - Potentially Railcom + K, Reserved for future use - Potentially Railcom + l, Loco speedbyte/function map broadcast + L, + m, + M, Write DCC packet + n, + N, + o, + O, Output broadcast + p, Broadcast power state + P, Write DCC packet + q, Sensor deactivated + Q, Sensor activated + r, Broadcast address read on programming track + R, Read CVs + s, Display status + S, Sensor configuration + t, Cab/loco update command + T, Turnout configuration/control + u, Reserved for user commands + U, Reserved for user commands + v, + V, Verify CVs + w, Write CV on main + W, Write CV + x, + X, Invalid command + y, + Y, Output broadcast + z, + Z, Output configuration/control +*/ + #include "StringFormatter.h" #include "DCCEXParser.h" #include "DCC.h" From 1491da48134852b0f8623b8455eb8c356e566e53 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 20 Aug 2023 19:26:04 +1000 Subject: [PATCH 07/83] Starting, very broken --- CommandDistributor.cpp | 4 + CommandDistributor.h | 1 + DCCEXParser.cpp | 29 +++++++ DCCEXParser.h | 13 +-- IODevice.h | 1 + Turntables.cpp | 176 +++++++++++++++++++++++++++++++++++++++++ Turntables.h | 164 ++++++++++++++++++++++++++++++++++++++ 7 files changed, 382 insertions(+), 6 deletions(-) create mode 100644 Turntables.cpp create mode 100644 Turntables.h diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index ab6b52f..eef84a9 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -161,6 +161,10 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { #endif } +void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position) { + broadcastReply(COMMAND_TYPE, F("<i %d %d>\n"), id, position); +} + void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { // The JMRI clock command is of the form : PFT65871<;>4 // The CS broadcast is of the form "<jC mmmm nn" where mmmm is time minutes and dd speed diff --git a/CommandDistributor.h b/CommandDistributor.h index 45f8147..b1af10a 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -49,6 +49,7 @@ public : static void broadcastLoco(byte slot); static void broadcastSensor(int16_t id, bool value); static void broadcastTurnout(int16_t id, bool isClosed); + static void broadcastTurntable(int16_t id, uint8_t position); static void broadcastClockTime(int16_t time, int8_t rate); static void setClockTime(int16_t time, int8_t rate, byte opt); static int16_t retClockTime(); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aaf733c..4a32902 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -41,6 +41,7 @@ #include "TrackManager.h" #include "DCCTimer.h" #include "EXRAIL2.h" +#include "Turntables.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -694,6 +695,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) break; // case J } + case 'I': // TURNTABLE <I ...> + if (parseI(stream, params, p)) + return; + break; + default: //anything else will diagnose and drop out to <X> DIAG(F("Opcode=%c params=%d"), opcode, params); for (int i = 0; i < params; i++) @@ -1013,6 +1019,29 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) return false; } +// ========================== +// Turntable +bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) +{ + switch (params) + { + case 0: // <I> list turntable objects + return Turntable::printAll(stream); + + case 1: // <T id> delete turntable + if (!Turntable::remove(p[0])) + return false; + StringFormatter::send(stream, F("<i>\n")); + return true; + + case 2: // <T id position> - rotate to position for DCC turntables + case 3: // <T id position activity> rotate to position for EX-Turntable + { + + } + } +} + // CALLBACKS must be static bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream) { diff --git a/DCCEXParser.h b/DCCEXParser.h index bb05ebf..bf067a7 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -45,13 +45,14 @@ struct DCCEXParser static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], const byte * command, bool usehex); static bool parseT(Print * stream, int16_t params, int16_t p[]); - static bool parseZ(Print * stream, int16_t params, int16_t p[]); - static bool parseS(Print * stream, int16_t params, int16_t p[]); - static bool parsef(Print * stream, int16_t params, int16_t p[]); - static bool parseD(Print * stream, int16_t params, int16_t p[]); + static bool parseZ(Print * stream, int16_t params, int16_t p[]); + static bool parseS(Print * stream, int16_t params, int16_t p[]); + static bool parsef(Print * stream, int16_t params, int16_t p[]); + static bool parseD(Print * stream, int16_t params, int16_t p[]); + static bool parseI(Print * stream, int16_t params, int16_t p[]); - static Print * getAsyncReplyStream(); - static void commitAsyncReplyStream(); + static Print * getAsyncReplyStream(); + static void commitAsyncReplyStream(); static bool stashBusy; static byte stashTarget; diff --git a/IODevice.h b/IODevice.h index 769e111..8b8f3fe 100644 --- a/IODevice.h +++ b/IODevice.h @@ -542,6 +542,7 @@ protected: #include "IO_PCF8575.h" #include "IO_duinoNodes.h" #include "IO_EXIOExpander.h" +#include "IO_EXTurntable.h" #endif // iodevice_h diff --git a/Turntables.cpp b/Turntables.cpp new file mode 100644 index 0000000..45a1d05 --- /dev/null +++ b/Turntables.cpp @@ -0,0 +1,176 @@ +/* + * © 2023 Peter Cole + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see <https://www.gnu.org/licenses/>. + */ + +#include "defines.h" +#include <Arduino.h> +#include "Turntables.h" +#include "StringFormatter.h" +#include "CommandDistributor.h" +#include "EXRAIL2.h" +#include "DCC.h" + + +/* + * Protected static data + */ +Turntable *Turntable::_firstTurntable = 0; + + +/* + * Public static data + */ +int Turntable::_turntablelistHash = 0; + + +/* + * Protected static functions + */ +// Add new turntable to end of list +void Turntable::add(Turntable *tto) { + if (!_firstTurntable) { + _firstTurntable = tto; + } else { + Turntable *ptr = _firstTurntable; + for ( ; ptr->_nextTurntable!=0; ptr=ptr->_nextTurntable) {} + ptr->_nextTurntable = tto; + } + turntablelistHash++; +} + +// Find turntable from list +Turntable *Turntable::get(uint16_t id) { + for (Turntable *tto = _firstTurntable; tto != NULL; tto = tto->_nextTurntable) + if (tto->_turntableData.id == id) return tto; + return NULL; +} + +// Remove specified turntable from list and delete it +bool Turntable::remove(uint16_t id) { + Turntable *tto, *pp=NULL; + + for (tto=_firstTurntable; tto!=NULL && tto->_turntableData.id!=id; pp=tto, tto=tto->_nextTurntable) {} + if (tto == NULL) return false; + if (tto == _firstTurntable) { + _firstTurntable = tto->_nextTurntable; + } else { + pp->_nextTurntable = tto->_nextTurntable; + } + + delete (EXTTTurntable *)tto; + + turntablelistHash++; + return true; +} + + +/* + * Public static functions + */ +bool Turntable::isPosition(uint16_t id, uint8_t position) { + Turntable *tto = get(id); + if (!tto) return false; + if (tto) { + if (tto->getPosition() == position) { + return true; + } else { + return false; + } + } +} + +bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { + Turntable *tto = get(id); + if (!tto) return false; + CommandDistributor::broadcastTurntable(id, position); +#if defined(EXRAIL_ACTIVE) + // RMFT2::turntableEvent(id, position); +#endif +} + +bool Turntable::setPosition(uint16_t id, uint8_t position) { +#if defined(DIAG_IO) + DIAG(F("Turntable(%d, %d)"), id, position); +#endif + Turntable *tto = Turntable::get(id); + if (!tto) return false; + bool ok = tto->setPositionInternal(position); + + if (ok) { + tto->setPositionStateOnly(id, position); + } + return ok; +} + +/************************************************************************************* + * EXTTTurntable - EX-Turntable device. + * + *************************************************************************************/ +// Private constructor +EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) : + Turntable(id, TURNTABLE_EXTT) +{ + _exttTurntableData.i2caddress = i2caddress; + _exttTurntableData.vpin = vpin; + _exttTurntableData.positions = **positions; +} + +// Create function +#ifndef IO_NO_HAL + Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) { + Turntable *tto = get(id); + if (tto) { + if (tto->isType(TURNTABLE_EXTT)) { + EXTTTurntable *extt = (EXTTTurntable *)tto; + extt->_exttTurntableData.i2caddress = i2caddress; + extt->_exttTurntableData.vpin = vpin; + extt->_exttTurntableData.positions = positions; + return tto; + } else { + remove(id); + } + } + tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin, **positions); + DIAG(F("Turntable 0x%x"), tto); + return tto; +#else + (void)id; + (void)i2caddress; + (void)vpin; + (void)positions; + return NULL; +#endif + } + + void EXTTTurntable::print(Print *stream) { + StringFormatter::send(stream, F("<i %d EXTURNTABLE %d %d>\n"), _turntableData.id, _exttTurntableData.i2caddress, _exttTurntableData.vpin); + } + + // EX-Turntable specific code for moving to the specified position + bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { +#ifndef IO_NO_HAL + // Get step value from positions + int value = _exttTurntableData.positions[position]; + // Set position via device driver + EXTurntable::_writeAnalogue(vpin, value, activity, 0); +#else + (void)position; +#endif + return true; + } diff --git a/Turntables.h b/Turntables.h new file mode 100644 index 0000000..5a6f346 --- /dev/null +++ b/Turntables.h @@ -0,0 +1,164 @@ +/* + * © 2023 Peter Cole + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see <https://www.gnu.org/licenses/>. + */ + +#ifndef TURNTABLES_H +#define TURNTABLES_H + +#include <Arduino.h> +#include "IODevice.h" +#include "StringFormatter.h" + +// Turntable type definitions +// EXTT = EX-Turntable +// DCC = DCC accessory turntables - to be added later +enum { + TURNTABLE_EXTT = 1, + // TURNTABLE_DCC = 2, +}; + +/************************************************************************************* + * Turntable - Base class for turntables. + * + *************************************************************************************/ + +class Turntable { +protected: + /* + * Object data + */ + + // Data common to all turntable types + struct TurntableData { + union { + struct { + bool hidden : 1; + uint8_t turntableType : 2; + uint8_t position : 5; // Allows up to 38 positions including 0/home + }; + uint8_t flags; + }; + uint16_t id; + } _turntableData; + + // Pointer to next turntable object + Turntable *_nextTurntable = 0; + + /* + * Constructor + */ + Turntable(uint16_t id, uint8_t turntableType) { + _turntableData.id = id; + _turntableData.turntableType = turntableType; + _turntableData.hidden = false; + add(this); + } + + /* + * Static data + */ + static Turntable *_firstTurntable; + static int _turntablelistHash; + + /* + * Virtual functions + */ + virtual bool setPositionInternal(uint8_t position, uint8_t activity) = 0; + + /* + * Static functions + */ + static void add(Turntable *tto); + +public: + static Turntable *get(uint16_t id); + + /* + * Static data + */ + static int turntablelistHash; + + /* + * Public base class functions + */ + inline uint8_t getPosition() { return _turntableData.position; } + inline bool isHidden() { return _turntableData.hidden; } + inline void setHidden(bool h) {_turntableData.hidden=h; } + inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } + inline uint16_t getId() { return _turntableData.id; } + inline Turntable *next() { return _nextTurntable; } + void printState(Print *stream); + + /* + * Virtual functions + */ + virtual void print(Print *stream) { + (void)stream; // suppress compiler warnings + } + virtual ~Turntable() {} // Destructor + + /* + * Public static functions + */ + inline static bool exists(uint16_t id) { return get(id) != 0; } + static bool remove(uint16_t id); + static bool isPosition(uint16_t id, uint8_t position); + static bool setPosition(uint16_t id, uint8_t position); + static bool setPositionStateOnly(uint16_t id, uint8_t position); + inline static Turntable *first() { return _firstTurntable; } + static bool printAll(Print *stream) { + bool gotOne = false; + for (Turntable *tto = _firstTurntable; tto != 0; tto = tto->_nextTurntable) + if (!tto->isHidden()) { + gotOne = true; + StringFormatter::send(stream, F("<i %d %d>\n"), tto->getId(), tto->getPosition()); + } + return gotOne; + } + +}; + +/************************************************************************************* + * EXTTTurntable - EX-Turntable device. + * + *************************************************************************************/ +class EXTTTurntable : public Turntable { +private: + // EXTTTurntableData contains device specific data + struct EXTTTurntableData { + uint8_t i2caddress; + VPIN vpin; + long **positions; // Array of longs to store step positions + } _exttTurntableData; + + // Constructor + EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + +public: + // Create function + static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + void print(Print *stream) override; + +protected: + // EX-Turntable specific code for setting position + bool setPositionInternal(uint8_t position, uint8_t activity) override; + +}; + +#endif From 98f8022268ad536cf6e2183e472a56ba7a6bcf04 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Mon, 21 Aug 2023 06:43:06 +1000 Subject: [PATCH 08/83] Fix device driver, disable objects, start parser --- DCCEXParser.cpp | 33 +++++++++++++++++++++----- IODevice.h | 1 - IO_EXTurntable.h => IO_EXTurntable.cpp | 4 ++-- Turntables.cpp => Turntables.cpp.txt | 0 Turntables.h => Turntables.h.txt | 0 5 files changed, 29 insertions(+), 9 deletions(-) rename IO_EXTurntable.h => IO_EXTurntable.cpp (97%) rename Turntables.cpp => Turntables.cpp.txt (100%) rename Turntables.h => Turntables.h.txt (100%) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 4a32902..cfe2563 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -41,7 +41,7 @@ #include "TrackManager.h" #include "DCCTimer.h" #include "EXRAIL2.h" -#include "Turntables.h" +// #include "Turntables.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -96,6 +96,7 @@ const int16_t HASH_KEYWORD_ANOUT = -26399; const int16_t HASH_KEYWORD_WIFI = -5583; const int16_t HASH_KEYWORD_ETHERNET = -30767; const int16_t HASH_KEYWORD_WIT = 31594; +const int16_t HASH_KEYWORD_EXTT = 8573; int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; @@ -1021,25 +1022,45 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable +// <I> - list all +// <I id> - delete +// <I id steps> - operate (DCC) +// <I id steps activity> - operate (EXTT) +// <I id EXTT i2caddress vpin position1 position2 ...> - create EXTT +// <I id DCC linear1 linear2 ...> - create DCC? - This TBA bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { switch (params) { case 0: // <I> list turntable objects - return Turntable::printAll(stream); + StringFormatter::send(stream, F("<i all>\n")); + return true; + // return Turntable::printAll(stream); case 1: // <T id> delete turntable - if (!Turntable::remove(p[0])) - return false; - StringFormatter::send(stream, F("<i>\n")); + // if (!Turntable::remove(p[0])) + // return false; + StringFormatter::send(stream, F("<i delete>\n")); return true; case 2: // <T id position> - rotate to position for DCC turntables case 3: // <T id position activity> rotate to position for EX-Turntable { - + DIAG(F("Got %d parameters (2 or 3)"), params); + return true; } + + default: + { + if (params < 40) { + DIAG(F("Create turntable with %d parameters"), params); + return true; + } + } + break; + } + return false; } // CALLBACKS must be static diff --git a/IODevice.h b/IODevice.h index 8b8f3fe..769e111 100644 --- a/IODevice.h +++ b/IODevice.h @@ -542,7 +542,6 @@ protected: #include "IO_PCF8575.h" #include "IO_duinoNodes.h" #include "IO_EXIOExpander.h" -#include "IO_EXTurntable.h" #endif // iodevice_h diff --git a/IO_EXTurntable.h b/IO_EXTurntable.cpp similarity index 97% rename from IO_EXTurntable.h rename to IO_EXTurntable.cpp index 29ce679..f1a108b 100644 --- a/IO_EXTurntable.h +++ b/IO_EXTurntable.cpp @@ -20,9 +20,9 @@ /* * The IO_EXTurntable device driver is used to control a turntable via an Arduino with a stepper motor over I2C. * -* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/Turntable-EX) and contains the stepper motor logic. +* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/EX-Turntable) and contains the stepper motor logic. * -* This device driver sends a step position to Turntable-EX to indicate the step position to move to using either of these commands: +* This device driver sends a step position to EX-Turntable to indicate the step position to move to using either of these commands: * <D TT vpin steps activity> in the serial console * MOVETT(vpin, steps, activity) in EX-RAIL * Refer to the documentation for further information including the valid activities. diff --git a/Turntables.cpp b/Turntables.cpp.txt similarity index 100% rename from Turntables.cpp rename to Turntables.cpp.txt diff --git a/Turntables.h b/Turntables.h.txt similarity index 100% rename from Turntables.h rename to Turntables.h.txt From c4febd1d0f15d2dec5fbba1784c84d9b3f58327c Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Mon, 21 Aug 2023 19:33:45 +1000 Subject: [PATCH 09/83] More parser --- DCCEXParser.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index cfe2563..55a6cf7 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1044,18 +1044,23 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return true; case 2: // <T id position> - rotate to position for DCC turntables + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + return true; + case 3: // <T id position activity> rotate to position for EX-Turntable - { - DIAG(F("Got %d parameters (2 or 3)"), params); - return true; - } + DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); + return true; - default: + default: // If we're here, it must be creating a turntable object { - if (params < 40) { - DIAG(F("Create turntable with %d parameters"), params); + if (params < 41 && p[1] == HASH_KEYWORD_EXTT) { + DIAG(F("Create EXTT turntable %d on vpin %d and address %s with %d positions"), p[0], p[2], p[3], params - 4); + return true; + } else if (params < 39 && p[1] == HASH_KEYWORD_DCC) { + DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); return true; } + } break; From b277d204f00b171b6d32407d3910da422a2334e8 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Tue, 22 Aug 2023 19:30:22 +1000 Subject: [PATCH 10/83] Progress! --- DCCEXParser.cpp | 28 ++++++++++++---------------- Turntables.cpp.txt => Turntables.cpp | 26 +++++++++++++------------- Turntables.h.txt => Turntables.h | 8 +++++--- 3 files changed, 30 insertions(+), 32 deletions(-) rename Turntables.cpp.txt => Turntables.cpp (88%) rename Turntables.h.txt => Turntables.h (96%) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 55a6cf7..4823e8e 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -41,7 +41,7 @@ #include "TrackManager.h" #include "DCCTimer.h" #include "EXRAIL2.h" -// #include "Turntables.h" +#include "Turntables.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -1033,14 +1033,12 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) switch (params) { case 0: // <I> list turntable objects - StringFormatter::send(stream, F("<i all>\n")); - return true; - // return Turntable::printAll(stream); + return Turntable::printAll(stream); case 1: // <T id> delete turntable - // if (!Turntable::remove(p[0])) - // return false; - StringFormatter::send(stream, F("<i delete>\n")); + if (!Turntable::remove(p[0])) + return false; + StringFormatter::send(stream, F("<O>\n")); return true; case 2: // <T id position> - rotate to position for DCC turntables @@ -1053,19 +1051,17 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { - if (params < 41 && p[1] == HASH_KEYWORD_EXTT) { - DIAG(F("Create EXTT turntable %d on vpin %d and address %s with %d positions"), p[0], p[2], p[3], params - 4); - return true; - } else if (params < 39 && p[1] == HASH_KEYWORD_DCC) { + if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { + DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); + if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); - return true; + } else { + return false; } - } - break; - + return true; } - return false; } // CALLBACKS must be static diff --git a/Turntables.cpp.txt b/Turntables.cpp similarity index 88% rename from Turntables.cpp.txt rename to Turntables.cpp index 45a1d05..67dc8c0 100644 --- a/Turntables.cpp.txt +++ b/Turntables.cpp @@ -36,13 +36,14 @@ Turntable *Turntable::_firstTurntable = 0; /* * Public static data */ -int Turntable::_turntablelistHash = 0; +int Turntable::turntablelistHash = 0; /* * Protected static functions */ // Add new turntable to end of list + void Turntable::add(Turntable *tto) { if (!_firstTurntable) { _firstTurntable = tto; @@ -73,25 +74,25 @@ bool Turntable::remove(uint16_t id) { pp->_nextTurntable = tto->_nextTurntable; } - delete (EXTTTurntable *)tto; + // delete (EXTTTurntable *)tto; turntablelistHash++; return true; } - /* * Public static functions */ bool Turntable::isPosition(uint16_t id, uint8_t position) { Turntable *tto = get(id); - if (!tto) return false; if (tto) { if (tto->getPosition() == position) { return true; } else { return false; } + } else { + return false; } } @@ -102,15 +103,16 @@ bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif + return true; } -bool Turntable::setPosition(uint16_t id, uint8_t position) { +bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) DIAG(F("Turntable(%d, %d)"), id, position); #endif Turntable *tto = Turntable::get(id); if (!tto) return false; - bool ok = tto->setPositionInternal(position); + bool ok = tto->setPositionInternal(position, activity); if (ok) { tto->setPositionStateOnly(id, position); @@ -123,30 +125,28 @@ bool Turntable::setPosition(uint16_t id, uint8_t position) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) : +EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : Turntable(id, TURNTABLE_EXTT) { _exttTurntableData.i2caddress = i2caddress; _exttTurntableData.vpin = vpin; - _exttTurntableData.positions = **positions; } // Create function #ifndef IO_NO_HAL - Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) { + Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; - extt->_exttTurntableData.positions = positions; return tto; } else { remove(id); } } - tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin, **positions); + tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); DIAG(F("Turntable 0x%x"), tto); return tto; #else @@ -166,9 +166,9 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long ** bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL // Get step value from positions - int value = _exttTurntableData.positions[position]; + // int value = _exttTurntableData.positions[position]; // Set position via device driver - EXTurntable::_writeAnalogue(vpin, value, activity, 0); + // EXTurntable::_writeAnalogue(vpin, value, activity, 0); #else (void)position; #endif diff --git a/Turntables.h.txt b/Turntables.h similarity index 96% rename from Turntables.h.txt rename to Turntables.h index 5a6f346..2fa4255 100644 --- a/Turntables.h.txt +++ b/Turntables.h @@ -104,6 +104,7 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); + /* * Virtual functions @@ -112,6 +113,7 @@ public: (void)stream; // suppress compiler warnings } virtual ~Turntable() {} // Destructor + /* * Public static functions @@ -119,7 +121,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool remove(uint16_t id); static bool isPosition(uint16_t id, uint8_t position); - static bool setPosition(uint16_t id, uint8_t position); + static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { @@ -148,11 +150,11 @@ private: } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin); public: // Create function - static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin); void print(Print *stream) override; protected: From ff9c558b61b9213f54d68e3db2e667cf040e91e4 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Wed, 23 Aug 2023 19:08:04 +1000 Subject: [PATCH 11/83] Not much progress --- DCCEXParser.cpp | 6 +++--- Turntables.cpp | 2 +- Turntables.h | 7 ++++++- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 4823e8e..e6bd814 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,17 +1035,17 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // <I> list turntable objects return Turntable::printAll(stream); - case 1: // <T id> delete turntable + case 1: // <I id> delete turntable if (!Turntable::remove(p[0])) return false; StringFormatter::send(stream, F("<O>\n")); return true; - case 2: // <T id position> - rotate to position for DCC turntables + case 2: // <I id position> - rotate to position for DCC turntables DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); return true; - case 3: // <T id position activity> rotate to position for EX-Turntable + case 3: // <I id position activity> rotate to position for EX-Turntable DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); return true; diff --git a/Turntables.cpp b/Turntables.cpp index 67dc8c0..5aaf9f0 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -74,7 +74,7 @@ bool Turntable::remove(uint16_t id) { pp->_nextTurntable = tto->_nextTurntable; } - // delete (EXTTTurntable *)tto; + delete (EXTTTurntable *)tto; turntablelistHash++; return true; diff --git a/Turntables.h b/Turntables.h index 2fa4255..c7bb394 100644 --- a/Turntables.h +++ b/Turntables.h @@ -57,6 +57,12 @@ protected: uint16_t id; } _turntableData; + // Linked list to store either positions (EXTT) or DCC addresses (DCC) + struct Position { + int16_t position; + Position *next; + }; + // Pointer to next turntable object Turntable *_nextTurntable = 0; @@ -146,7 +152,6 @@ private: struct EXTTTurntableData { uint8_t i2caddress; VPIN vpin; - long **positions; // Array of longs to store step positions } _exttTurntableData; // Constructor From 57d4655d54be41357d7a87469c45847044b8f51b Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 24 Aug 2023 07:22:37 +1000 Subject: [PATCH 12/83] Fix Uno/Nano build errors --- Turntables.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Turntables.cpp b/Turntables.cpp index 5aaf9f0..2f2a05e 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -133,8 +133,8 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : } // Create function -#ifndef IO_NO_HAL Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { +#ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { @@ -153,7 +153,6 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : (void)id; (void)i2caddress; (void)vpin; - (void)positions; return NULL; #endif } From 6cd7002e911f3bd09421e4570a7fc6129bc8a193 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Thu, 24 Aug 2023 10:03:29 +0200 Subject: [PATCH 13/83] Bugfix: execute 30ms off time before rejoin --- DCCACK.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCACK.cpp b/DCCACK.cpp index 1b339ee..8a074b4 100644 --- a/DCCACK.cpp +++ b/DCCACK.cpp @@ -351,7 +351,7 @@ void DCCACK::callback(int value) { switch (callbackState) { case AFTER_READ: - if (ackManagerRejoin && autoPowerOff) { + if (ackManagerRejoin && !autoPowerOff) { progDriver->setPower(POWERMODE::OFF); callbackStart=millis(); callbackState=WAITING_30; From 42f3c7c12836a545bc6ca7e6e3577e9d9fa31b2f Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Thu, 24 Aug 2023 10:05:31 +0200 Subject: [PATCH 14/83] version number update --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 3eafa76..a6e05ac 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.0.0" +#define VERSION "5.0.1" +// 5.0.1 - Bugfix: execute 30ms off time before rejoin // 5.0.0 - Make 4.2.69 the 5.0.0 release // 4.2.69 - Bugfix: Make <!> work in DC mode // 4.2.68 - Rename track mode OFF to NONE From 210d96a3e37c75ef50f59ab0f0bab1abd7746124 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Fri, 25 Aug 2023 19:07:57 +0200 Subject: [PATCH 15/83] Bugfix: ESP32 30ms off time --- TrackManager.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 0f69235..91c78ea 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -53,7 +53,7 @@ bool TrackManager::progTrackSyncMain=false; bool TrackManager::progTrackBoosted=false; int16_t TrackManager::joinRelay=UNUSED_PIN; #ifdef ARDUINO_ARCH_ESP32 -byte TrackManager::tempProgTrack=MAX_TRACKS+1; +byte TrackManager::tempProgTrack=MAX_TRACKS+1; // MAX_TRACKS+1 is the unused flag #endif #ifdef ANALOG_READ_INTERRUPT @@ -505,7 +505,12 @@ void TrackManager::setJoin(bool joined) { } } else { if (tempProgTrack != MAX_TRACKS+1) { + // as setTrackMode with TRACK_MODE_PROG defaults to + // power off, we will take the current power state + // of our track and then preserve that state. + POWERMODE tPTmode = track[tempProgTrack]->getPower(); //get current power status of this track setTrackMode(tempProgTrack, TRACK_MODE_PROG); + track[tempProgTrack]->setPower(tPTmode); //set track status as it was before tempProgTrack = MAX_TRACKS+1; } } From c55fa9f9d29f29968db96e45c21fef6e6c9c04fc Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Fri, 25 Aug 2023 19:08:58 +0200 Subject: [PATCH 16/83] version number update --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index a6e05ac..d52902a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.0.1" +#define VERSION "5.0.2" +// 5.0.2 - Bugfix: ESP32 30ms off time // 5.0.1 - Bugfix: execute 30ms off time before rejoin // 5.0.0 - Make 4.2.69 the 5.0.0 release // 4.2.69 - Bugfix: Make <!> work in DC mode From b823a647ac82a90ad1f95b3797933e92854d0eca Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Sat, 26 Aug 2023 10:26:01 +1000 Subject: [PATCH 17/83] Some progress --- DCCEXParser.cpp | 26 ++++++++++++++++++++------ Turntables.cpp | 29 ++++++++++++++--------------- Turntables.h | 49 +++++++++++++++++++++++++++++++++++++++++-------- 3 files changed, 75 insertions(+), 29 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index e6bd814..835dd32 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,18 +1035,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // <I> list turntable objects return Turntable::printAll(stream); - case 1: // <I id> delete turntable - if (!Turntable::remove(p[0])) - return false; - StringFormatter::send(stream, F("<O>\n")); - return true; + case 1: // <I id> nothing here for the moment at least + return false; case 2: // <I id position> - rotate to position for DCC turntables DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); return true; case 3: // <I id position activity> rotate to position for EX-Turntable - DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Position %d value is %d"), p[1], value); + } else { + return false; + } + } else { + return false; + } + } return true; default: // If we're here, it must be creating a turntable object @@ -1054,6 +1063,11 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + Turntable *tto = Turntable::get(p[0]); + for ( uint8_t i = 0; i < params - 4; i++) { + tto->addPosition(p[i + 3]); + DIAG(F("Add position %d"), p[i + 3]); + } } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index 2f2a05e..1ab5a70 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -62,22 +62,23 @@ Turntable *Turntable::get(uint16_t id) { return NULL; } -// Remove specified turntable from list and delete it -bool Turntable::remove(uint16_t id) { - Turntable *tto, *pp=NULL; +// Add a position +void Turntable::addPosition(uint16_t value) { + _turntablePositions.insert(value); +} - for (tto=_firstTurntable; tto!=NULL && tto->_turntableData.id!=id; pp=tto, tto=tto->_nextTurntable) {} - if (tto == NULL) return false; - if (tto == _firstTurntable) { - _firstTurntable = tto->_nextTurntable; - } else { - pp->_nextTurntable = tto->_nextTurntable; +// Get value for position +uint16_t Turntable::getPositionValue(size_t position) { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + for (size_t i = 0; i < position && currentPosition; i++) { + currentPosition = currentPosition->next; } - delete (EXTTTurntable *)tto; - - turntablelistHash++; - return true; + if (currentPosition) { + return currentPosition->data; + } else { + return false; + } } /* @@ -142,8 +143,6 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; return tto; - } else { - remove(id); } } tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); diff --git a/Turntables.h b/Turntables.h index c7bb394..3708d2a 100644 --- a/Turntables.h +++ b/Turntables.h @@ -33,6 +33,41 @@ enum { // TURNTABLE_DCC = 2, }; +/************************************************************************************* + * Turntable positions. + * + *************************************************************************************/ +struct TurntablePosition { + uint16_t data; + TurntablePosition* next; + + TurntablePosition(uint16_t value) : data(value), next(nullptr) {} +}; + +class TurntablePositionList { +public: + TurntablePositionList() : head(nullptr) {} + + void insert(uint16_t value) { + TurntablePosition* newPosition = new TurntablePosition(value); + if(!head) { + head = newPosition; + } else { + newPosition->next = head; + head = newPosition; + } + } + + TurntablePosition* getHead() { + return head; + } + +private: + TurntablePosition* head; + +}; + + /************************************************************************************* * Turntable - Base class for turntables. * @@ -57,15 +92,12 @@ protected: uint16_t id; } _turntableData; - // Linked list to store either positions (EXTT) or DCC addresses (DCC) - struct Position { - int16_t position; - Position *next; - }; - // Pointer to next turntable object Turntable *_nextTurntable = 0; + // Linked list for positions + TurntablePositionList _turntablePositions; + /* * Constructor */ @@ -73,6 +105,7 @@ protected: _turntableData.id = id; _turntableData.turntableType = turntableType; _turntableData.hidden = false; + _turntableData.position = 0; add(this); } @@ -110,7 +143,8 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - + void addPosition(uint16_t value); + uint16_t getPositionValue(size_t position); /* * Virtual functions @@ -125,7 +159,6 @@ public: * Public static functions */ inline static bool exists(uint16_t id) { return get(id) != 0; } - static bool remove(uint16_t id); static bool isPosition(uint16_t id, uint8_t position); static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); From 1425da20b500f254f7f16b2a1ba4493f463753ce Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sat, 26 Aug 2023 19:41:17 +1000 Subject: [PATCH 18/83] Correct order --- DCCEXParser.cpp | 5 +++-- IO_EXTurntable.cpp | 1 + Turntables.cpp | 12 ++++++------ Turntables.h | 6 +++--- 4 files changed, 13 insertions(+), 11 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 835dd32..995162b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1060,11 +1060,12 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { + DIAG(F("Params: %d"), params); if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); - if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for ( uint8_t i = 0; i < params - 4; i++) { + for ( uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); DIAG(F("Add position %d"), p[i + 3]); } diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index f1a108b..b57fa25 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -100,6 +100,7 @@ int EXTurntable::_read(VPIN vpin) { // Acc_Off = 9 // Turn accessory pin off void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) { if (_deviceState == DEVSTATE_FAILED) return; + if (value < 0) return; uint8_t stepsMSB = value >> 8; uint8_t stepsLSB = value & 0xFF; #ifdef DIAG_IO diff --git a/Turntables.cpp b/Turntables.cpp index 1ab5a70..f75b30d 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -126,26 +126,26 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : +EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : Turntable(id, TURNTABLE_EXTT) { - _exttTurntableData.i2caddress = i2caddress; _exttTurntableData.vpin = vpin; + _exttTurntableData.i2caddress = i2caddress; } // Create function - Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { + Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin, uint8_t i2caddress) { #ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; - extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; + extt->_exttTurntableData.i2caddress = i2caddress; return tto; } } - tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); + tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); DIAG(F("Turntable 0x%x"), tto); return tto; #else @@ -157,7 +157,7 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : } void EXTTTurntable::print(Print *stream) { - StringFormatter::send(stream, F("<i %d EXTURNTABLE %d %d>\n"), _turntableData.id, _exttTurntableData.i2caddress, _exttTurntableData.vpin); + StringFormatter::send(stream, F("<i %d EXTURNTABLE %d %d>\n"), _turntableData.id, _exttTurntableData.vpin, _exttTurntableData.i2caddress); } // EX-Turntable specific code for moving to the specified position diff --git a/Turntables.h b/Turntables.h index 3708d2a..303c542 100644 --- a/Turntables.h +++ b/Turntables.h @@ -183,16 +183,16 @@ class EXTTTurntable : public Turntable { private: // EXTTTurntableData contains device specific data struct EXTTTurntableData { - uint8_t i2caddress; VPIN vpin; + uint8_t i2caddress; } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin); + EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress); public: // Create function - static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin); + static Turntable *create(uint16_t id, VPIN vpin, uint8_t i2caddress); void print(Print *stream) override; protected: From 2202cb0c5eddbc4ca3c1a3df1c95604278f64353 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 27 Aug 2023 19:30:56 +1000 Subject: [PATCH 19/83] Minor progress --- DCCEXParser.cpp | 6 +++--- IO_EXTurntable.cpp | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 995162b..48c45fb 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1060,15 +1060,15 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { - DIAG(F("Params: %d"), params); if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); + if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for ( uint8_t i = params - 4; i > 0; i--) { + for (uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); - DIAG(F("Add position %d"), p[i + 3]); } + tto->addPosition(0); // Need to add position 0 as 0 so positions start at 1 } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index b57fa25..8c7057b 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -51,6 +51,7 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { void EXTurntable::_begin() { I2CManager.begin(); if (I2CManager.exists(_I2CAddress)) { + DIAG(F("EX-Turntable device found, I2C:%s"), _I2CAddress.toString()); #ifdef DIAG_IO _display(); #endif From df4a501e8a34fd7748675bf3801be10419334649 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 28 Aug 2023 08:36:09 +1000 Subject: [PATCH 20/83] Writing to driver --- DCCEXParser.cpp | 23 +++++++++++++++-------- Turntables.cpp | 22 ++++++---------------- Turntables.h | 1 - 3 files changed, 21 insertions(+), 25 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 48c45fb..45e8a73 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1039,19 +1039,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return false; case 2: // <I id position> - rotate to position for DCC turntables - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (tto->getPosition() == p[1]) return true; + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + } else { + return false; + } + } else { + return false; + } + } return true; case 3: // <I id position activity> rotate to position for EX-Turntable { Turntable *tto = Turntable::get(p[0]); if (tto) { - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Position %d value is %d"), p[1], value); - } else { - return false; - } + if (!tto->setPosition(p[0], p[1], p[2])) return false; } else { return false; } @@ -1061,7 +1069,6 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { - DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); diff --git a/Turntables.cpp b/Turntables.cpp index f75b30d..ec31a00 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -84,19 +84,6 @@ uint16_t Turntable::getPositionValue(size_t position) { /* * Public static functions */ -bool Turntable::isPosition(uint16_t id, uint8_t position) { - Turntable *tto = get(id); - if (tto) { - if (tto->getPosition() == position) { - return true; - } else { - return false; - } - } else { - return false; - } -} - bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { Turntable *tto = get(id); if (!tto) return false; @@ -117,6 +104,7 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { tto->setPositionStateOnly(id, position); + tto->_turntableData.position = position; } return ok; } @@ -163,10 +151,12 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : // EX-Turntable specific code for moving to the specified position bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL - // Get step value from positions - // int value = _exttTurntableData.positions[position]; + DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); + // Get position value from position list + int16_t value = getPositionValue(position); + if (!value) return false; // Return false if it's not a valid position // Set position via device driver - // EXTurntable::_writeAnalogue(vpin, value, activity, 0); + EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else (void)position; #endif diff --git a/Turntables.h b/Turntables.h index 303c542..f3a3321 100644 --- a/Turntables.h +++ b/Turntables.h @@ -159,7 +159,6 @@ public: * Public static functions */ inline static bool exists(uint16_t id) { return get(id) != 0; } - static bool isPosition(uint16_t id, uint8_t position); static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); inline static Turntable *first() { return _firstTurntable; } From 3bfdd16288af0424c7d162f6f13787a79030dc25 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 28 Aug 2023 13:11:37 +1000 Subject: [PATCH 21/83] Start on JO --- DCCEXParser.cpp | 26 +++++++++++++++++++++++++- Turntables.cpp | 4 ++-- 2 files changed, 27 insertions(+), 3 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 45e8a73..f8dd9d4 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -85,6 +85,7 @@ const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_I='I'; +const int16_t HASH_KEYWORD_O='O'; const int16_t HASH_KEYWORD_R='R'; const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_X='X'; @@ -691,6 +692,29 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; + case HASH_KEYWORD_O: // <JO returns turntable list + StringFormatter::send(stream, F("<jO")); + if (params==1) { // <JO> + for ( Turntable * tto=Turntable::first(); tto; tto=tto->next()) { + if (tto->isHidden()) continue; + StringFormatter::send(stream, F(" %d"),tto->getId()); + } + } else { // <JO id> + Turntable *tto=Turntable::get(id); + if (!tto || tto->isHidden()) { + StringFormatter::send(stream, F(" %d X"), id); + } else { + uint8_t pos = tto->getPosition(); + const FSH *todesc = NULL; +#ifdef EXRAIL_ACTIVE + // todesc = RMFT2::getTurntableDescription(id); +#endif + if (todesc == NULL) todesc = F(""); + StringFormatter::send(stream, F(" %d %d"), id, pos); + } + } + StringFormatter::send(stream, F(">\n")); + return; default: break; } // switch(p[1]) break; // case J @@ -1075,7 +1099,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) for (uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); } - tto->addPosition(0); // Need to add position 0 as 0 so positions start at 1 + tto->addPosition(p[3]); // Allow setting a value for the home angle for throttles to draw it } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index ec31a00..5332aa5 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -152,8 +152,8 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); - // Get position value from position list - int16_t value = getPositionValue(position); + if (position == 0) return false; // Position 0 is just so throttles know where home is + int16_t value = getPositionValue(position); // Get position value from position list if (!value) return false; // Return false if it's not a valid position // Set position via device driver EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); From b0d85101275b3184f902547a9b0f6a684571e5e9 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 29 Aug 2023 13:38:52 +1000 Subject: [PATCH 22/83] Working but limited --- DCCEXParser.cpp | 17 +++++++++++------ Turntables.cpp | 32 +++++++++++++++++++++++++------- Turntables.h | 2 ++ 3 files changed, 38 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index f8dd9d4..9047cad 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -695,7 +695,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case HASH_KEYWORD_O: // <JO returns turntable list StringFormatter::send(stream, F("<jO")); if (params==1) { // <JO> - for ( Turntable * tto=Turntable::first(); tto; tto=tto->next()) { + for (Turntable * tto=Turntable::first(); tto; tto=tto->next()) { if (tto->isHidden()) continue; StringFormatter::send(stream, F(" %d"),tto->getId()); } @@ -705,12 +705,18 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) StringFormatter::send(stream, F(" %d X"), id); } else { uint8_t pos = tto->getPosition(); + uint8_t type = tto->getType(); + uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE // todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d"), id, pos); + StringFormatter::send(stream, F(" %d %d %d %d"), id, type, pos, posCount); + for (uint8_t p = 0; p < posCount; p++) { + int16_t value = tto->getPositionValue(p); + StringFormatter::send(stream, F(" %d"), value); + } } } StringFormatter::send(stream, F(">\n")); @@ -1047,7 +1053,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable // <I> - list all -// <I id> - delete // <I id steps> - operate (DCC) // <I id steps activity> - operate (EXTT) // <I id EXTT i2caddress vpin position1 position2 ...> - create EXTT @@ -1096,10 +1101,10 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for (uint8_t i = params - 4; i > 0; i--) { - tto->addPosition(p[i + 3]); + for (uint8_t i = params - 5; i > 0; i--) { + tto->addPosition(p[i + 4]); } - tto->addPosition(p[3]); // Allow setting a value for the home angle for throttles to draw it + tto->addPosition(p[4]); // Allow setting a value for the home angle for throttles to draw it } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index 5332aa5..bcc0a94 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -81,6 +81,17 @@ uint16_t Turntable::getPositionValue(size_t position) { } } +// Get the count of positions associated with the turntable +uint8_t Turntable::getPositionCount() { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + uint8_t count = 0; + while (currentPosition) { + count++; + currentPosition = currentPosition->next; + } + return count; +} + /* * Public static functions */ @@ -103,8 +114,11 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { bool ok = tto->setPositionInternal(position, activity); if (ok) { - tto->setPositionStateOnly(id, position); - tto->_turntableData.position = position; + // Broadcast a position change only if non zero has been set, or home/calibration sent + if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { + tto->setPositionStateOnly(id, position); + tto->_turntableData.position = position; + } } return ok; } @@ -134,7 +148,7 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : } } tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); - DIAG(F("Turntable 0x%x"), tto); + DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; #else (void)id; @@ -151,10 +165,14 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : // EX-Turntable specific code for moving to the specified position bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL - DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); - if (position == 0) return false; // Position 0 is just so throttles know where home is - int16_t value = getPositionValue(position); // Get position value from position list - if (!value) return false; // Return false if it's not a valid position + int16_t value; + if (position == 0) { + value = 0; // Position 0 is just to send activities + } else { + if (activity > 1) return false; // If sending a position update, only phase changes valid (0|1) + value = getPositionValue(position); // Get position value from position list + } + if (position > 0 && !value) return false; // Return false if it's not a valid position // Set position via device driver EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else diff --git a/Turntables.h b/Turntables.h index f3a3321..1016140 100644 --- a/Turntables.h +++ b/Turntables.h @@ -140,11 +140,13 @@ public: inline bool isHidden() { return _turntableData.hidden; } inline void setHidden(bool h) {_turntableData.hidden=h; } inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } + inline uint8_t getType() { return _turntableData.turntableType; } inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); void addPosition(uint16_t value); uint16_t getPositionValue(size_t position); + uint8_t getPositionCount(); /* * Virtual functions From 6cad794411f60f2022548cb9fb9c6272a0daafd2 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Tue, 29 Aug 2023 19:04:45 +1000 Subject: [PATCH 23/83] Working with 15 positions --- DCCEXParser.cpp | 10 +++++++++- DCCEXParser.h | 5 ++++- IODevice.h | 6 ------ Turntables.cpp | 4 ++++ Turntables.h | 5 +++++ defines.h | 20 ++++++++++++++++++++ 6 files changed, 42 insertions(+), 8 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9047cad..a37e5d0 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -692,6 +692,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; +// No turntables without HAL support +#ifndef IO_NO_HAL case HASH_KEYWORD_O: // <JO returns turntable list StringFormatter::send(stream, F("<jO")); if (params==1) { // <JO> @@ -721,15 +723,19 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; +#endif default: break; } // switch(p[1]) break; // case J } +// No turntables without HAL support +#ifndef IO_NO_HAL case 'I': // TURNTABLE <I ...> if (parseI(stream, params, p)) return; break; +#endif default: //anything else will diagnose and drop out to <X> DIAG(F("Opcode=%c params=%d"), opcode, params); @@ -1051,12 +1057,13 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) } // ========================== -// Turntable +// Turntable - no support if no HAL // <I> - list all // <I id steps> - operate (DCC) // <I id steps activity> - operate (EXTT) // <I id EXTT i2caddress vpin position1 position2 ...> - create EXTT // <I id DCC linear1 linear2 ...> - create DCC? - This TBA +#ifndef IO_NO_HAL bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { switch (params) @@ -1114,6 +1121,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return true; } } +#endif // CALLBACKS must be static bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream) diff --git a/DCCEXParser.h b/DCCEXParser.h index bf067a7..a3d5e10 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -24,6 +24,7 @@ #include <Arduino.h> #include "FSH.h" #include "RingStream.h" +#include "defines.h" typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); typedef void (*AT_COMMAND_CALLBACK)(HardwareSerial * stream,const byte * command); @@ -37,7 +38,7 @@ struct DCCEXParser static void setFilter(FILTER_CALLBACK filter); static void setRMFTFilter(FILTER_CALLBACK filter); static void setAtCommandCallback(AT_COMMAND_CALLBACK filter); - static const int MAX_COMMAND_PARAMS=10; // Must not exceed this + static const int MAX_COMMAND_PARAMS=MAX_PARSER_PARAMS; // Must not exceed this private: @@ -49,7 +50,9 @@ struct DCCEXParser static bool parseS(Print * stream, int16_t params, int16_t p[]); static bool parsef(Print * stream, int16_t params, int16_t p[]); static bool parseD(Print * stream, int16_t params, int16_t p[]); +#ifndef IO_NO_HAL static bool parseI(Print * stream, int16_t params, int16_t p[]); +#endif static Print * getAsyncReplyStream(); static void commitAsyncReplyStream(); diff --git a/IODevice.h b/IODevice.h index 769e111..d2c80a4 100644 --- a/IODevice.h +++ b/IODevice.h @@ -27,12 +27,6 @@ // Define symbol DIAG_LOOPTIMES to enable CS loop execution time to be reported //#define DIAG_LOOPTIMES -// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required -// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. -#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) -#define IO_NO_HAL -#endif - // Define symbol IO_SWITCH_OFF_SERVO to set the PCA9685 output to 0 when an // animation has completed. This switches off the servo motor, preventing // the continuous buzz sometimes found on servos, and reducing the diff --git a/Turntables.cpp b/Turntables.cpp index bcc0a94..6b4260f 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -26,6 +26,8 @@ #include "EXRAIL2.h" #include "DCC.h" +// No turntable support without HAL +#ifndef IO_NO_HAL /* * Protected static data @@ -180,3 +182,5 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : #endif return true; } + +#endif diff --git a/Turntables.h b/Turntables.h index 1016140..67017df 100644 --- a/Turntables.h +++ b/Turntables.h @@ -25,6 +25,9 @@ #include "IODevice.h" #include "StringFormatter.h" +// No turntable support without HAL +#ifndef IO_NO_HAL + // Turntable type definitions // EXTT = EX-Turntable // DCC = DCC accessory turntables - to be added later @@ -203,3 +206,5 @@ protected: }; #endif + +#endif diff --git a/defines.h b/defines.h index f3822ca..342d1b6 100644 --- a/defines.h +++ b/defines.h @@ -213,6 +213,26 @@ // #define WIFI_SERIAL_LINK_SPEED 115200 +//////////////////////////////////////////////////////////////////////////////// +// +// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required +// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. +// +#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) +#define IO_NO_HAL +#endif + +//////////////////////////////////////////////////////////////////////////////// +// +// This defines the maximum number of parameters DCCEXParser will accept. +// The increase is required to allow for a sufficient number of turntable positions. +// +#ifdef IO_NO_HAL + #define MAX_PARSER_PARAMS 10 +#else + #define MAX_PARSER_PARAMS 20 +#endif + #if __has_include ( "myAutomation.h") #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #define EXRAIL_ACTIVE From 232ac993ecf58451457d6b959cd0845616ff18b0 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 30 Aug 2023 08:45:11 +1000 Subject: [PATCH 24/83] Separate add from create --- DCCEXParser.cpp | 65 +++++++++++++++++++++++++++++++------------------ Turntables.cpp | 14 +++++------ Turntables.h | 18 ++++++++------ 3 files changed, 57 insertions(+), 40 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a37e5d0..24a7914 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -98,6 +98,7 @@ const int16_t HASH_KEYWORD_WIFI = -5583; const int16_t HASH_KEYWORD_ETHERNET = -30767; const int16_t HASH_KEYWORD_WIT = 31594; const int16_t HASH_KEYWORD_EXTT = 8573; +const int16_t HASH_KEYWORD_ADD = 3201; int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; @@ -714,7 +715,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) // todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d %d"), id, type, pos, posCount); + StringFormatter::send(stream, F(" %d %d %d"), id, type, pos); for (uint8_t p = 0; p < posCount; p++) { int16_t value = tto->getPositionValue(p); StringFormatter::send(stream, F(" %d"), value); @@ -1059,10 +1060,12 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable - no support if no HAL // <I> - list all +// <I id> - broadcast type and current position +// <I id DCC> - create DCC - This is TBA // <I id steps> - operate (DCC) // <I id steps activity> - operate (EXTT) -// <I id EXTT i2caddress vpin position1 position2 ...> - create EXTT -// <I id DCC linear1 linear2 ...> - create DCC? - This TBA +// <I id ADD position value> - add position +// <I id EXTT i2caddress vpin home> - create EXTT #ifndef IO_NO_HAL bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { @@ -1071,47 +1074,58 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // <I> list turntable objects return Turntable::printAll(stream); - case 1: // <I id> nothing here for the moment at least + case 1: // <I id> broadcast type and current position return false; case 2: // <I id position> - rotate to position for DCC turntables { - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (tto->getPosition() == p[1]) return true; - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable + DIAG(F("Create DCC turntable %d"), p[0]); + } else { // Otherwise move a DCC turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (tto->getPosition() == p[1]) return true; + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + } else { + return false; + } } else { return false; } - } else { - return false; } } return true; - case 3: // <I id position activity> rotate to position for EX-Turntable + case 3: { - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } else { - return false; + if (p[1] == HASH_KEYWORD_ADD) { // <I id ADD value> add position value to turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + tto->addPosition(p[2]); + StringFormatter::send(stream, F("<i>\n")); + } else { + return false; + } + } else { // <I id position activity> rotate to position for EX-Turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (!tto->setPosition(p[0], p[1], p[2])) return false; + } else { + return false; + } } } return true; - default: // If we're here, it must be creating a turntable object + case 5: // <I id EXTT vpin i2caddress home> create an EXTT turntable { - if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { + if (p[1] == HASH_KEYWORD_EXTT) { if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for (uint8_t i = params - 5; i > 0; i--) { - tto->addPosition(p[i + 4]); - } - tto->addPosition(p[4]); // Allow setting a value for the home angle for throttles to draw it + tto->addPosition(p[4]); } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { @@ -1119,6 +1133,9 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } } return true; + + default: // Anything else is invalid + return false; } } #endif diff --git a/Turntables.cpp b/Turntables.cpp index 6b4260f..a7d42ab 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -70,17 +70,15 @@ void Turntable::addPosition(uint16_t value) { } // Get value for position -uint16_t Turntable::getPositionValue(size_t position) { +uint16_t Turntable::getPositionValue(uint8_t position) { TurntablePosition* currentPosition = _turntablePositions.getHead(); - for (size_t i = 0; i < position && currentPosition; i++) { + while (currentPosition) { + if (currentPosition->index == position) { + return currentPosition->data; + } currentPosition = currentPosition->next; } - - if (currentPosition) { - return currentPosition->data; - } else { - return false; - } + return false; } // Get the count of positions associated with the turntable diff --git a/Turntables.h b/Turntables.h index 67017df..36f5b90 100644 --- a/Turntables.h +++ b/Turntables.h @@ -32,8 +32,8 @@ // EXTT = EX-Turntable // DCC = DCC accessory turntables - to be added later enum { - TURNTABLE_EXTT = 1, - // TURNTABLE_DCC = 2, + TURNTABLE_EXTT = 0, + TURNTABLE_DCC = 1, }; /************************************************************************************* @@ -41,18 +41,19 @@ enum { * *************************************************************************************/ struct TurntablePosition { + uint8_t index; uint16_t data; TurntablePosition* next; - TurntablePosition(uint16_t value) : data(value), next(nullptr) {} + TurntablePosition(uint8_t idx, uint16_t value) : index(idx), data(value), next(nullptr) {} }; class TurntablePositionList { public: - TurntablePositionList() : head(nullptr) {} + TurntablePositionList() : head(nullptr), currentIndex(0) {} void insert(uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(value); + TurntablePosition* newPosition = new TurntablePosition(currentIndex++, value); if(!head) { head = newPosition; } else { @@ -67,6 +68,7 @@ public: private: TurntablePosition* head; + uint8_t currentIndex; }; @@ -87,8 +89,8 @@ protected: union { struct { bool hidden : 1; - uint8_t turntableType : 2; - uint8_t position : 5; // Allows up to 38 positions including 0/home + bool turntableType : 1; + uint8_t position : 6; // Allows up to 63 positions including 0/home }; uint8_t flags; }; @@ -148,7 +150,7 @@ public: inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); void addPosition(uint16_t value); - uint16_t getPositionValue(size_t position); + uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); /* From dbf053858b61d5315790427adb5ed4da08e7a8ae Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 30 Aug 2023 13:40:09 +1000 Subject: [PATCH 25/83] Undo max params --- DCCEXParser.h | 2 +- defines.h | 11 ----------- 2 files changed, 1 insertion(+), 12 deletions(-) diff --git a/DCCEXParser.h b/DCCEXParser.h index a3d5e10..8a7367a 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -38,7 +38,7 @@ struct DCCEXParser static void setFilter(FILTER_CALLBACK filter); static void setRMFTFilter(FILTER_CALLBACK filter); static void setAtCommandCallback(AT_COMMAND_CALLBACK filter); - static const int MAX_COMMAND_PARAMS=MAX_PARSER_PARAMS; // Must not exceed this + static const int MAX_COMMAND_PARAMS=10; // Must not exceed this private: diff --git a/defines.h b/defines.h index 342d1b6..3286aca 100644 --- a/defines.h +++ b/defines.h @@ -222,17 +222,6 @@ #define IO_NO_HAL #endif -//////////////////////////////////////////////////////////////////////////////// -// -// This defines the maximum number of parameters DCCEXParser will accept. -// The increase is required to allow for a sufficient number of turntable positions. -// -#ifdef IO_NO_HAL - #define MAX_PARSER_PARAMS 10 -#else - #define MAX_PARSER_PARAMS 20 -#endif - #if __has_include ( "myAutomation.h") #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #define EXRAIL_ACTIVE From a0c1ad182cb9f76be7da471a6f18ea7698431cde Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Wed, 30 Aug 2023 19:48:30 +1000 Subject: [PATCH 26/83] Start on callback --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- DCCEXParser.cpp | 5 +++++ DCCEXParser.h | 1 + Turntables.cpp | 10 +++++++--- Turntables.h | 5 ++++- 6 files changed, 20 insertions(+), 7 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index eef84a9..ee760b0 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -161,8 +161,8 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { #endif } -void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position) { - broadcastReply(COMMAND_TYPE, F("<i %d %d>\n"), id, position); +void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position, bool moving) { + broadcastReply(COMMAND_TYPE, F("<i %d %d %d>\n"), id, position, moving); } void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { diff --git a/CommandDistributor.h b/CommandDistributor.h index b1af10a..a51d58a 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -49,7 +49,7 @@ public : static void broadcastLoco(byte slot); static void broadcastSensor(int16_t id, bool value); static void broadcastTurnout(int16_t id, bool isClosed); - static void broadcastTurntable(int16_t id, uint8_t position); + static void broadcastTurntable(int16_t id, uint8_t position, bool moving); static void broadcastClockTime(int16_t time, int8_t rate); static void setClockTime(int16_t time, int8_t rate, byte opt); static int16_t retClockTime(); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 24a7914..2b0e06f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1226,3 +1226,8 @@ void DCCEXParser::callback_Wloco(int16_t result) StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result); commitAsyncReplyStream(); } + +void DCCEXParser::callback_Imoving(bool moving) { + if (!moving) StringFormatter::send(getAsyncReplyStream(), F("<i>")); + commitAsyncReplyStream(); +} diff --git a/DCCEXParser.h b/DCCEXParser.h index 8a7367a..7a7ef89 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -72,6 +72,7 @@ struct DCCEXParser static void callback_Wloco(int16_t result); static void callback_Vbit(int16_t result); static void callback_Vbyte(int16_t result); + static void callback_Imoving(bool moving); static FILTER_CALLBACK filterCallback; static FILTER_CALLBACK filterRMFTCallback; static AT_COMMAND_CALLBACK atCommandCallback; diff --git a/Turntables.cpp b/Turntables.cpp index a7d42ab..a0419b1 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -95,10 +95,10 @@ uint8_t Turntable::getPositionCount() { /* * Public static functions */ -bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { +bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); if (!tto) return false; - CommandDistributor::broadcastTurntable(id, position); + CommandDistributor::broadcastTurntable(id, position, moving); #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif @@ -116,7 +116,11 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - tto->setPositionStateOnly(id, position); + if (tto->getType() == TURNTABLE_EXTT) { + tto->setPositionStateOnly(id, position, 1); + } else { + tto->setPositionStateOnly(id, position, 0); + } tto->_turntableData.position = position; } } diff --git a/Turntables.h b/Turntables.h index 36f5b90..d59bc80 100644 --- a/Turntables.h +++ b/Turntables.h @@ -36,6 +36,9 @@ enum { TURNTABLE_DCC = 1, }; +// Callback needs to return a bool: 1 = moving, 0 = stopped +typedef void (*EXTT_CALLBACK)(bool moving); + /************************************************************************************* * Turntable positions. * @@ -167,7 +170,7 @@ public: */ inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); - static bool setPositionStateOnly(uint16_t id, uint8_t position); + static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From b3cafd126e51f2fe954a031fa54dc36fb5c19089 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Wed, 30 Aug 2023 23:26:20 +0200 Subject: [PATCH 27/83] sample file corrections --- myHal.cpp_example.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index d93ea5c..5533554 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -24,6 +24,7 @@ //#include "IO_TouchKeypad.h // Touch keypad with 16 keys //#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXFastClock.h" // FastClock driver +//#include "IO_PCA9555.h" // 16-bit I/O expander (NXP & Texas Instruments). //========================================================================== // The function halSetup() is invoked from CS if it exists within the build. @@ -51,7 +52,7 @@ void halSetup() { // Create a 20x4 LCD display device as display number 2 // (line 0 is written by EX-RAIL 'SCREEN(2, 0, "text")'). - // HALDisplay<LiquidCrystal>(2, 0x27, 20, 4); + // HALDisplay<LiquidCrystal>::create(2, 0x27, 20, 4); //======================================================================= From 9fa213e198f66c877a8fdc6db7bb03ee9ea3e1e4 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 31 Aug 2023 13:51:25 +1000 Subject: [PATCH 28/83] Undo callback --- DCCEXParser.cpp | 5 ----- DCCEXParser.h | 1 - 2 files changed, 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2b0e06f..24a7914 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1226,8 +1226,3 @@ void DCCEXParser::callback_Wloco(int16_t result) StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result); commitAsyncReplyStream(); } - -void DCCEXParser::callback_Imoving(bool moving) { - if (!moving) StringFormatter::send(getAsyncReplyStream(), F("<i>")); - commitAsyncReplyStream(); -} diff --git a/DCCEXParser.h b/DCCEXParser.h index 7a7ef89..8a7367a 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -72,7 +72,6 @@ struct DCCEXParser static void callback_Wloco(int16_t result); static void callback_Vbit(int16_t result); static void callback_Vbyte(int16_t result); - static void callback_Imoving(bool moving); static FILTER_CALLBACK filterCallback; static FILTER_CALLBACK filterRMFTCallback; static AT_COMMAND_CALLBACK atCommandCallback; From f40d57d8bde35ef7b075a602e65ec213a7058b2f Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 08:44:32 +1000 Subject: [PATCH 29/83] Add DCC type, EXTT broadcast from driver --- DCCEXParser.cpp | 55 ++++++++++++++-------------- IODevice.cpp | 7 ++++ IODevice.h | 5 +++ IO_EXTurntable.cpp | 16 +++++++++ Turntables.cpp | 90 +++++++++++++++++++++++++++++++++++++--------- Turntables.h | 29 ++++++++++++--- 6 files changed, 152 insertions(+), 50 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 24a7914..7473c26 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -708,7 +708,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) StringFormatter::send(stream, F(" %d X"), id); } else { uint8_t pos = tto->getPosition(); - uint8_t type = tto->getType(); + uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE @@ -1075,22 +1075,29 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return Turntable::printAll(stream); case 1: // <I id> broadcast type and current position - return false; + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + bool type = tto->isEXTT(); + uint8_t position = tto->getPosition(); + StringFormatter::send(stream, F("<i %d %d>\n"), type, position); + } else { + return false; + } + } + return true; case 2: // <I id position> - rotate to position for DCC turntables { + Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable - DIAG(F("Create DCC turntable %d"), p[0]); - } else { // Otherwise move a DCC turntable + if (tto) return false; + if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); + tto->addPosition(0); + } else { // Otherwise move a DCC turntable if (tto) { - if (tto->getPosition() == p[1]) return true; - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); - } else { - return false; - } + if (!tto->setPosition(p[0], p[1])) return false; } else { return false; } @@ -1100,34 +1107,24 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 3: { + Turntable *tto = Turntable::get(p[0]); + if (!tto) return false; if (p[1] == HASH_KEYWORD_ADD) { // <I id ADD value> add position value to turntable - Turntable *tto = Turntable::get(p[0]); - if (tto) { - tto->addPosition(p[2]); - StringFormatter::send(stream, F("<i>\n")); - } else { - return false; - } + tto->addPosition(p[2]); + StringFormatter::send(stream, F("<i>\n")); } else { // <I id position activity> rotate to position for EX-Turntable - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } else { - return false; - } + if (!tto->setPosition(p[0], p[1], p[2])) return false; } } return true; - case 5: // <I id EXTT vpin i2caddress home> create an EXTT turntable + case 4: // <I id EXTT vpin home> create an EXTT turntable { if (p[1] == HASH_KEYWORD_EXTT) { if (Turntable::get(p[0])) return false; - if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; + if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(p[4]); - } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { - DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); + tto->addPosition(p[3]); } else { return false; } diff --git a/IODevice.cpp b/IODevice.cpp index 2ed21b6..e811fff 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -176,6 +176,13 @@ bool IODevice::exists(VPIN vpin) { return findDevice(vpin) != NULL; } +// Return the status of the device att vpin. +uint8_t IODevice::getStatus(VPIN vpin) { + IODevice *dev = findDevice(vpin); + if (!dev) return false; + return dev->_deviceState; +} + // check whether the pin supports notification. If so, then regular _read calls are not required. bool IODevice::hasCallback(VPIN vpin) { IODevice *dev = findDevice(vpin); diff --git a/IODevice.h b/IODevice.h index d2c80a4..a03a64d 100644 --- a/IODevice.h +++ b/IODevice.h @@ -154,6 +154,9 @@ public: // exists checks whether there is a device owning the specified vpin static bool exists(VPIN vpin); + // getStatus returns the state of the device at the specified vpin + static uint8_t getStatus(VPIN vpin); + // Enable shared interrupt on specified pin for GPIO extender modules. The extender module // should pull down this pin when requesting a scan. The pin may be shared by multiple modules. // Without the shared interrupt, input states are scanned periodically to detect changes on @@ -405,9 +408,11 @@ private: void _begin() override; void _loop(unsigned long currentMicros) override; int _read(VPIN vpin) override; + void _broadcastStatus (VPIN vpin, uint8_t status); void _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override; void _display() override; uint8_t _stepperStatus; + uint8_t _previousStatus; }; ///////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 8c7057b..fc1f9c1 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -34,6 +34,8 @@ #include "IODevice.h" #include "I2CManager.h" #include "DIAG.h" +#include "Turntables.h" +#include "CommandDistributor.h" void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { new EXTurntable(firstVpin, nPins, I2CAddress); @@ -44,6 +46,8 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { _firstVpin = firstVpin; _nPins = nPins; _I2CAddress = I2CAddress; + _stepperStatus = 0; + _previousStatus = 0; addDevice(this); } @@ -80,10 +84,22 @@ int EXTurntable::_read(VPIN vpin) { if (_stepperStatus > 1) { return false; } else { + if (_stepperStatus != _previousStatus) { + _broadcastStatus(vpin, _stepperStatus); + _previousStatus = _stepperStatus; + } return _stepperStatus; } } +// If a status change has occurred for a turntable object, broadcast it +void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { + Turntable *tto = Turntable::getByVpin(vpin); + if (tto) { + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + } +} + // writeAnalogue to send the steps and activity to Turntable-EX. // Sends 3 bytes containing the MSB and LSB of the step count, and activity. // value contains the steps, bit shifted to MSB + LSB. diff --git a/Turntables.cpp b/Turntables.cpp index a0419b1..3e33d2b 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -57,13 +57,6 @@ void Turntable::add(Turntable *tto) { turntablelistHash++; } -// Find turntable from list -Turntable *Turntable::get(uint16_t id) { - for (Turntable *tto = _firstTurntable; tto != NULL; tto = tto->_nextTurntable) - if (tto->_turntableData.id == id) return tto; - return NULL; -} - // Add a position void Turntable::addPosition(uint16_t value) { _turntablePositions.insert(value); @@ -95,16 +88,39 @@ uint8_t Turntable::getPositionCount() { /* * Public static functions */ +// Find turntable from list +Turntable *Turntable::get(uint16_t id) { + for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable) + if (tto->_turntableData.id == id) return tto; + return NULL; +} + +// Find turntable via Vpin +Turntable *Turntable::getByVpin(VPIN vpin) { + for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable) { + if (tto->isEXTT()) { + EXTTTurntable *exttTto = static_cast<EXTTTurntable*>(tto); + if (exttTto->getVpin() == vpin) { + return tto; + } + } + } + return nullptr; +} + +// Broadcast position changes bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); if (!tto) return false; - CommandDistributor::broadcastTurntable(id, position, moving); + // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT + if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif return true; } +// Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) DIAG(F("Turntable(%d, %d)"), id, position); @@ -116,12 +132,12 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - if (tto->getType() == TURNTABLE_EXTT) { + tto->_turntableData.position = position; + if (tto->isEXTT()) { tto->setPositionStateOnly(id, position, 1); } else { tto->setPositionStateOnly(id, position, 0); } - tto->_turntableData.position = position; } } return ok; @@ -132,38 +148,39 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : +EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin) : Turntable(id, TURNTABLE_EXTT) { _exttTurntableData.vpin = vpin; - _exttTurntableData.i2caddress = i2caddress; } +using DevState = IODevice::DeviceStateEnum; + // Create function - Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin, uint8_t i2caddress) { + Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin) { #ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; extt->_exttTurntableData.vpin = vpin; - extt->_exttTurntableData.i2caddress = i2caddress; return tto; } } - tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); + if (!IODevice::exists(vpin)) return nullptr; + if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; + tto = (Turntable *)new EXTTTurntable(id, vpin); DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; #else (void)id; - (void)i2caddress; (void)vpin; return NULL; #endif } void EXTTTurntable::print(Print *stream) { - StringFormatter::send(stream, F("<i %d EXTURNTABLE %d %d>\n"), _turntableData.id, _exttTurntableData.vpin, _exttTurntableData.i2caddress); + StringFormatter::send(stream, F("<i %d EXTURNTABLE %d>\n"), _turntableData.id, _exttTurntableData.vpin); } // EX-Turntable specific code for moving to the specified position @@ -185,4 +202,43 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : return true; } +/************************************************************************************* + * DCCTurntable - DCC Turntable device. + * + *************************************************************************************/ +// Private constructor +DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} + +// Create function + Turntable *DCCTurntable::create(uint16_t id) { +#ifndef IO_NO_HAL + Turntable *tto = get(id); + if (!tto) { + tto = (Turntable *)new DCCTurntable(id); + DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); + } + return tto; +#else + (void)id; + return NULL; +#endif + } + + void DCCTurntable::print(Print *stream) { + StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id); + } + + // EX-Turntable specific code for moving to the specified position + bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) { +#ifndef IO_NO_HAL + int16_t value = getPositionValue(position); + if (position == 0 || !value) return false; // Return false if it's not a valid position + // Set position via device driver + // DCC activate function here +#else + (void)position; +#endif + return true; + } + #endif diff --git a/Turntables.h b/Turntables.h index d59bc80..e318724 100644 --- a/Turntables.h +++ b/Turntables.h @@ -135,6 +135,7 @@ protected: public: static Turntable *get(uint16_t id); + static Turntable *getByVpin(VPIN vpin); /* * Static data @@ -148,7 +149,7 @@ public: inline bool isHidden() { return _turntableData.hidden; } inline void setHidden(bool h) {_turntableData.hidden=h; } inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } - inline uint8_t getType() { return _turntableData.turntableType; } + inline bool isEXTT() const { return _turntableData.turntableType == TURNTABLE_EXTT; } inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); @@ -193,16 +194,16 @@ private: // EXTTTurntableData contains device specific data struct EXTTTurntableData { VPIN vpin; - uint8_t i2caddress; } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress); + EXTTTurntable(uint16_t id, VPIN vpin); public: // Create function - static Turntable *create(uint16_t id, VPIN vpin, uint8_t i2caddress); + static Turntable *create(uint16_t id, VPIN vpin); void print(Print *stream) override; + VPIN getVpin() const { return _exttTurntableData.vpin; } protected: // EX-Turntable specific code for setting position @@ -210,6 +211,26 @@ protected: }; +/************************************************************************************* + * DCCTurntable - DCC accessory Turntable device. + * + *************************************************************************************/ +class DCCTurntable : public Turntable { +private: + // Constructor + DCCTurntable(uint16_t id); + +public: + // Create function + static Turntable *create(uint16_t id); + void print(Print *stream) override; + +protected: + // DCC specific code for setting position + bool setPositionInternal(uint8_t position, uint8_t activity=0) override; + +}; + #endif #endif From df2f09f4d2efaaf61722d1f98072e1ee13330898 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 09:04:48 +1000 Subject: [PATCH 30/83] Fix build errors --- IODevice.h | 2 ++ IO_EXTurntable.cpp | 3 +-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/IODevice.h b/IODevice.h index a03a64d..4803f56 100644 --- a/IODevice.h +++ b/IODevice.h @@ -380,6 +380,7 @@ private: uint8_t *_pinInUse; }; +#ifndef IO_NO_HAL ///////////////////////////////////////////////////////////////////////////////////////////////////// /* * IODevice subclass for EX-Turntable. @@ -414,6 +415,7 @@ private: uint8_t _stepperStatus; uint8_t _previousStatus; }; +#endif ///////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index fc1f9c1..8741c0c 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -28,8 +28,7 @@ * Refer to the documentation for further information including the valid activities. */ -#ifndef IO_EXTurntable_h -#define IO_EXTurntable_h +#ifndef IO_NO_HAL #include "IODevice.h" #include "I2CManager.h" From 798241927f1909e0fb30272f1d4170d842d7fb22 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 13:28:24 +1000 Subject: [PATCH 31/83] Really fix build errors --- IO_EXTurntable.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 8741c0c..bf06e62 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -28,14 +28,14 @@ * Refer to the documentation for further information including the valid activities. */ -#ifndef IO_NO_HAL - #include "IODevice.h" #include "I2CManager.h" #include "DIAG.h" #include "Turntables.h" #include "CommandDistributor.h" +#ifndef IO_NO_HAL + void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { new EXTurntable(firstVpin, nPins, I2CAddress); } From bcb250bacfc8b2e7a60810dd5b20d0f1da737863 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Fri, 1 Sep 2023 18:30:02 +1000 Subject: [PATCH 32/83] Broadcasts working --- IO_EXTurntable.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index bf06e62..59a65d9 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -71,6 +71,12 @@ void EXTurntable::_loop(unsigned long currentMicros) { uint8_t readBuffer[1]; I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; + if (_stepperStatus < 2) { + if (_stepperStatus != _previousStatus) { + _broadcastStatus(_firstVpin, _stepperStatus); + _previousStatus = _stepperStatus; + } + } // DIAG(F("Turntable-EX returned status: %d"), _stepperStatus); delayUntil(currentMicros + 500000); // Wait 500ms before checking again, turntables turn slowly } @@ -83,10 +89,6 @@ int EXTurntable::_read(VPIN vpin) { if (_stepperStatus > 1) { return false; } else { - if (_stepperStatus != _previousStatus) { - _broadcastStatus(vpin, _stepperStatus); - _previousStatus = _stepperStatus; - } return _stepperStatus; } } From e734661d1b83eb0f3d79d5116e5e9404f07e4b36 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sat, 2 Sep 2023 08:29:49 +1000 Subject: [PATCH 33/83] EXRAIL ready for testing --- EXRAIL2.cpp | 53 +++++++++++++++++++++++++++++++++++++++++++++ EXRAIL2.h | 8 +++++++ EXRAIL2MacroReset.h | 28 +++++++++++++++++------- EXRAILMacros.h | 32 ++++++++++++++++++++++++++- Turntables.cpp | 12 +++++++++- Turntables.h | 1 + 6 files changed, 124 insertions(+), 10 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 0e17ea9..c01189c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -52,6 +52,7 @@ #include "Turnouts.h" #include "CommandDistributor.h" #include "TrackManager.h" +#include "Turntables.h" // Command parsing keywords const int16_t HASH_KEYWORD_EXRAIL=15435; @@ -94,6 +95,7 @@ LookList * RMFT2::onAmberLookup=NULL; LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onClockLookup=NULL; +LookList * RMFT2::onRotateLookup=NULL; #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -175,6 +177,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); + onRotateLookup=LookListLoader(OPCODE_ONROTATE); // Second pass startup, define any turnouts or servos, set signals red @@ -238,6 +241,32 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { setTurnoutHiddenState(VpinTurnout::create(id,pin)); break; } + + case OPCODE_DCCTURNTABLE: { + VPIN id=operand; + setTurntableHiddenState(DCCTurntable::create(id)); + Turntable *tto=Turntable::get(id); + tto->addPosition(0); + break; + } + + case OPCODE_EXTTTURNTABLE: { + VPIN id=operand; + VPIN pin=getOperand(progCounter,1); + int home=getOperand(progCounter,2); + setTurntableHiddenState(EXTTTurntable::create(id,pin)); + Turntable *tto=Turntable::get(id); + tto->addPosition(home); + break; + } + + case OPCODE_TTADDPOSITION: { + VPIN id=operand; + int value=getOperand(progCounter,1); + Turntable *tto=Turntable::get(id); + tto->addPosition(value); + break; + } case OPCODE_AUTOSTART: // automatically create a task from here at startup. @@ -263,6 +292,10 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) { t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); } +void RMFT2::setTurntableHiddenState(Turntable * tto) { + tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); +} + char RMFT2::getRouteType(int16_t id) { for (int16_t i=0;;i+=2) { int16_t rid= GETHIGHFLASHW(routeIdList,i); @@ -598,6 +631,13 @@ void RMFT2::loop2() { case OPCODE_CLOSE: Turnout::setClosed(operand, true); break; + + case OPCODE_ROTATE: + uint8_t activity; + activity=getOperand(2); + if (!activity) activity=0; + Turntable::setPosition(operand,getOperand(1),activity); + break; case OPCODE_REV: forward = false; @@ -788,6 +828,10 @@ void RMFT2::loop2() { case OPCODE_IFCLOSED: skipIf=Turnout::isThrown(operand); break; + + case OPCODE_IFTTPOSITION: // do block if turntable at this position + skipIf=Turntable::getPosition(operand)!=(int)getOperand(1); + break; case OPCODE_ENDIF: break; @@ -986,6 +1030,10 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: + case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime + case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime + case OPCODE_TTADDPOSITION: // Turntable position definition ignored at runtime + case OPCODE_ONROTATE: break; @@ -1130,6 +1178,11 @@ void RMFT2::changeEvent(int16_t vpin, bool change) { if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); } +void RMFT2::rotateEvent(int16_t turntableId, bool change) { + // Hunt or an ONROTATE for this turntable + if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId); +} + void RMFT2::clockEvent(int16_t clocktime, bool change) { // Hunt for an ONTIME for this time if (Diag::CMD) diff --git a/EXRAIL2.h b/EXRAIL2.h index 4d106e6..96bc7db 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -25,6 +25,7 @@ #include "FSH.h" #include "IODevice.h" #include "Turnouts.h" +#include "Turntables.h" // The following are the operation codes (or instructions) for a kind of virtual machine. // Each instruction is normally 3 bytes long with an operation code followed by a parameter. @@ -62,6 +63,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, + OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, + OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -130,6 +133,7 @@ class LookList { static void activateEvent(int16_t addr, bool active); static void changeEvent(int16_t id, bool change); static void clockEvent(int16_t clocktime, bool change); + static void rotateEvent(int16_t id, bool change); static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; @@ -144,6 +148,8 @@ class LookList { static const FSH * getTurnoutDescription(int16_t id); static const FSH * getRosterName(int16_t id); static const FSH * getRosterFunctions(int16_t id); + static const FSH * getTurntableDescription(int16_t id); + // static const FSH * getTurntablePositionDescription(int16_t id, uint8_t position); private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); @@ -156,6 +162,7 @@ private: static bool isSignal(int16_t id,char rag); static int16_t getSignalSlot(int16_t id); static void setTurnoutHiddenState(Turnout * t); + static void setTurntableHiddenState(Turntable * tto); static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); @@ -188,6 +195,7 @@ private: static LookList * onGreenLookup; static LookList * onChangeLookup; static LookList * onClockLookup; + static LookList * onRotateLookup; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 588a417..7c690b7 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -40,6 +40,7 @@ #undef CALL #undef CLOSE #undef DCC_SIGNAL +#undef DCC_TURNTABLE #undef DEACTIVATE #undef DEACTIVATEL #undef DELAY @@ -51,8 +52,9 @@ #undef ENDEXRAIL #undef ENDIF #undef ENDTASK -#undef ESTOP -#undef EXRAIL +#undef ESTOP +#undef EXRAIL +#undef EXTT_TURNTABLE #undef FADE #undef FOFF #undef FOLLOW @@ -75,6 +77,7 @@ #undef IFRESERVE #undef IFTHROWN #undef IFTIMEOUT +#undef IFTTPOSITION #undef IFRE #undef INVERT_DIRECTION #undef JOIN @@ -95,6 +98,7 @@ #undef ONCLOCKMINS #undef ONGREEN #undef ONRED +#undef ONROTATE #undef ONTHROW #undef ONCHANGE #undef PARSE @@ -113,7 +117,8 @@ #undef RESUME #undef RETURN #undef REV -#undef ROSTER +#undef ROSTER +#undef ROTATE #undef ROUTE #undef SENDLOCO #undef SEQUENCE @@ -136,7 +141,8 @@ #undef SPEED #undef START #undef STOP -#undef THROW +#undef THROW +#undef TT_ADDPOSITION #undef TURNOUT #undef TURNOUTL #undef UNJOIN @@ -165,6 +171,7 @@ #define CALL(route) #define CLOSE(id) #define DCC_SIGNAL(id,add,subaddr) +#define DCC_TURNTABLE(id,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) #define DELAY(mindelay) @@ -177,7 +184,8 @@ #define ENDIF #define ENDTASK #define ESTOP -#define EXRAIL +#define EXRAIL +#define EXTT_TURNTABLE(id,vpin,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) @@ -200,6 +208,7 @@ #define IFTHROWN(turnout_id) #define IFRESERVE(block) #define IFTIMEOUT +#define IFTTPOSITION(turntable_id,position) #define IFRE(sensor_id,value) #define INVERT_DIRECTION #define JOIN @@ -219,7 +228,8 @@ #define ONDEACTIVATEL(linear) #define ONCLOSE(turnout_id) #define ONGREEN(signal_id) -#define ONRED(signal_id) +#define ONRED(signal_id) +#define ONROTATE(turntable_id) #define ONTHROW(turnout_id) #define ONCHANGE(sensor_id) #define PAUSE @@ -238,8 +248,9 @@ #define RESUME #define RETURN #define REV(speed) -#define ROUTE(id,description) +#define ROTATE(turntable_id,position,activity) #define ROSTER(cab,name,funcmap...) +#define ROUTE(id,description) #define SENDLOCO(cab,route) #define SEQUENCE(id) #define SERIAL(msg) @@ -261,7 +272,8 @@ #define SPEED(speed) #define START(route) #define STOP -#define THROW(id) +#define THROW(id) +#define TT_ADDPOSITION(turntable_id,value,description) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 66b0111..fc8dbca 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -187,6 +187,30 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { return NULL; } +// Pass to get turntable descriptions (optional) +#include "EXRAIL2MacroReset.h" +#undef DCC_TURNTABLE +#define DCC_TURNTABLE(id,description...) O_DESC(id,description) +#undef EXTT_TURNTABLE +#define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) + +const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { + switch (turntableId) { + #include "myAutomation.h" + default:break; + } + return NULL; +} + +// Pass to get turntable position descriptions (optional) +// #include "EXRAIL2MacroReset.h" +// #undef TT_ADDPOSITION +// #define TT_ADDPOSITION(turntable_id,value,description...) 0_DESC(id,description) + +// const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { + +// } + // Pass 6: Roster IDs (count) #include "EXRAIL2MacroReset.h" #undef ROSTER @@ -268,6 +292,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), +#define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), #define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)), @@ -281,7 +306,8 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ENDIF OPCODE_ENDIF,0,0, #define ENDTASK OPCODE_ENDTASK,0,0, #define ESTOP OPCODE_SPEED,V(1), -#define EXRAIL +#define EXRAIL +#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), #define FOLLOW(route) OPCODE_FOLLOW,V(route), @@ -304,6 +330,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define IFRESERVE(block) OPCODE_IFRESERVE,V(block), #define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id), #define IFTIMEOUT OPCODE_IFTIMEOUT,0,0, +#define IFTTPOSITION(id,position) OPCODE_IFTTPOSITION,V(id),OPCODE_PAD,V(position), #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define JOIN OPCODE_JOIN,0,0, @@ -324,6 +351,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONRED(signal_id) OPCODE_ONRED,V(signal_id), +#define ONROTATE(id) OPCODE_ONROTATE,V(id), #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, @@ -343,6 +371,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define RETURN OPCODE_RETURN,0,0, #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) +#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), @@ -366,6 +395,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), +#define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) #define UNJOIN OPCODE_UNJOIN,0,0, diff --git a/Turntables.cpp b/Turntables.cpp index 3e33d2b..dcf50a0 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -108,6 +108,13 @@ Turntable *Turntable::getByVpin(VPIN vpin) { return nullptr; } +// Get the current position for turntable with the specified ID +uint8_t Turntable::getPosition(uint16_t id) { + Turntable *tto = get(id); + if (!tto) return false; + return tto->getPosition(); +} + // Broadcast position changes bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); @@ -234,7 +241,10 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} int16_t value = getPositionValue(position); if (position == 0 || !value) return false; // Return false if it's not a valid position // Set position via device driver - // DCC activate function here + int16_t addr=value>>3; + int16_t subaddr=(value>>1) & 0x03; + bool active=value & 0x01; + DCC::setAccessory(addr, subaddr, active); #else (void)position; #endif diff --git a/Turntables.h b/Turntables.h index e318724..b95c9c0 100644 --- a/Turntables.h +++ b/Turntables.h @@ -172,6 +172,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); + static uint8_t getPosition(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From 004d10ee586a5efb5eb6ae7c2704b75e4fe8b100 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sat, 2 Sep 2023 18:45:59 +1000 Subject: [PATCH 34/83] Fix build errors --- EXRAIL2.cpp | 14 +++++++++++--- EXRAIL2.h | 2 ++ EXRAILMacros.h | 12 ++++++++++++ 3 files changed, 25 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index c01189c..77a9f88 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -242,6 +242,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { break; } +#ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: { VPIN id=operand; setTurntableHiddenState(DCCTurntable::create(id)); @@ -267,7 +268,8 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { tto->addPosition(value); break; } - +#endif + case OPCODE_AUTOSTART: // automatically create a task from here at startup. // Removed if (progCounter>0) check 4.2.31 because @@ -292,9 +294,11 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) { t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); } +#ifndef IO_NO_HAL void RMFT2::setTurntableHiddenState(Turntable * tto) { tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); } +#endif char RMFT2::getRouteType(int16_t id) { for (int16_t i=0;;i+=2) { @@ -631,13 +635,15 @@ void RMFT2::loop2() { case OPCODE_CLOSE: Turnout::setClosed(operand, true); break; - + +#ifndef IO_NO_HAL case OPCODE_ROTATE: uint8_t activity; activity=getOperand(2); if (!activity) activity=0; Turntable::setPosition(operand,getOperand(1),activity); break; +#endif case OPCODE_REV: forward = false; @@ -829,10 +835,12 @@ void RMFT2::loop2() { skipIf=Turnout::isThrown(operand); break; +#ifndef IO_NO_HAL case OPCODE_IFTTPOSITION: // do block if turntable at this position skipIf=Turntable::getPosition(operand)!=(int)getOperand(1); break; - +#endif + case OPCODE_ENDIF: break; diff --git a/EXRAIL2.h b/EXRAIL2.h index 96bc7db..16fff82 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -162,7 +162,9 @@ private: static bool isSignal(int16_t id,char rag); static int16_t getSignalSlot(int16_t id); static void setTurnoutHiddenState(Turnout * t); + #ifndef IO_NO_HAL static void setTurntableHiddenState(Turntable * tto); + #endif static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index fc8dbca..f5d905e 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -292,7 +292,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), +#ifndef IO_NO_HAL #define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), +#endif #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), #define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)), @@ -307,7 +309,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ENDTASK OPCODE_ENDTASK,0,0, #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL +#ifndef IO_NO_HAL #define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), +#endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), #define FOLLOW(route) OPCODE_FOLLOW,V(route), @@ -330,7 +334,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define IFRESERVE(block) OPCODE_IFRESERVE,V(block), #define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id), #define IFTIMEOUT OPCODE_IFTIMEOUT,0,0, +#ifndef IO_NO_HAL #define IFTTPOSITION(id,position) OPCODE_IFTTPOSITION,V(id),OPCODE_PAD,V(position), +#endif #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define JOIN OPCODE_JOIN,0,0, @@ -351,7 +357,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONRED(signal_id) OPCODE_ONRED,V(signal_id), +#ifndef IO_NO_HAL #define ONROTATE(id) OPCODE_ONROTATE,V(id), +#endif #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, @@ -371,7 +379,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define RETURN OPCODE_RETURN,0,0, #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) +#ifndef IO_NO_HAL #define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), +#endif #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), @@ -395,7 +405,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), +#ifndef IO_NO_HAL #define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), +#endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) #define UNJOIN OPCODE_UNJOIN,0,0, From 1e48c59cd8d4b0a16370731078e60e8abb949999 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 3 Sep 2023 18:54:56 +1000 Subject: [PATCH 35/83] Capture progress --- IO_EXTurntable.cpp | 12 +++++------- Turntables.cpp | 5 ++++- Turntables.h | 3 +++ 3 files changed, 12 insertions(+), 8 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 59a65d9..eba8321 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -71,14 +71,11 @@ void EXTurntable::_loop(unsigned long currentMicros) { uint8_t readBuffer[1]; I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; - if (_stepperStatus < 2) { - if (_stepperStatus != _previousStatus) { - _broadcastStatus(_firstVpin, _stepperStatus); - _previousStatus = _stepperStatus; - } + if (_stepperStatus != _previousStatus && _stepperStatus == 0) { // Broadcast when a rotation finishes + _broadcastStatus(_firstVpin, _stepperStatus); + _previousStatus = _stepperStatus; } - // DIAG(F("Turntable-EX returned status: %d"), _stepperStatus); - delayUntil(currentMicros + 500000); // Wait 500ms before checking again, turntables turn slowly + delayUntil(currentMicros + 100000); // Wait 100ms before checking again } // Read returns status as obtained in our loop. @@ -128,6 +125,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } diff --git a/Turntables.cpp b/Turntables.cpp index dcf50a0..f7b2a46 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -122,7 +122,9 @@ bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } #if defined(EXRAIL_ACTIVE) - // RMFT2::turntableEvent(id, position); + bool rotated = false; + if (position != tto->_previousPosition) rotated = true; + if (!tto->isEXTT()) { RMFT2::rotateEvent(id, rotated); } #endif return true; } @@ -138,6 +140,7 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent + tto->_previousPosition = tto->getPosition(); if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { tto->_turntableData.position = position; if (tto->isEXTT()) { diff --git a/Turntables.h b/Turntables.h index b95c9c0..67ab0e3 100644 --- a/Turntables.h +++ b/Turntables.h @@ -105,6 +105,9 @@ protected: // Linked list for positions TurntablePositionList _turntablePositions; + + // Store the previous position to allow checking for changes + uint8_t _previousPosition = 0; /* * Constructor From dd890e65bfe2b307ff19c501ac3b87c69f0b8256 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 4 Sep 2023 07:38:26 +1000 Subject: [PATCH 36/83] Add move check --- IO_EXTurntable.cpp | 1 + Turntables.h | 5 +++++ 2 files changed, 6 insertions(+) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index eba8321..dcbe018 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -95,6 +95,7 @@ void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + tto->setMoving(status); } } diff --git a/Turntables.h b/Turntables.h index 67ab0e3..30cba82 100644 --- a/Turntables.h +++ b/Turntables.h @@ -109,6 +109,9 @@ protected: // Store the previous position to allow checking for changes uint8_t _previousPosition = 0; + // Store the current state of the turntable + bool _isMoving = false; + /* * Constructor */ @@ -159,6 +162,8 @@ public: void addPosition(uint16_t value); uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); + bool isMoving() { return _isMoving; } + void setMoving(bool moving) { _isMoving=moving; } /* * Virtual functions From 86f45675565ab4df0d4beddd0d07e52b06c340b1 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Mon, 4 Sep 2023 18:46:28 +1000 Subject: [PATCH 37/83] Revisiting logic --- DCCEXParser.cpp | 9 +++++---- Turntables.cpp | 3 ++- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7473c26..2014762 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1087,7 +1087,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 2: // <I id position> - rotate to position for DCC turntables + case 2: // <I id DCC> | <I id position> - rotate or create DCC turntable { Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable @@ -1096,7 +1096,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) Turntable *tto = Turntable::get(p[0]); tto->addPosition(0); } else { // Otherwise move a DCC turntable - if (tto) { + if (tto && !tto->isEXTT()) { if (!tto->setPosition(p[0], p[1])) return false; } else { return false; @@ -1105,14 +1105,15 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 3: + case 3: // <I id ADD value> | <I id position activity> { Turntable *tto = Turntable::get(p[0]); if (!tto) return false; - if (p[1] == HASH_KEYWORD_ADD) { // <I id ADD value> add position value to turntable + if (p[1] == HASH_KEYWORD_ADD) { // Add position value to turntable tto->addPosition(p[2]); StringFormatter::send(stream, F("<i>\n")); } else { // <I id position activity> rotate to position for EX-Turntable + if (!tto->isEXTT()) return false; if (!tto->setPosition(p[0], p[1], p[2])) return false; } } diff --git a/Turntables.cpp b/Turntables.cpp index f7b2a46..f96a3a8 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -140,8 +140,8 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent - tto->_previousPosition = tto->getPosition(); if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { + tto->_previousPosition = tto->getPosition(); tto->_turntableData.position = position; if (tto->isEXTT()) { tto->setPositionStateOnly(id, position, 1); @@ -179,6 +179,7 @@ using DevState = IODevice::DeviceStateEnum; } if (!IODevice::exists(vpin)) return nullptr; if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; + if (Turntable::getByVpin(vpin)) return nullptr; tto = (Turntable *)new EXTTTurntable(id, vpin); DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; From 3094c52bf8509d600fa829995d8cf7be263b6365 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 5 Sep 2023 08:38:37 +1000 Subject: [PATCH 38/83] Ready to test --- IO_EXTurntable.cpp | 2 +- Turntables.cpp | 39 +++++++++++++++------------------------ Turntables.h | 1 - 3 files changed, 16 insertions(+), 26 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index dcbe018..b36237f 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -94,8 +94,8 @@ int EXTurntable::_read(VPIN vpin) { void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { - CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); tto->setMoving(status); + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); } } diff --git a/Turntables.cpp b/Turntables.cpp index f96a3a8..120ac2f 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -115,40 +115,27 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } -// Broadcast position changes -bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { - Turntable *tto = get(id); - if (!tto) return false; - // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT - if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } -#if defined(EXRAIL_ACTIVE) - bool rotated = false; - if (position != tto->_previousPosition) rotated = true; - if (!tto->isEXTT()) { RMFT2::rotateEvent(id, rotated); } -#endif - return true; -} - // Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) - DIAG(F("Turntable(%d, %d)"), id, position); + DIAG(F("Rotate turntable %d to position %d, activity %d)"), id, position, activity); #endif Turntable *tto = Turntable::get(id); if (!tto) return false; + if (tto->isMoving()) return false; bool ok = tto->setPositionInternal(position, activity); if (ok) { - // Broadcast a position change only if non zero has been set, or home/calibration sent - if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - tto->_previousPosition = tto->getPosition(); - tto->_turntableData.position = position; - if (tto->isEXTT()) { - tto->setPositionStateOnly(id, position, 1); - } else { - tto->setPositionStateOnly(id, position, 0); - } + // We only deal with broadcasts for DCC turntables here, EXTT in the device driver + if (!tto->isEXTT()) { + CommandDistributor::broadcastTurntable(id, position, false); } + // Trigger EXRAIL rotateEvent for both types here if changed +#if defined(EXRAIL_ACTIVE) + bool rotated = false; + if (position != tto->_previousPosition) rotated = true; + RMFT2::rotateEvent(id, rotated); +#endif } return ok; } @@ -206,6 +193,8 @@ using DevState = IODevice::DeviceStateEnum; } if (position > 0 && !value) return false; // Return false if it's not a valid position // Set position via device driver + _previousPosition = _turntableData.position; + _turntableData.position = position; EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else (void)position; @@ -248,6 +237,8 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} int16_t addr=value>>3; int16_t subaddr=(value>>1) & 0x03; bool active=value & 0x01; + _previousPosition = _turntableData.position; + _turntableData.position = position; DCC::setAccessory(addr, subaddr, active); #else (void)position; diff --git a/Turntables.h b/Turntables.h index 30cba82..de0151c 100644 --- a/Turntables.h +++ b/Turntables.h @@ -179,7 +179,6 @@ public: */ inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); - static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); static uint8_t getPosition(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { From 152f9850bbd0bd8c1ff7f5cfe4a8c5a8ecad8b90 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Tue, 5 Sep 2023 19:05:18 +1000 Subject: [PATCH 39/83] Working --- IO_EXTurntable.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index b36237f..af220a3 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -82,7 +82,6 @@ void EXTurntable::_loop(unsigned long currentMicros) { // Return false if our status value is invalid. int EXTurntable::_read(VPIN vpin) { if (_deviceState == DEVSTATE_FAILED) return 0; - // DIAG(F("_read status: %d"), _stepperStatus); if (_stepperStatus > 1) { return false; } else { @@ -126,6 +125,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + _previousStatus = _stepperStatus; _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } From 6adff43f4b0f5b7231ca61e555318232c1fd98f5 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 6 Sep 2023 07:59:43 +1000 Subject: [PATCH 40/83] Update add position --- DCCEXParser.cpp | 24 ++++++++++++------------ EXRAIL2.cpp | 9 +++++---- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 2 +- Turntables.cpp | 4 ++-- Turntables.h | 9 ++++----- 6 files changed, 25 insertions(+), 25 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2014762..de1618c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1094,7 +1094,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (tto) return false; if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0); + tto->addPosition(0, 0); } else { // Otherwise move a DCC turntable if (tto && !tto->isEXTT()) { if (!tto->setPosition(p[0], p[1])) return false; @@ -1105,27 +1105,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 3: // <I id ADD value> | <I id position activity> + case 3: // <I id position activity> rotate to position for EX-Turntable { Turntable *tto = Turntable::get(p[0]); if (!tto) return false; - if (p[1] == HASH_KEYWORD_ADD) { // Add position value to turntable - tto->addPosition(p[2]); - StringFormatter::send(stream, F("<i>\n")); - } else { // <I id position activity> rotate to position for EX-Turntable - if (!tto->isEXTT()) return false; - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } + if (!tto->isEXTT()) return false; + if (!tto->setPosition(p[0], p[1], p[2])) return false; } return true; - case 4: // <I id EXTT vpin home> create an EXTT turntable + case 4: // <I id EXTT vpin home> | <I id ADD position value> create an EXTT turntable or add position { + Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_EXTT) { - if (Turntable::get(p[0])) return false; + if (tto) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(p[3]); + tto->addPosition(0, p[3]); + } else if (p[1] == HASH_KEYWORD_ADD) { + if (!tto) return false; + tto->addPosition(p[2], p[3]); + StringFormatter::send(stream, F("<i>\n")); } else { return false; } diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 77a9f88..d88a6f4 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -247,7 +247,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { VPIN id=operand; setTurntableHiddenState(DCCTurntable::create(id)); Turntable *tto=Turntable::get(id); - tto->addPosition(0); + tto->addPosition(0,0); break; } @@ -257,15 +257,16 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { int home=getOperand(progCounter,2); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); - tto->addPosition(home); + tto->addPosition(0,home); break; } case OPCODE_TTADDPOSITION: { VPIN id=operand; - int value=getOperand(progCounter,1); + int position=getOperand(progCounter,1); + int value=getOperand(progCounter,2); Turntable *tto=Turntable::get(id); - tto->addPosition(value); + tto->addPosition(position,value); break; } #endif diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 7c690b7..21d4f18 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -273,7 +273,7 @@ #define START(route) #define STOP #define THROW(id) -#define TT_ADDPOSITION(turntable_id,value,description) +#define TT_ADDPOSITION(turntable_id,position,value,description) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index f5d905e..68f3bf0 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -406,7 +406,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL -#define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), +#define TT_ADDPOSITION(id,position,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value), #endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) diff --git a/Turntables.cpp b/Turntables.cpp index 120ac2f..abbac81 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -58,8 +58,8 @@ void Turntable::add(Turntable *tto) { } // Add a position -void Turntable::addPosition(uint16_t value) { - _turntablePositions.insert(value); +void Turntable::addPosition(uint8_t idx, uint16_t value) { + _turntablePositions.insert(idx, value); } // Get value for position diff --git a/Turntables.h b/Turntables.h index de0151c..15333c9 100644 --- a/Turntables.h +++ b/Turntables.h @@ -53,10 +53,10 @@ struct TurntablePosition { class TurntablePositionList { public: - TurntablePositionList() : head(nullptr), currentIndex(0) {} + TurntablePositionList() : head(nullptr) {} - void insert(uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(currentIndex++, value); + void insert(uint8_t idx, uint16_t value) { + TurntablePosition* newPosition = new TurntablePosition(idx, value); if(!head) { head = newPosition; } else { @@ -71,7 +71,6 @@ public: private: TurntablePosition* head; - uint8_t currentIndex; }; @@ -159,7 +158,7 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - void addPosition(uint16_t value); + void addPosition(uint8_t idx, uint16_t value); uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); bool isMoving() { return _isMoving; } From 1f5f7754c1a4b5c928fadf10046715cd4099aea5 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 6 Sep 2023 15:16:46 +1000 Subject: [PATCH 41/83] Start on position description --- DCCEXParser.cpp | 5 +++-- EXRAIL2.h | 2 +- EXRAILMacros.h | 8 ++++++-- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index de1618c..404685d 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -712,10 +712,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE - // todesc = RMFT2::getTurntableDescription(id); + todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d"), id, type, pos); + StringFormatter::send(stream, F(" %d %d %d"), id, type, pos, todesc); + for (uint8_t p = 0; p < posCount; p++) { int16_t value = tto->getPositionValue(p); StringFormatter::send(stream, F(" %d"), value); diff --git a/EXRAIL2.h b/EXRAIL2.h index 16fff82..f6c4807 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -149,7 +149,7 @@ class LookList { static const FSH * getRosterName(int16_t id); static const FSH * getRosterFunctions(int16_t id); static const FSH * getTurntableDescription(int16_t id); - // static const FSH * getTurntablePositionDescription(int16_t id, uint8_t position); + static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 68f3bf0..c413989 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -205,10 +205,14 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { // Pass to get turntable position descriptions (optional) // #include "EXRAIL2MacroReset.h" // #undef TT_ADDPOSITION -// #define TT_ADDPOSITION(turntable_id,value,description...) 0_DESC(id,description) +// #define TT_ADDPOSITION(turntable_id,value,description...) O_DESC(turntable_id,description) // const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { - +// switch (turntableId) { +// #include "myAutomation.h" +// default:break; +// } +// return NULL; // } // Pass 6: Roster IDs (count) From 21ce87eb3e72a7d8925ea5fec407222ffbd2ce6c Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Thu, 7 Sep 2023 05:33:26 +1000 Subject: [PATCH 42/83] Descriptions available --- DCCEXParser.cpp | 13 ++++++++++--- EXRAILMacros.h | 19 +++++++++---------- 2 files changed, 19 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 404685d..405512c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -702,6 +702,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (tto->isHidden()) continue; StringFormatter::send(stream, F(" %d"),tto->getId()); } + StringFormatter::send(stream, F(">\n")); } else { // <JO id> Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { @@ -711,19 +712,25 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; + const FSH *tpdesc = NULL; #ifdef EXRAIL_ACTIVE todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d"), id, type, pos, todesc); + StringFormatter::send(stream, F(" %d %d %d %d \"%S\">\n"), id, type, pos, posCount, todesc); for (uint8_t p = 0; p < posCount; p++) { + StringFormatter::send(stream, F("jO>")); int16_t value = tto->getPositionValue(p); - StringFormatter::send(stream, F(" %d"), value); +#ifdef EXRAIL_ACTIVE + tpdesc = RMFT2::getTurntablePositionDescription(id, p); +#endif + if (tpdesc == NULL) todesc = F(""); + StringFormatter::send(stream, F(" %d \"%S\""), value, tpdesc); + StringFormatter::send(stream, F(">\n")); } } } - StringFormatter::send(stream, F(">\n")); return; #endif default: break; diff --git a/EXRAILMacros.h b/EXRAILMacros.h index c413989..97604c5 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -54,6 +54,8 @@ // helper macro for turnout descriptions, creates NULL for missing description #define O_DESC(id, desc) case id: return ("" desc)[0]?F("" desc):NULL; +// helper macro for turntable descriptions, creates NULL for missing description +#define T_DESC(tid,pid,desc) if(turntableId==tid && positionId==pid) return ("" desc)[0]?F("" desc):NULL; // helper macro for turnout description as HIDDEN #define HIDDEN "\x01" @@ -203,17 +205,14 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { } // Pass to get turntable position descriptions (optional) -// #include "EXRAIL2MacroReset.h" -// #undef TT_ADDPOSITION -// #define TT_ADDPOSITION(turntable_id,value,description...) O_DESC(turntable_id,description) +#include "EXRAIL2MacroReset.h" +#undef TT_ADDPOSITION +#define TT_ADDPOSITION(turntable_id,position,value,description...) T_DESC(turntable_id,position,description) -// const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { -// switch (turntableId) { -// #include "myAutomation.h" -// default:break; -// } -// return NULL; -// } +const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { + #include "myAutomation.h" + return NULL; +} // Pass 6: Roster IDs (count) #include "EXRAIL2MacroReset.h" From 004d7b66317f34a43006e4319cdbc7bf3a0f066d Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 7 Sep 2023 07:32:54 +1000 Subject: [PATCH 43/83] JO and JP working --- DCCEXParser.cpp | 24 ++++++++++++++++++------ platformio.ini | 2 +- 2 files changed, 19 insertions(+), 7 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 405512c..94b711e 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -86,6 +86,7 @@ const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_I='I'; const int16_t HASH_KEYWORD_O='O'; +const int16_t HASH_KEYWORD_P='P'; const int16_t HASH_KEYWORD_R='R'; const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_X='X'; @@ -706,30 +707,41 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } else { // <JO id> Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { - StringFormatter::send(stream, F(" %d X"), id); + StringFormatter::send(stream, F(" %d X>\n"), id); } else { uint8_t pos = tto->getPosition(); uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; - const FSH *tpdesc = NULL; #ifdef EXRAIL_ACTIVE todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); StringFormatter::send(stream, F(" %d %d %d %d \"%S\">\n"), id, type, pos, posCount, todesc); - + } + } + return; + case HASH_KEYWORD_P: // <JP id> returns turntable position list for the turntable id + if (params==2) { // <JP id> + Turntable *tto=Turntable::get(id); + if (!tto || tto->isHidden()) { + StringFormatter::send(stream, F(" %d X>\n"), id); + } else { + uint8_t posCount = tto->getPositionCount(); + const FSH *tpdesc = NULL; for (uint8_t p = 0; p < posCount; p++) { - StringFormatter::send(stream, F("jO>")); + StringFormatter::send(stream, F("<jP")); int16_t value = tto->getPositionValue(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif - if (tpdesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d \"%S\""), value, tpdesc); + if (tpdesc == NULL) tpdesc = F(""); + StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, value, tpdesc); StringFormatter::send(stream, F(">\n")); } } + } else { + StringFormatter::send(stream, F("<jP X>\n")); } return; #endif diff --git a/platformio.ini b/platformio.ini index 1a87770..ac2d598 100644 --- a/platformio.ini +++ b/platformio.ini @@ -30,7 +30,7 @@ include_dir = . [env] build_flags = -Wall -Wextra -monitor_filters = time +; monitor_filters = time ; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0 [env:samd21-dev-usb] From bd02d1c15bf4cc35848d07b15c5630dcc352ebd8 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 7 Sep 2023 07:58:19 +1000 Subject: [PATCH 44/83] WAITFORTT ready for testing --- EXRAIL2.cpp | 20 ++++++++++++++++++-- EXRAIL2.h | 6 +++++- EXRAIL2MacroReset.h | 6 ++++++ EXRAILMacros.h | 3 +++ Turntables.cpp | 6 ++++++ Turntables.h | 1 + 6 files changed, 39 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index d88a6f4..2d379a7 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -95,7 +95,9 @@ LookList * RMFT2::onAmberLookup=NULL; LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onClockLookup=NULL; +#ifndef IO_NO_HAL LookList * RMFT2::onRotateLookup=NULL; +#endif #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -177,8 +179,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); +#ifndef IO_NO_HAL onRotateLookup=LookListLoader(OPCODE_ONROTATE); - +#endif // Second pass startup, define any turnouts or servos, set signals red // add sequences onRoutines to the lookups @@ -1014,7 +1017,16 @@ void RMFT2::loop2() { return; } break; - + +#ifndef IO_NO_HAL + case OPCODE_WAITFORTT: // OPCODE_WAITFOR,V(turntable_id) + if (Turntable::ttMoving(operand)) { + delayMe(100); + return; + } + break; +#endif + case OPCODE_PRINT: printMessage(operand); break; @@ -1039,10 +1051,12 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: +#ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime case OPCODE_TTADDPOSITION: // Turntable position definition ignored at runtime case OPCODE_ONROTATE: +#endif break; @@ -1187,10 +1201,12 @@ void RMFT2::changeEvent(int16_t vpin, bool change) { if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); } +#ifndef IO_NO_HAL void RMFT2::rotateEvent(int16_t turntableId, bool change) { // Hunt or an ONROTATE for this turntable if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId); } +#endif void RMFT2::clockEvent(int16_t clocktime, bool change) { // Hunt for an ONTIME for this time diff --git a/EXRAIL2.h b/EXRAIL2.h index f6c4807..5247e3e 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -63,8 +63,10 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, +#ifndef IO_NO_HAL OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, - OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION, + OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION,OPCODE_WAITFORTT, +#endif // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -197,7 +199,9 @@ private: static LookList * onGreenLookup; static LookList * onChangeLookup; static LookList * onClockLookup; +#ifndef IO_NO_HAL static LookList * onRotateLookup; +#endif // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 21d4f18..efe91a5 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -150,6 +150,9 @@ #undef VIRTUAL_SIGNAL #undef VIRTUAL_TURNOUT #undef WAITFOR +#ifndef IO_NO_HAL +#undef WAITFORTT +#endif #undef WITHROTTLE #undef XFOFF #undef XFON @@ -281,6 +284,9 @@ #define VIRTUAL_SIGNAL(id) #define VIRTUAL_TURNOUT(id,description...) #define WAITFOR(pin) +#ifndef IO_NO_HAL +#define WAITFORTT(turntable_id) +#endif #define WITHROTTLE(msg) #define XFOFF(cab,func) #define XFON(cab,func) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 97604c5..e3ce129 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -419,6 +419,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0), #define WITHROTTLE(msg) PRINT(msg) #define WAITFOR(pin) OPCODE_WAITFOR,V(pin), +#ifndef IO_NO_HAL +#define WAITFORTT(turntable_id) OPCODE_WAITFORTT,V(turntable_id), +#endif #define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func), #define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func), diff --git a/Turntables.cpp b/Turntables.cpp index abbac81..d43a515 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -115,6 +115,12 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } +bool Turntable::ttMoving(uint16_t id) { + Turntable *tto = get(id); + if (!tto) return false; + return tto->isMoving(); +} + // Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) diff --git a/Turntables.h b/Turntables.h index 15333c9..e7b7415 100644 --- a/Turntables.h +++ b/Turntables.h @@ -179,6 +179,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static uint8_t getPosition(uint16_t id); + static bool ttMoving(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From be10be5a1a9e55ef6bbb35cfac156966f5612a45 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sat, 9 Sep 2023 07:22:10 +1000 Subject: [PATCH 45/83] Added angles --- DCCEXParser.cpp | 57 +++++++++++++++++++++++++++------------------ EXRAIL2.cpp | 9 ++++--- EXRAIL2MacroReset.h | 6 +++-- EXRAILMacros.h | 11 +++++---- Turntables.cpp | 17 ++++++++++++-- Turntables.h | 13 +++++------ 6 files changed, 71 insertions(+), 42 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 94b711e..40ea635 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -732,11 +732,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) for (uint8_t p = 0; p < posCount; p++) { StringFormatter::send(stream, F("<jP")); int16_t value = tto->getPositionValue(p); + int16_t angle = tto->getPositionAngle(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif if (tpdesc == NULL) tpdesc = F(""); - StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, value, tpdesc); + StringFormatter::send(stream, F(" %d %d %d %d \"%S\""), id, p, value, angle, tpdesc); StringFormatter::send(stream, F(">\n")); } } @@ -1107,44 +1108,54 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 2: // <I id DCC> | <I id position> - rotate or create DCC turntable + case 2: // <I id position> - rotate a DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable - if (tto) return false; - if (!DCCTurntable::create(p[0])) return false; - Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0, 0); - } else { // Otherwise move a DCC turntable - if (tto && !tto->isEXTT()) { - if (!tto->setPosition(p[0], p[1])) return false; - } else { - return false; - } + if (tto && !tto->isEXTT()) { + if (!tto->setPosition(p[0], p[1])) return false; + } else { + return false; } } return true; - case 3: // <I id position activity> rotate to position for EX-Turntable + case 3: // <I id position activity> | <I id DCC home> - rotate to position for EX-Turntable or create DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (!tto) return false; - if (!tto->isEXTT()) return false; - if (!tto->setPosition(p[0], p[1], p[2])) return false; + if (p[1] == HASH_KEYWORD_DCC) { + if (tto || p[2] < 0 || p[2] > 3600) return false; + if (!DCCTurntable::create(p[0])) return false; + Turntable *tto = Turntable::get(p[0]); + tto->addPosition(0, 0, p[2]); + } else { + if (!tto) return false; + if (!tto->isEXTT()) return false; + if (!tto->setPosition(p[0], p[1], p[2])) return false; + } } return true; - case 4: // <I id EXTT vpin home> | <I id ADD position value> create an EXTT turntable or add position + case 4: // <I id EXTT vpin home> create an EXTT turntable { Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_EXTT) { - if (tto) return false; + if (tto || p[3] < 0 || p[3] > 3600) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0, p[3]); - } else if (p[1] == HASH_KEYWORD_ADD) { - if (!tto) return false; - tto->addPosition(p[2], p[3]); + tto->addPosition(0, 0, p[3]); + } else { + return false; + } + } + return true; + + case 5: // <I id ADD position value angle> add a position + { + Turntable *tto = Turntable::get(p[0]); + if (p[1] == HASH_KEYWORD_ADD) { + // tto must exist, no more than 48 positions, angle 0 - 3600 + if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; + tto->addPosition(p[2], p[3], p[4]); StringFormatter::send(stream, F("<i>\n")); } else { return false; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 2d379a7..32d2795 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -53,6 +53,7 @@ #include "CommandDistributor.h" #include "TrackManager.h" #include "Turntables.h" +#include "IODevice.h" // Command parsing keywords const int16_t HASH_KEYWORD_EXRAIL=15435; @@ -248,9 +249,10 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { #ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: { VPIN id=operand; + int home=getOperand(progCounter,1); setTurntableHiddenState(DCCTurntable::create(id)); Turntable *tto=Turntable::get(id); - tto->addPosition(0,0); + tto->addPosition(0,0,home); break; } @@ -260,7 +262,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { int home=getOperand(progCounter,2); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); - tto->addPosition(0,home); + tto->addPosition(0,0,home); break; } @@ -268,8 +270,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { VPIN id=operand; int position=getOperand(progCounter,1); int value=getOperand(progCounter,2); + int angle=getOperand(progCounter,3); Turntable *tto=Turntable::get(id); - tto->addPosition(position,value); + tto->addPosition(position,value,angle); break; } #endif diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index efe91a5..b54a9d9 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -119,6 +119,7 @@ #undef REV #undef ROSTER #undef ROTATE +#undef ROTATE_DCC #undef ROUTE #undef SENDLOCO #undef SEQUENCE @@ -174,7 +175,7 @@ #define CALL(route) #define CLOSE(id) #define DCC_SIGNAL(id,add,subaddr) -#define DCC_TURNTABLE(id,description) +#define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) #define DELAY(mindelay) @@ -252,6 +253,7 @@ #define RETURN #define REV(speed) #define ROTATE(turntable_id,position,activity) +#define ROTATE_DCC(turntable_id,position) #define ROSTER(cab,name,funcmap...) #define ROUTE(id,description) #define SENDLOCO(cab,route) @@ -276,7 +278,7 @@ #define START(route) #define STOP #define THROW(id) -#define TT_ADDPOSITION(turntable_id,position,value,description) +#define TT_ADDPOSITION(turntable_id,position,value,angle,description...) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index e3ce129..440a619 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -192,7 +192,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { // Pass to get turntable descriptions (optional) #include "EXRAIL2MacroReset.h" #undef DCC_TURNTABLE -#define DCC_TURNTABLE(id,description...) O_DESC(id,description) +#define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE #define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) @@ -207,7 +207,7 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { // Pass to get turntable position descriptions (optional) #include "EXRAIL2MacroReset.h" #undef TT_ADDPOSITION -#define TT_ADDPOSITION(turntable_id,position,value,description...) T_DESC(turntable_id,position,description) +#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description) const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { #include "myAutomation.h" @@ -296,7 +296,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), #ifndef IO_NO_HAL -#define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), +#define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), #endif #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), @@ -383,7 +383,8 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) #ifndef IO_NO_HAL -#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), +#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(EXTurntable::activity), +#define ROTATE_DCC(id,position) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(0), #endif #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), @@ -409,7 +410,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL -#define TT_ADDPOSITION(id,position,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value), +#define TT_ADDPOSITION(id,position,value,angle,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value),OPCODE_PAD,V(angle), #endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) diff --git a/Turntables.cpp b/Turntables.cpp index d43a515..ba143cb 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -58,8 +58,8 @@ void Turntable::add(Turntable *tto) { } // Add a position -void Turntable::addPosition(uint8_t idx, uint16_t value) { - _turntablePositions.insert(idx, value); +void Turntable::addPosition(uint8_t idx, uint16_t value, uint16_t angle) { + _turntablePositions.insert(idx, value, angle); } // Get value for position @@ -74,6 +74,18 @@ uint16_t Turntable::getPositionValue(uint8_t position) { return false; } +// Get value for position +uint16_t Turntable::getPositionAngle(uint8_t position) { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + while (currentPosition) { + if (currentPosition->index == position) { + return currentPosition->angle; + } + currentPosition = currentPosition->next; + } + return false; +} + // Get the count of positions associated with the turntable uint8_t Turntable::getPositionCount() { TurntablePosition* currentPosition = _turntablePositions.getHead(); @@ -115,6 +127,7 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } +// Got the moving state of the specified turntable bool Turntable::ttMoving(uint16_t id) { Turntable *tto = get(id); if (!tto) return false; diff --git a/Turntables.h b/Turntables.h index e7b7415..6c15bab 100644 --- a/Turntables.h +++ b/Turntables.h @@ -36,9 +36,6 @@ enum { TURNTABLE_DCC = 1, }; -// Callback needs to return a bool: 1 = moving, 0 = stopped -typedef void (*EXTT_CALLBACK)(bool moving); - /************************************************************************************* * Turntable positions. * @@ -46,17 +43,18 @@ typedef void (*EXTT_CALLBACK)(bool moving); struct TurntablePosition { uint8_t index; uint16_t data; + uint16_t angle; TurntablePosition* next; - TurntablePosition(uint8_t idx, uint16_t value) : index(idx), data(value), next(nullptr) {} + TurntablePosition(uint8_t idx, uint16_t value, uint16_t angle) : index(idx), data(value), angle(angle), next(nullptr) {} }; class TurntablePositionList { public: TurntablePositionList() : head(nullptr) {} - void insert(uint8_t idx, uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(idx, value); + void insert(uint8_t idx, uint16_t value, uint16_t angle) { + TurntablePosition* newPosition = new TurntablePosition(idx, value, angle); if(!head) { head = newPosition; } else { @@ -158,8 +156,9 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - void addPosition(uint8_t idx, uint16_t value); + void addPosition(uint8_t idx, uint16_t value, uint16_t angle); uint16_t getPositionValue(uint8_t position); + uint16_t getPositionAngle(uint8_t position); uint8_t getPositionCount(); bool isMoving() { return _isMoving; } void setMoving(bool moving) { _isMoving=moving; } From dba5d35aa231ebbe732a755462f8b95043554c64 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sat, 9 Sep 2023 09:23:10 +1000 Subject: [PATCH 46/83] Add response to create --- DCCEXParser.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 40ea635..05e0eca 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1127,6 +1127,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[2]); + StringFormatter::send(stream, F("<i>\n")); } else { if (!tto) return false; if (!tto->isEXTT()) return false; @@ -1143,6 +1144,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[3]); + StringFormatter::send(stream, F("<i>\n")); } else { return false; } From 7ee2c29a526078d2f5a395adc0cd671f1d1df0a9 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 10 Sep 2023 05:30:48 +1000 Subject: [PATCH 47/83] Include HAL create with EXTT_TURNTABLE --- EXRAIL2.cpp | 2 +- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 9 ++++++--- 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 32d2795..c8ff8f3 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -259,7 +259,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { case OPCODE_EXTTTURNTABLE: { VPIN id=operand; VPIN pin=getOperand(progCounter,1); - int home=getOperand(progCounter,2); + int home=getOperand(progCounter,3); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); tto->addPosition(0,0,home); diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index b54a9d9..c8ff395 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -189,7 +189,7 @@ #define ENDTASK #define ESTOP #define EXRAIL -#define EXTT_TURNTABLE(id,vpin,home,description) +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 440a619..39e5dda 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -69,10 +69,13 @@ #define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; #include "myAutomation.h" -// Pass 1h Implements HAL macro by creating exrailHalSetup function +// Pass 1h Implements HAL macro by creating exrailHalSetup function +// Also allows creating EXTurntable object #include "EXRAIL2MacroReset.h" #undef HAL #define HAL(haltype,params...) haltype::create(params); +#undef EXTT_TURNTABLE +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) EXTurntable::create(vpin,1,i2c_address); void exrailHalSetup() { #include "myAutomation.h" } @@ -194,7 +197,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { #undef DCC_TURNTABLE #define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE -#define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) O_DESC(id,description) const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { switch (turntableId) { @@ -313,7 +316,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL #ifndef IO_NO_HAL -#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(i2c_address),OPCODE_PAD,V(home), #endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), From a0562fdf5c0e1af6ffb0a95091535d827d3e0343 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 10 Sep 2023 07:06:27 +1000 Subject: [PATCH 48/83] Update defines to match changes in devel --- defines.h | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/defines.h b/defines.h index 3286aca..49aff71 100644 --- a/defines.h +++ b/defines.h @@ -218,8 +218,12 @@ // Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required // The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. // -#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) -#define IO_NO_HAL +#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) + #if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG) + #warning you have sacrificed DIAG for HAL + #else + #define IO_NO_HAL + #endif #endif #if __has_include ( "myAutomation.h") From 4fcd81a118a1ee8b89410bd5a30f2b0d73b4c61c Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 10 Sep 2023 07:18:54 +1000 Subject: [PATCH 49/83] Update version --- version.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index abcc577..e8ee138 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,10 @@ #include "StringFormatter.h" -#define VERSION "5.1.4" +#define VERSION "5.1.5" +// 5.1.5 - Added turntable object and EXRAIL commands +// - <I ...>, <JO ...>, <JP ...> - turntable commands +// - DCC_TURNTABLE, EXTT_TURNTABLE, IFTTPOSITION, ONROTATE, ROTATE, ROTATE_DCC, TT_ADDPOSITION, WAITFORTT EXRAIL // 5.1.4 - Added ONOVERLOAD & AFTEROVERLOAD to EXRAIL // 5.1.3 - Make parser more fool proof // 5.1.2 - Bugfix: ESP32 30ms off time From da6a3c442f66d8802112b3b676ec47228f0a94b1 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Sun, 10 Sep 2023 18:41:14 +1000 Subject: [PATCH 50/83] Remove redundant line --- EXRAIL2.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index fae6add..d6d2597 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -650,7 +650,6 @@ void RMFT2::loop2() { case OPCODE_ROTATE: uint8_t activity; activity=getOperand(2); - if (!activity) activity=0; Turntable::setPosition(operand,getOperand(1),activity); break; #endif From ebbeea5fbb8198ed7d3e7679b4dea6bd212a002b Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Wed, 13 Sep 2023 16:46:36 +0800 Subject: [PATCH 51/83] STM32F4xx native I2C driver merge --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index e8ee138..c8f6a68 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.5" +#define VERSION "5.1.6" +// 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - <I ...>, <JO ...>, <JP ...> - turntable commands // - DCC_TURNTABLE, EXTT_TURNTABLE, IFTTPOSITION, ONROTATE, ROTATE, ROTATE_DCC, TT_ADDPOSITION, WAITFORTT EXRAIL From 46289fa78cc1db6dd02b52da36a405aa662ef2a9 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Fri, 11 Aug 2023 00:07:02 +0200 Subject: [PATCH 52/83] Check bad AT firmware version --- WifiInterface.cpp | 16 +++++++++++++++- version.h | 3 ++- 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 7511af6..ab36957 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -200,7 +200,21 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, // Display the AT version information StringFormatter::send(wifiStream, F("AT+GMR\r\n")); - checkForOK(2000, true, false); // Makes this visible on the console + if (checkForOK(2000, F("AT version:"), true, false)) { + char version[] = "0.0.0.0"; + for (int i=0; i<8;i++) { + while(!wifiStream->available()); + version[i]=wifiStream->read(); + StringFormatter::printEscape(version[i]); + if ((version[0] == '0') || + (version[0] == '2' && version[2] == '0') || + (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) { + SSid = F("DCCEX_SAYS_BROKEN_FIRMWARE"); + forceAP = true; + } + } + } + checkForOK(2000, true, false); #ifdef DONT_TOUCH_WIFI_CONF DIAG(F("DONT_TOUCH_WIFI_CONF was set: Using existing config")); diff --git a/version.h b/version.h index d52902a..a76aef2 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.0.2" +#define VERSION "5.0.3" +// 5.0.3 - Check bad AT firmware version // 5.0.2 - Bugfix: ESP32 30ms off time // 5.0.1 - Bugfix: execute 30ms off time before rejoin // 5.0.0 - Make 4.2.69 the 5.0.0 release From 8437b0e7aa994d78153a1cbf367559c830b0a314 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Fri, 15 Sep 2023 06:26:29 +1000 Subject: [PATCH 53/83] Updated broadcasts --- DCCEXParser.cpp | 3 +-- IODevice.h | 3 ++- IO_EXTurntable.cpp | 17 +++++++++++------ version.h | 3 ++- 4 files changed, 16 insertions(+), 10 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 08aae01..29c252d 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -812,13 +812,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) const FSH *tpdesc = NULL; for (uint8_t p = 0; p < posCount; p++) { StringFormatter::send(stream, F("<jP")); - int16_t value = tto->getPositionValue(p); int16_t angle = tto->getPositionAngle(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif if (tpdesc == NULL) tpdesc = F(""); - StringFormatter::send(stream, F(" %d %d %d %d \"%S\""), id, p, value, angle, tpdesc); + StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, angle, tpdesc); StringFormatter::send(stream, F(">\n")); } } diff --git a/IODevice.h b/IODevice.h index 4803f56..74fe49b 100644 --- a/IODevice.h +++ b/IODevice.h @@ -409,11 +409,12 @@ private: void _begin() override; void _loop(unsigned long currentMicros) override; int _read(VPIN vpin) override; - void _broadcastStatus (VPIN vpin, uint8_t status); + void _broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity); void _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override; void _display() override; uint8_t _stepperStatus; uint8_t _previousStatus; + uint8_t _currentActivity; }; #endif diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index af220a3..aeb935b 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -72,7 +72,9 @@ void EXTurntable::_loop(unsigned long currentMicros) { I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; if (_stepperStatus != _previousStatus && _stepperStatus == 0) { // Broadcast when a rotation finishes - _broadcastStatus(_firstVpin, _stepperStatus); + if ( _currentActivity < 4) { + _broadcastStatus(_firstVpin, _stepperStatus, _currentActivity); + } _previousStatus = _stepperStatus; } delayUntil(currentMicros + 100000); // Wait 100ms before checking again @@ -90,11 +92,13 @@ int EXTurntable::_read(VPIN vpin) { } // If a status change has occurred for a turntable object, broadcast it -void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { +void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { - tto->setMoving(status); - CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + if (activity < 4) { + tto->setMoving(status); + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + } } } @@ -124,9 +128,10 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"), _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif - _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy _previousStatus = _stepperStatus; - _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts + _currentActivity = activity; + _broadcastStatus(vpin, _stepperStatus, activity); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } diff --git a/version.h b/version.h index c8f6a68..35d3f1a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.6" +#define VERSION "5.1.7" +// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - <I ...>, <JO ...>, <JP ...> - turntable commands From 550ad58c4d2fec42657c5e17374ebf03d160635a Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Thu, 21 Sep 2023 14:39:25 +0800 Subject: [PATCH 54/83] STM32 ADCee extended to support ADC2 and ADC3 --- DCCTimer.h | 5 ++ DCCTimerSTM32.cpp | 181 ++++++++++++++++++++++++++++++++++++---------- 2 files changed, 147 insertions(+), 39 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 7402f16..3b14fd6 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -125,8 +125,13 @@ private: // On platforms that scan, it is called from waveform ISR // only on a regular basis. static void scan(); + #if defined (ARDUINO_ARCH_STM32) + // bit array of used pins (max 32) + static uint32_t usedpins; +#else // bit array of used pins (max 16) static uint16_t usedpins; +#endif static uint8_t highestPin; // cached analog values (malloc:ed to actual number of ADC channels) static int *analogvals; diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index cffae40..f57499a 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -52,7 +52,7 @@ HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE // On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins -#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)|| defined(ARDUINO_NUCLEO_F412ZG) +#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) // Nucleo-144 boards don't have Serial1 defined by default HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 // Serial3 is defined to use USART3 by default, but is in fact used as the diag console @@ -235,22 +235,19 @@ void DCCTimer::reset() { while(true) {}; } -// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs! -#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) -#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing! -#endif -// For now, define the max of 16 ports - some variants have more, but this not **yet** supported -#define NUM_ADC_INPUTS 16 -// #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS +// Now we can handle more ADCs, maybe this works! +#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS -uint16_t ADCee::usedpins = 0; -uint8_t ADCee::highestPin = 0; -int * ADCee::analogvals = NULL; -uint32_t * analogchans = NULL; -bool adc1configured = false; +uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels! +uint8_t ADCee::highestPin = 0; // Highest pin to scan +int * ADCee::analogvals = NULL; // Array of analog values last captured +uint32_t * analogchans = NULL; // Array of channel numbers to be scanned +// bool adc1configured = false; +ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on -int16_t ADCee::ADCmax() { - return 4095; +int16_t ADCee::ADCmax() +{ + return 4095; } int ADCee::init(uint8_t pin) { @@ -261,11 +258,33 @@ int ADCee::init(uint8_t pin) { return -1024; // some silly value as error uint32_t stmgpio = STM_PORT(stmpin); // converts to the GPIO port (16-bits per port group on STM32) - uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC channel (only valid for ADC1!) - GPIO_TypeDef * gpioBase; + uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel + ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc. + int adcnum = 1; + if (adc == ADC1) + DIAG(F("ADCee::init(): found pin %d on ADC1"), pin); +// Checking for ADC2 and ADC3 being defined helps cater for more variants later +#if defined(ADC2) + else if (adc == ADC2) + { + DIAG(F("ADCee::init(): found pin %d on ADC2"), pin); + adcnum = 2; + } +#endif +#if defined(ADC3) + else if (adc == ADC3) + { + DIAG(F("ADCee::init(): found pin %d on ADC3"), pin); + adcnum = 3; + } +#endif + else DIAG(F("ADCee::init(): found pin %d on unknown ADC!"), pin); - // Port config - find which port we're on and power it up - switch(stmgpio) { + // Port config - find which port we're on and power it up + GPIO_TypeDef *gpioBase; + + switch (stmgpio) + { case 0x00: RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA gpioBase = GPIOA; @@ -278,6 +297,20 @@ int ADCee::init(uint8_t pin) { RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC gpioBase = GPIOC; break; + case 0x03: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; //Power up PORTD + gpioBase = GPIOD; + break; + case 0x04: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOEEN; //Power up PORTE + gpioBase = GPIOE; + break; +#if defined(GPIOF) + case 0x05: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF + gpioBase = GPIOF; + break; +#endif default: return -1023; // some silly value as error } @@ -293,31 +326,33 @@ int ADCee::init(uint8_t pin) { if (adcchan > 18) return -1022; // silly value as error if (adcchan < 10) - ADC1->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles + adc->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles else - ADC1->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles + adc->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles // Read the inital ADC value for this analog input - ADC1->SQR3 = adcchan; // 1st conversion in regular sequence - ADC1->CR2 |= (1 << 30); // Start 1st conversion SWSTART - while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete - value = ADC1->DR; // Read value from register + adc->SQR3 = adcchan; // 1st conversion in regular sequence + adc->CR2 |= ADC_CR2_SWSTART; //(1 << 30); // Start 1st conversion SWSTART + while(!(adc->SR & (1 << 1))); // Wait until conversion is complete + value = adc->DR; // Read value from register uint8_t id = pin - PNUM_ANALOG_BASE; - if (id > 15) { // today we have not enough bits in the mask to support more - return -1021; - } + // if (id > 15) { // today we have not enough bits in the mask to support more + // return -1021; + // } - if (analogvals == NULL) { // allocate analogvals and analogchans if this is the first invocation of init. + if (analogvals == NULL) { // allocate analogvals, analogchans and adcchans if this is the first invocation of init analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int)); analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t)); + adcchans = (ADC_TypeDef **)calloc(NUM_ADC_INPUTS+1, sizeof(ADC_TypeDef)); } analogvals[id] = value; // Store sampled value analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin - usedpins |= (1 << id); // This pin is now ready + adcchans[id] = adc; // Keep track of which ADC this channel is on + usedpins |= (1 << id); // This pin is now ready if (id > highestPin) highestPin = id; // Store our highest pin in use - DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id); + DIAG(F("ADCee::init(): value=%d, ADC%d: channel=%d, id=%d"), value, adcnum, adcchan, id); return value; } @@ -344,13 +379,16 @@ void ADCee::scan() { static uint8_t id = 0; // id and mask are the same thing but it is faster to static uint16_t mask = 1; // increment and shift instead to calculate mask from id static bool waiting = false; + static ADC_TypeDef *adc; - if (waiting) { + adc = adcchans[id]; + if (waiting) + { // look if we have a result - if (!(ADC1->SR & (1 << 1))) + if (!(adc->SR & (1 << 1))) return; // no result, continue to wait // found value - analogvals[id] = ADC1->DR; + analogvals[id] = adc->DR; // advance at least one track #ifdef DEBUG_ADC if (id == 1) TrackManager::track[1]->setBrake(0); @@ -369,9 +407,10 @@ void ADCee::scan() { // look for a valid track to sample or until we are around while (true) { if (mask & usedpins) { - // start new ADC aquire on id - ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence - ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART + // start new ADC aquire on id + adc = adcchans[id]; + adc->SQR3 = analogchans[id]; // 1st conversion in regular sequence + adc->CR2 |= (1 << 30); // Start 1st conversion SWSTART #ifdef DEBUG_ADC if (id == 1) TrackManager::track[1]->setBrake(1); #endif @@ -392,19 +431,83 @@ void ADCee::scan() { void ADCee::begin() { noInterrupts(); //ADC1 config sequence - // TODO: currently defaults to ADC1, may need more to handle other members of STM32F4xx family - RCC->APB2ENR |= (1 << 8); //Enable ADC1 clock (Bit8) + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable ADC1 clock // Set ADC prescaler - DIV8 ~ 40ms, DIV6 ~ 30ms, DIV4 ~ 20ms, DIV2 ~ 11ms ADC->CCR = (0 << 16); // Set prescaler 0=DIV2, 1=DIV4, 2=DIV6, 3=DIV8 ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) ADC1->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + // Disable the DMA controller for ADC1 + ADC1->CR2 &= ~ADC_CR2_DMA; ADC1->CR2 &= ~(1 << 1); //Single conversion ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->CR2 |= (1 << 0); // Switch on ADC1 + // Wait for ADC1 to become ready (calibration complete) + while (!(ADC1->CR2 & ADC_CR2_ADON)) { + } +#if defined(ADC2) + // Enable the ADC2 clock + RCC->APB2ENR |= RCC_APB2ENR_ADC2EN; + + // Initialize ADC2 + ADC2->CR1 = 0; // Disable all channels + ADC2->CR2 = 0; // Clear CR2 register + + ADC2->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) + ADC2->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) + ADC2->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + ADC2->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3 + ADC2->CR2 &= ~(1 << 1); //Single conversion + ADC2->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 + ADC2->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC2->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC2->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + + // Enable the ADC + ADC2->CR2 |= ADC_CR2_ADON; + + // Wait for ADC2 to become ready (calibration complete) + while (!(ADC2->CR2 & ADC_CR2_ADON)) { + } + + // Perform ADC3 calibration (optional) + // ADC3->CR2 |= ADC_CR2_CAL; + // while (ADC3->CR2 & ADC_CR2_CAL) { + // } +#endif +#if defined(ADC3) + // Enable the ADC3 clock + RCC->APB2ENR |= RCC_APB2ENR_ADC3EN; + + // Initialize ADC3 + ADC3->CR1 = 0; // Disable all channels + ADC3->CR2 = 0; // Clear CR2 register + + ADC3->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) + ADC3->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) + ADC3->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + ADC3->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3 + ADC3->CR2 &= ~(1 << 1); //Single conversion + ADC3->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 + ADC3->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC3->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC3->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + + // Enable the ADC + ADC3->CR2 |= ADC_CR2_ADON; + + // Wait for ADC3 to become ready (calibration complete) + while (!(ADC3->CR2 & ADC_CR2_ADON)) { + } + + // Perform ADC3 calibration (optional) + // ADC3->CR2 |= ADC_CR2_CAL; + // while (ADC3->CR2 & ADC_CR2_CAL) { + // } +#endif interrupts(); } #endif From 5d810a620b759cc8dfa7fff275b68d78c9767a0a Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Thu, 21 Sep 2023 16:05:35 +0800 Subject: [PATCH 55/83] STM32 variant support extension and tidy --- I2CManager_STM32.h | 6 ++-- platformio.ini | 79 +++++++++++++++++++++++++++++++++++++++++----- 2 files changed, 75 insertions(+), 10 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index cde4f20..86b9b74 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -37,9 +37,11 @@ * I2C bus, or more than one I2C bus on the STM32 architecture *****************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) -#if defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) +#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) \ + || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) \ + || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) // Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64 -// and Nucleo-144variants +// and Nucleo-144 variants I2C_TypeDef *s = I2C1; // In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz diff --git a/platformio.ini b/platformio.ini index ac2d598..8767ef1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -31,7 +31,6 @@ include_dir = . [env] build_flags = -Wall -Wextra ; monitor_filters = time -; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0 [env:samd21-dev-usb] platform = atmelsam @@ -60,7 +59,7 @@ framework = arduino lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes -build_flags = -std=c++17 ; -DI2C_USE_WIRE -DDIAG_LOOPTIMES -DDIAG_IO +build_flags = -std=c++17 [env:mega2560-debug] platform = atmelavr @@ -72,7 +71,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES +build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES [env:mega2560-no-HAL] platform = atmelavr @@ -84,7 +83,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = -DIO_NO_HAL +build_flags = -DIO_NO_HAL [env:mega2560-I2C-wire] platform = atmelavr @@ -108,7 +107,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = ; -DDIAG_LOOPTIMES +build_flags = [env:mega328] platform = atmelavr @@ -190,10 +189,75 @@ platform = ststm32 board = nucleo_f446re framework = arduino lib_deps = ${env.lib_deps} -build_flags = -std=c++17 -Os -g2 -Wunused-variable ; -DDIAG_LOOPTIMES ; -DDIAG_IO +build_flags = -std=c++17 -Os -g2 -Wunused-variable monitor_speed = 115200 monitor_echo = yes +; Experimental - no reason this should not work, but not +; tested as yet +; +[env:Nucleo-F401RE] +platform = ststm32 +board = nucleo_f401re +framework = arduino +lib_deps = ${env.lib_deps} +build_flags = -std=c++17 -Os -g2 -Wunused-variable +monitor_speed = 115200 +monitor_echo = yes + +; Commented out by default as the F13ZH has variant files +; but NOT the nucleo_f413zh.json file which needs to be +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F413ZH] +; platform = ststm32 +; board = nucleo_f413zh +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes + +; Commented out by default as the F446ZE needs variant files +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F446ZE] +; platform = ststm32 +; board = nucleo_f446ze +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes + +; Commented out by default as the F412ZG needs variant files +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F412ZG] +; platform = ststm32 +; board = blah_f412zg +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes +; upload_protocol = stlink + +; Experimental - Ethernet work still in progress +; +; [env:Nucleo-F429ZI] +; platform = ststm32 +; board = nucleo_f429zi +; framework = arduino +; lib_deps = ${env.lib_deps} +; arduino-libraries/Ethernet @ ^2.0.1 +; stm32duino/STM32Ethernet @ ^1.3.0 +; stm32duino/STM32duino LwIP @ ^2.1.2 +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes +; upload_protocol = stlink + [env:Teensy3_2] platform = teensy board = teensy31 @@ -232,5 +296,4 @@ board = teensy41 framework = arduino build_flags = -std=c++17 -Os -g2 lib_deps = ${env.lib_deps} -lib_ignore = - +lib_ignore = From dfe3e9d42c590c6a821406f049df34f3094d51a1 Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Thu, 21 Sep 2023 16:09:04 +0800 Subject: [PATCH 56/83] STM32 ADCee extensions --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 35d3f1a..f10ceee 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.7" +#define VERSION "5.1.8" +// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands From 8052090e0f1c47d7c87220cf1b925354539d1125 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Fri, 22 Sep 2023 17:03:40 +0100 Subject: [PATCH 57/83] Added Single Track Power On/Off Added power On/Off <> commands --- CommandDistributor.cpp | 4 +- CommandDistributor.h | 2 +- DCCEXParser.cpp | 51 ++++++++++++++++--- TrackManager.cpp | 111 +++++++++++++++++++++++++---------------- TrackManager.h | 9 ++-- 5 files changed, 121 insertions(+), 56 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index ee760b0..32f9874 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,6 +269,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter,dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format,trackLetter,pmode, dcAddr); } diff --git a/CommandDistributor.h b/CommandDistributor.h index a51d58a..99b9f1e 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr); template<typename... Targs> static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 29c252d..150070c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -555,6 +555,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool main=false; bool prog=false; bool join=false; + bool singletrack=false; if (params > 1) break; if (params==0) { // All main=true; @@ -574,12 +575,28 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + uint8_t t = (p[0] - 'A'); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); + if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); + } else break; // will reply <X> } TrackManager::setJoin(join); - if (main) TrackManager::setMainPower(POWERMODE::ON); - if (prog) TrackManager::setProgPower(POWERMODE::ON); - + if (!singletrack) { + if (main) TrackManager::setMainPower(POWERMODE::ON); + if (prog) TrackManager::setProgPower(POWERMODE::ON); + } CommandDistributor::broadcastPower(); return; } @@ -588,6 +605,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) { bool main=false; bool prog=false; + bool singletrack=false; if (params > 1) break; if (params==0) { // All main=true; @@ -601,17 +619,34 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> prog=true; } -#endif +#endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + uint8_t t = (p[0] - 'A'); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::SetMainTrackPower(POWERMODE::OFF, t); + if (prog) TrackManager::SetProgTrackPower(POWERMODE::OFF, t); + } + else break; // will reply <X> } TrackManager::setJoin(false); + if (!singletrack) { if (main) TrackManager::setMainPower(POWERMODE::OFF); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setProgPower(POWERMODE::OFF); + if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setProgPower(POWERMODE::OFF); + } } - CommandDistributor::broadcastPower(); return; } diff --git a/TrackManager.cpp b/TrackManager.cpp index bd7c623..413fd95 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -353,32 +353,48 @@ void TrackManager::streamTrackState(Print* stream, byte t) { // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; auto format=F(""); + bool pstate = TrackManager::isPowerOn(t); + //char PMODE[] = "OFF"; + //if (pstate) PMODE="ON "; + //if (TrackManager::isPowerOn(t)) {char PMODE[] = "ON";} + // else {char PMODE[] = "OFF";} + switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - format=F("<= %c MAIN>\n"); + format=F("<= %c MAIN %c>\n"); break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: - format=F("<= %c PROG>\n"); + format=F("<= %c PROG %c>\n"); break; #endif case TRACK_MODE_NONE: - format=F("<= %c NONE>\n"); + format=F("<= %c NONE %c>\n"); break; case TRACK_MODE_EXT: - format=F("<= %c EXT>\n"); + format=F("<= %c EXT %c>\n"); break; case TRACK_MODE_DC: - format=F("<= %c DC %d>\n"); + format=F("<= %c DC %c %d>\n"); break; case TRACK_MODE_DCX: - format=F("<= %c DCX %d>\n"); + format=F("<= %c DCX %c %d>\n"); break; default: break; // unknown, dont care } - if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]); + switch (pstate) { + case true: + if (stream) StringFormatter::send(stream,format,'A'+t,"ON", trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t,"ON", trackDCAddr[t]); + break; + case false: + if (stream) StringFormatter::send(stream,format,'A'+t,"OFF", trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t,"OFF", trackDCAddr[t]); + break; + } + //if (stream) StringFormatter::send(stream,format,'A'+t,PMODE, trackDCAddr[t]); + //else CommandDistributor::broadcastTrackState(format,'A'+t,PMODE, trackDCAddr[t]); } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -412,45 +428,51 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode) { +void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t thistrack) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - MotorDriver * driver=track[t]; - if (!driver) continue; - switch (track[t]->getMode()) { - case TRACK_MODE_MAIN: - if (setProg) break; - // toggle brake before turning power on - resets overcurrent error - // on the Pololu board if brake is wired to ^D2. - // XXX see if we can make this conditional - driver->setBrake(true); - driver->setBrake(false); // DCC runs with brake off - driver->setPower(mode); - break; - case TRACK_MODE_DC: - case TRACK_MODE_DCX: - if (setProg) break; - driver->setBrake(true); // DC starts with brake on - applyDCSpeed(t); // speed match DCC throttles - driver->setPower(mode); - break; - case TRACK_MODE_PROG: - if (!setProg) break; - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); - break; - case TRACK_MODE_EXT: - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); - break; - case TRACK_MODE_NONE: - break; + if (doall==false && thistrack != t) break; + MotorDriver * driver=track[t]; + if (!driver) continue; + switch (track[t]->getMode()) { + case TRACK_MODE_MAIN: + if (setProg) break; + // toggle brake before turning power on - resets overcurrent error + // on the Pololu board if brake is wired to ^D2. + // XXX see if we can make this conditional + driver->setBrake(true); + driver->setBrake(false); // DCC runs with brake off + driver->setPower(mode); + break; + case TRACK_MODE_DC: + case TRACK_MODE_DCX: + if (setProg) break; + driver->setBrake(true); // DC starts with brake on + applyDCSpeed(t); // speed match DCC throttles + driver->setPower(mode); + break; + case TRACK_MODE_PROG: + if (!setProg) break; + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); + break; + case TRACK_MODE_EXT: + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); + break; + case TRACK_MODE_NONE: + break; } + } } - + +// void TrackManager::setTrackPower(bool progTrack,POWERMODE mode, uint8_t track) { +// // write the code for this. +// } + POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) if (track[t]->getMode()==TRACK_MODE_PROG) @@ -526,3 +548,8 @@ bool TrackManager::isPowerOn(byte t) { return true; } +bool TrackManager::isProg(byte t) { + if (track[t]->getMode()==TRACK_MODE_PROG) + return true; + return false; +} \ No newline at end of file diff --git a/TrackManager.h b/TrackManager.h index 60d5f24..3f9c73f 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -60,10 +60,12 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vector<MotorDriver *>getMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode); + static void setPower2(bool progTrack,POWERMODE mode, bool doall, uint8_t thistrack); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode);} + static void setMainPower(POWERMODE mode) {setPower2(false,mode,true,0);} + static void setProgPower(POWERMODE mode) {setPower2(true,mode,true,0);} + static void SetMainTrackPower(POWERMODE mode, uint8_t track) {setPower2(false,mode,false,track);} + static void SetProgTrackPower(POWERMODE mode, uint8_t track) {setPower2(true,mode,false,track);} static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); @@ -80,6 +82,7 @@ class TrackManager { static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); + static bool isProg(byte t); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From c9d4f5e94dc31fcdc0e55d53eeae3a89008ec783 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 15:56:09 +0100 Subject: [PATCH 58/83] Update IO_PCA9555.h --- IO_PCA9555.h | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index e493165..75f2c38 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -33,17 +33,16 @@ public: static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) { if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } - + +private: // Constructor - PCA9555(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1) + PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) : GPIOBase<uint16_t>((FSH *)F("PCA9555"), vpin, nPins, I2CAddress, interruptPin) { requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer), outputBuffer, sizeof(outputBuffer)); outputBuffer[0] = REG_INPUT_P0; } - -private: void _writeGpioPort() override { I2CManager.write(_I2CAddress, 3, REG_OUTPUT_P0, _portOutputState, _portOutputState>>8); } From 6ad5326f1d1e44b8d17ffb5b3a7bd2312d9f7ae8 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 16:06:14 +0100 Subject: [PATCH 59/83] PCA9555 compiles and tested on PCA9548 mux IO_PCA9555.h added changes that had been applied to IO_MCP23017 for support on PCA9548 Mux. Constructor now also private and type casting of variables made the same for IO_PCA9555. Tested with MCP23017 and PCA9555 simultaneous on the same Mux Subbus --- IO_PCA9555.h | 1 + 1 file changed, 1 insertion(+) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index 75f2c38..607e1a8 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -34,6 +34,7 @@ public: if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } + private: // Constructor PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) From dab02ec65960764b750a0cd7bb2250f6b7315b97 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 16:10:16 +0100 Subject: [PATCH 60/83] Update IO_PCA9555.h Now compiles and works on PCA9548 Mux. Tested with MCP23017 and PCA9555 on the same Subbus --- IO_PCA9555.h | 1 - 1 file changed, 1 deletion(-) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index 607e1a8..75f2c38 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -34,7 +34,6 @@ public: if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } - private: // Constructor PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) From d57b5ba537c86bd9c6d6963b196d0a7febe25424 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:09:01 +0100 Subject: [PATCH 61/83] Update version.h to 5.1.7 --- version.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/version.h b/version.h index f10ceee..9b7c8ef 100644 --- a/version.h +++ b/version.h @@ -3,9 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.8" -// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 -// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result +#define VERSION "5.1.7" +// 5.1.7 - IO_PCA9555.h fixed to work on PCA9548 Subbus, tested // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - <I ...>, <JO ...>, <JP ...> - turntable commands From d07718be8cc34ffc852c771ba6cf4754eb7aebe8 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:18:59 +0100 Subject: [PATCH 62/83] Revert "Update version.h to 5.1.7" This reverts commit d57b5ba537c86bd9c6d6963b196d0a7febe25424. --- version.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/version.h b/version.h index 9b7c8ef..f10ceee 100644 --- a/version.h +++ b/version.h @@ -3,8 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.1.7" -// 5.1.7 - IO_PCA9555.h fixed to work on PCA9548 Subbus, tested +#define VERSION "5.1.8" +// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 +// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - <I ...>, <JO ...>, <JP ...> - turntable commands From 11b9fd4ef56d417d3e73a81ea0c390cad7b02233 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:25:10 +0100 Subject: [PATCH 63/83] Fixed IO_PCA9555.h to work with PCA9548 mux --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index f10ceee..b7c157b 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.8" +#define VERSION "5.1.9" +// 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK // 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result // 5.1.6 - STM32F4xx native I2C driver added From aacb980dc873cc52742d5840aebb215ef0b573ce Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Sun, 24 Sep 2023 15:40:42 +0100 Subject: [PATCH 64/83] Power control plus EXRAIL Power Control <0 A> etc plus EXRAIL SET_POWER Not yet fully tested. --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- DCCEXParser.cpp | 18 ++++++++++------- EXRAIL2.cpp | 14 +++++++++++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 8 +++++++- TrackManager.cpp | 46 +++++++++++++++++------------------------- TrackManager.h | 15 +++++++++----- 9 files changed, 66 insertions(+), 45 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 32f9874..a521b52 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,6 +269,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter,pmode, dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); } diff --git a/CommandDistributor.h b/CommandDistributor.h index 99b9f1e..d54ef31 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); template<typename... Targs> static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 150070c..9c94f82 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -576,7 +576,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - uint8_t t = (p[0] - 'A'); + byte t = (p[0] - 'A'); + DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -587,8 +588,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); - if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); + DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::ON, false, t); + if (main) TrackManager::setTrackPower(POWERMODE::ON, t); + //if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); + //if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); } else break; // will reply <X> } @@ -621,8 +624,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - uint8_t t = (p[0] - 'A'); - if (TrackManager::isProg(t)) { + byte t = (p[0] - 'A'); + DIAG(F("Processing track - %d "), t); + if (TrackManager::isProg(t)) { main = false; prog = true; } @@ -632,8 +636,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::SetMainTrackPower(POWERMODE::OFF, t); - if (prog) TrackManager::SetProgTrackPower(POWERMODE::OFF, t); + DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::OFF, false, t); + if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); } else break; // will reply <X> diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index d6d2597..07f4768 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -780,6 +780,20 @@ void RMFT2::loop2() { TrackManager::setJoin(false); CommandDistributor::broadcastPower(); break; + + case OPCODE_SET_POWER: + // operand is TRACK_POWER , trackid + + switch (operand) { + case TRACK_POWER_0: + TrackManager::setTrackPower(POWERMODE::OFF, getOperand(1)); + break; + case TRACK_POWER_1: + TrackManager::setTrackPower(POWERMODE::ON, getOperand(1)); + break; + } + + break; case OPCODE_SET_TRACK: // operand is trackmode<<8 | track id diff --git a/EXRAIL2.h b/EXRAIL2.h index 8af36d2..ad399ec 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -59,7 +59,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ROSTER,OPCODE_KILLALL, OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE, OPCODE_ENDTASK,OPCODE_ENDEXRAIL, - OPCODE_SET_TRACK, + OPCODE_SET_TRACK,OPCODE_SET_POWER, OPCODE_ONRED,OPCODE_ONAMBER,OPCODE_ONGREEN, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 11c598b..03e310e 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -138,6 +138,7 @@ #undef SERVO_SIGNAL #undef SET #undef SET_TRACK +#undef SET_POWER #undef SETLOCO #undef SIGNAL #undef SIGNALH @@ -275,6 +276,7 @@ #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) #define SET(pin) #define SET_TRACK(track,mode) +#define SET_POWER(track,onoff) #define SETLOCO(loco) #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 0784242..62b852a 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -63,6 +63,11 @@ // (10#mins)%100) #define STRIP_ZERO(value) 10##value%100 +// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF). +//const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0; +//const byte TRACK_POWER_1=1, TRACK_POWER_ON=1; + + // Pass 1 Implements aliases #include "EXRAIL2MacroReset.h" #undef ALIAS @@ -407,11 +412,12 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile), #define SET(pin) OPCODE_SET,V(pin), #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), +#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff, TRACK_NUMBER_##track), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco), #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) OPCODE_SPEED,V(speed), -#define START(route) OPCODE_START,V(route), +#define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL diff --git a/TrackManager.cpp b/TrackManager.cpp index 413fd95..ad7ef6a 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -354,47 +354,32 @@ void TrackManager::streamTrackState(Print* stream, byte t) { if (track[t]==NULL) return; auto format=F(""); bool pstate = TrackManager::isPowerOn(t); - //char PMODE[] = "OFF"; - //if (pstate) PMODE="ON "; - //if (TrackManager::isPowerOn(t)) {char PMODE[] = "ON";} - // else {char PMODE[] = "OFF";} - switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - format=F("<= %c MAIN %c>\n"); + if (pstate) {format=F("<= %c MAIN ON \n");} else {format = F("<= %c MAIN OFF \n");} break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: - format=F("<= %c PROG %c>\n"); + if (pstate) {format=F("<= %c PROG ON>\n");} else {format=F("<= %c PROG OFF>\n");} break; #endif case TRACK_MODE_NONE: - format=F("<= %c NONE %c>\n"); + if (pstate) {format=F("<= %c NONE %ON>\n");} else {format=F("<= %c NONE %OFF>\n");} break; case TRACK_MODE_EXT: - format=F("<= %c EXT %c>\n"); + if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} break; case TRACK_MODE_DC: - format=F("<= %c DC %c %d>\n"); + if (pstate) {format=F("<= %c DC ON %d>\n");} else {format=F("<= %c DC OFF %d>\n");} break; case TRACK_MODE_DCX: - format=F("<= %c DCX %c %d>\n"); + if (pstate) {format=F("<= %c DCX ON %d>\n");} else {format=F("<= %c DCX OFF %d>\n");} break; default: break; // unknown, dont care } - switch (pstate) { - case true: - if (stream) StringFormatter::send(stream,format,'A'+t,"ON", trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,"ON", trackDCAddr[t]); - break; - case false: - if (stream) StringFormatter::send(stream,format,'A'+t,"OFF", trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,"OFF", trackDCAddr[t]); - break; - } - //if (stream) StringFormatter::send(stream,format,'A'+t,PMODE, trackDCAddr[t]); - //else CommandDistributor::broadcastTrackState(format,'A'+t,PMODE, trackDCAddr[t]); + if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -428,10 +413,9 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t thistrack) { +void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - if (doall==false && thistrack != t) break; MotorDriver * driver=track[t]; if (!driver) continue; switch (track[t]->getMode()) { @@ -469,9 +453,15 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t th } } -// void TrackManager::setTrackPower(bool progTrack,POWERMODE mode, uint8_t track) { -// // write the code for this. -// } +void TrackManager::setTrackPower(POWERMODE mode, byte thistrack) { + + DIAG(F("SetPower Processing Track %d"), thistrack); + MotorDriver * driver=track[thistrack]; + if (!driver) return; + + driver->setPower(mode); + + } POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) diff --git a/TrackManager.h b/TrackManager.h index 3f9c73f..c6eea5c 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -39,6 +39,10 @@ const byte TRACK_NUMBER_5=5, TRACK_NUMBER_F=5; const byte TRACK_NUMBER_6=6, TRACK_NUMBER_G=6; const byte TRACK_NUMBER_7=7, TRACK_NUMBER_H=7; +// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF). +const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0; +const byte TRACK_POWER_1=1, TRACK_POWER_ON=1; + class TrackManager { public: static void Setup(const FSH * shieldName, @@ -60,12 +64,13 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vector<MotorDriver *>getMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode, bool doall, uint8_t thistrack); + static void setTrackPower(POWERMODE mode, byte thistrack); + static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode,true,0);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode,true,0);} - static void SetMainTrackPower(POWERMODE mode, uint8_t track) {setPower2(false,mode,false,track);} - static void SetProgTrackPower(POWERMODE mode, uint8_t track) {setPower2(true,mode,false,track);} + static void setMainPower(POWERMODE mode) {setPower2(false,mode);} + static void setProgPower(POWERMODE mode) {setPower2(true,mode);} + + static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); From 9333beda4941b739d50bc47d5ec22390a77b1fa6 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Sun, 24 Sep 2023 20:54:17 +0200 Subject: [PATCH 65/83] correct return when requesting D RAM --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7610d45..fe21549 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -985,7 +985,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) case HASH_KEYWORD_RAM: // <D RAM> StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); - break; + return true; #ifndef DISABLE_PROG case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value> From 5a7f278b1e94251a971eb65bd49da48cc722c29d Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Sun, 24 Sep 2023 20:54:17 +0200 Subject: [PATCH 66/83] correct return when requesting D RAM --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 29c252d..c9f31f0 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1057,7 +1057,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) case HASH_KEYWORD_RAM: // <D RAM> StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); - break; + return true; #ifndef DISABLE_PROG case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value> From 624656ebc97a60df1c8085fda0fd9e8cb4d33b99 Mon Sep 17 00:00:00 2001 From: Harald Barth <haba@kth.se> Date: Sun, 24 Sep 2023 20:56:27 +0200 Subject: [PATCH 67/83] date tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 98afa03..d46ef22 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308302157Z" +#define GITHUB_SHA "devel-202309241855Z" From 9e3ae21bb8fc26e25b5e448498217cea53159207 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Mon, 25 Sep 2023 09:59:17 +0100 Subject: [PATCH 68/83] Change to EXRAIL Set_Power Change to EXRAIL SET_Power --- DCCEXParser.cpp | 6 +----- EXRAILMacros.h | 2 +- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9c94f82..a8c257b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -588,10 +588,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::ON, false, t); if (main) TrackManager::setTrackPower(POWERMODE::ON, t); - //if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); - //if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); } else break; // will reply <X> } @@ -622,7 +619,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> prog=true; } -#endif +#endif <= else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> byte t = (p[0] - 'A'); DIAG(F("Processing track - %d "), t); @@ -636,7 +633,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::OFF, false, t); if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); } diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 62b852a..b85b68a 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -412,7 +412,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile), #define SET(pin) OPCODE_SET,V(pin), #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), -#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff, TRACK_NUMBER_##track), +#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco), #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) From 17c004aecf558baa980bf9bb620cd7e456cf7969 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Mon, 25 Sep 2023 14:32:54 +0100 Subject: [PATCH 69/83] Code corrections code corrections --- DCCEXParser.cpp | 37 ++++++++++++++++--------- EXRAIL2.cpp | 6 ++--- TrackManager.cpp | 70 +++++++++++++++++++++++++++++++++++------------- TrackManager.h | 2 +- 4 files changed, 81 insertions(+), 34 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a8c257b..a68b398 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -556,6 +556,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool prog=false; bool join=false; bool singletrack=false; + byte t=0; if (params > 1) break; if (params==0) { // All main=true; @@ -576,8 +577,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - byte t = (p[0] - 'A'); - DIAG(F("Processing track - %d "), t); + t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -588,7 +589,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::setTrackPower(POWERMODE::ON, t); + } else break; // will reply <X> } @@ -597,6 +598,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (main) TrackManager::setMainPower(POWERMODE::ON); if (prog) TrackManager::setProgPower(POWERMODE::ON); } + else { + if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); + if (prog) { + TrackManager::setTrackPower(true, POWERMODE::ON, t); + } + } CommandDistributor::broadcastPower(); return; } @@ -606,6 +613,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool main=false; bool prog=false; bool singletrack=false; + byte t=0; if (params > 1) break; if (params==0) { // All main=true; @@ -621,8 +629,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif <= else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - byte t = (p[0] - 'A'); - DIAG(F("Processing track - %d "), t); + t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -632,24 +640,29 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) main=true; prog=false; } - singletrack=true; - if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); - } - + singletrack=true; + } else break; // will reply <X> } TrackManager::setJoin(false); if (!singletrack) { - if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setProgPower(POWERMODE::OFF); + } + } + else { + if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setProgPower(POWERMODE::OFF); + TrackManager::setTrackPower(true, POWERMODE::OFF, t); } } CommandDistributor::broadcastPower(); return; - } + } case '!': // ESTOP ALL <!> DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 07f4768..8fd9532 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -783,13 +783,13 @@ void RMFT2::loop2() { case OPCODE_SET_POWER: // operand is TRACK_POWER , trackid - + //byte thistrack=getOperand(1); switch (operand) { case TRACK_POWER_0: - TrackManager::setTrackPower(POWERMODE::OFF, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::OFF, getOperand(1)); break; case TRACK_POWER_1: - TrackManager::setTrackPower(POWERMODE::ON, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::ON, getOperand(1)); break; } diff --git a/TrackManager.cpp b/TrackManager.cpp index ad7ef6a..d653645 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -364,16 +364,16 @@ void TrackManager::streamTrackState(Print* stream, byte t) { break; #endif case TRACK_MODE_NONE: - if (pstate) {format=F("<= %c NONE %ON>\n");} else {format=F("<= %c NONE %OFF>\n");} + if (pstate) {format=F("<= %c NONE ON>\n");} else {format=F("<= %c NONE OFF>\n");} break; case TRACK_MODE_EXT: if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} break; case TRACK_MODE_DC: - if (pstate) {format=F("<= %c DC ON %d>\n");} else {format=F("<= %c DC OFF %d>\n");} + if (pstate) {format=F("<= %c DC %d ON>\n");} else {format=F("<= %c DC %d OFF>\n");} break; case TRACK_MODE_DCX: - if (pstate) {format=F("<= %c DCX ON %d>\n");} else {format=F("<= %c DCX OFF %d>\n");} + if (pstate) {format=F("<= %c DCX %d ON>\n");} else {format=F("<= %c DCX %d OFF>\n");} break; default: break; // unknown, dont care @@ -416,9 +416,51 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() { void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - MotorDriver * driver=track[t]; - if (!driver) continue; - switch (track[t]->getMode()) { + TrackManager::setTrackPower(setProg, mode, t); + // MotorDriver * driver=track[t]; + // if (!driver) continue; + // switch (track[t]->getMode()) { + // case TRACK_MODE_MAIN: + // if (setProg) break; + // // toggle brake before turning power on - resets overcurrent error + // // on the Pololu board if brake is wired to ^D2. + // // XXX see if we can make this conditional + // driver->setBrake(true); + // driver->setBrake(false); // DCC runs with brake off + // driver->setPower(mode); + // break; + // case TRACK_MODE_DC: + // case TRACK_MODE_DCX: + // if (setProg) break; + // driver->setBrake(true); // DC starts with brake on + // applyDCSpeed(t); // speed match DCC throttles + // driver->setPower(mode); + // break; + // case TRACK_MODE_PROG: + // if (!setProg) break; + // driver->setBrake(true); + // driver->setBrake(false); + // driver->setPower(mode); + // break; + // case TRACK_MODE_EXT: + // driver->setBrake(true); + // driver->setBrake(false); + // driver->setPower(mode); + // break; + // case TRACK_MODE_NONE: + // break; + // } + + } +} + +void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { + + DIAG(F("SetTrackPower Processing Track %d"), thistrack); + MotorDriver * driver=track[thistrack]; + if (!driver) return; + + switch (track[thistrack]->getMode()) { case TRACK_MODE_MAIN: if (setProg) break; // toggle brake before turning power on - resets overcurrent error @@ -432,7 +474,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) { case TRACK_MODE_DCX: if (setProg) break; driver->setBrake(true); // DC starts with brake on - applyDCSpeed(t); // speed match DCC throttles + applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); break; case TRACK_MODE_PROG: @@ -449,17 +491,9 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) { case TRACK_MODE_NONE: break; } - - } -} - -void TrackManager::setTrackPower(POWERMODE mode, byte thistrack) { - - DIAG(F("SetPower Processing Track %d"), thistrack); - MotorDriver * driver=track[thistrack]; - if (!driver) return; - - driver->setPower(mode); + if (mode == POWERMODE::ON) {DIAG(F("Power Track %d ON"), thistrack);} + else {DIAG(F("Power Track %d OFF"), thistrack);} + //driver->setPower(mode); } diff --git a/TrackManager.h b/TrackManager.h index c6eea5c..39f708a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -64,7 +64,7 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vector<MotorDriver *>getMainDrivers(); #endif - static void setTrackPower(POWERMODE mode, byte thistrack); + static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} static void setMainPower(POWERMODE mode) {setPower2(false,mode);} From 2a46b960838e3d96e4577001afb24bd3ae7f8016 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Tue, 26 Sep 2023 18:02:39 +0100 Subject: [PATCH 70/83] Updates to power Updates to powere routines and EXRAIL --- DCCEXParser.cpp | 175 +++++++++++++++++++++++++---------------------- TrackManager.cpp | 59 +++++----------- TrackManager.h | 5 +- 3 files changed, 114 insertions(+), 125 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a68b398..aee7e05 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -552,84 +552,88 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case '1': // POWERON <1 [MAIN|PROG|JOIN]> { - bool main=false; - bool prog=false; - bool join=false; - bool singletrack=false; - byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> - main=true; - } + bool main=false; + bool prog=false; + bool join=false; + bool singletrack=false; + //byte t=0; + if (params > 1) break; + if (params==0) { // All + main=true; + prog=true; + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> + main=true; + } #ifndef DISABLE_PROG - else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> - main=true; - prog=true; - join=true; - } - else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> - prog=true; - } + else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> + main=true; + prog=true; + join=true; + } + else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> + prog=true; + } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - t = (p[0] - 'A'); - //DIAG(F("Processing track - %d "), t); - if (TrackManager::isProg(t)) { - main = false; - prog = true; - } - else - { - main=true; - prog=false; - } - singletrack=true; + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + byte t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); + if (prog) TrackManager::setTrackPower(true, POWERMODE::ON, t); + //CommandDistributor::broadcastPower(); + //TrackManager::streamTrackState(stream, t); + TrackManager::streamTrackState(NULL,t); + StringFormatter::send(stream, F("Track %d ON\n"), t); + return; + } + + else break; // will reply <X> + } - } - else break; // will reply <X> - } - TrackManager::setJoin(join); if (!singletrack) { + TrackManager::setJoin(join); if (main) TrackManager::setMainPower(POWERMODE::ON); if (prog) TrackManager::setProgPower(POWERMODE::ON); - } - else { - if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); - if (prog) { - TrackManager::setTrackPower(true, POWERMODE::ON, t); + CommandDistributor::broadcastPower(); + + return; } - } - CommandDistributor::broadcastPower(); - return; + } case '0': // POWEROFF <0 [MAIN | PROG] > { - bool main=false; - bool prog=false; - bool singletrack=false; - byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> - main=true; - } + bool main=false; + bool prog=false; + bool singletrack=false; + //byte t=0; + if (params > 1) break; + if (params==0) { // All + main=true; + prog=true; + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> + main=true; + } #ifndef DISABLE_PROG - else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> - prog=true; - } -#endif <= - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - t = (p[0] - 'A'); + else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> + prog=true; + } +#endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; @@ -640,28 +644,33 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) main=true; prog=false; } - singletrack=true; - } - else break; // will reply <X> - } - - TrackManager::setJoin(false); - if (!singletrack) { - if (main) TrackManager::setMainPower(POWERMODE::OFF); + singletrack=true; + TrackManager::setJoin(false); + if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setTrackPower(true, POWERMODE::OFF, t); + CommandDistributor::broadcastPower(); + } + StringFormatter::send(stream, F("Track %d OFF\n"), t); + TrackManager::streamTrackState(NULL, t); + return; + } + + else break; // will reply <X> + } + + if (!singletrack) { + TrackManager::setJoin(false); + + if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off TrackManager::setProgPower(POWERMODE::OFF); } - } - else { - if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, POWERMODE::OFF, t); - } + CommandDistributor::broadcastPower(); + return; } - CommandDistributor::broadcastPower(); - return; } case '!': // ESTOP ALL <!> diff --git a/TrackManager.cpp b/TrackManager.cpp index d653645..f66fb4d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -26,7 +26,8 @@ #include "MotorDriver.h" #include "DCCTimer.h" #include "DIAG.h" -#include"CommandDistributor.h" +#include "CommandDistributor.h" +#include "DCCEXParser.h" // Virtualised Motor shield multi-track hardware Interface #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) @@ -319,6 +320,7 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) FOR_EACH_TRACK(t) streamTrackState(stream,t); return true; + } p[0]-=HASH_KEYWORD_A; // convert A... to 0.... @@ -378,8 +380,10 @@ void TrackManager::streamTrackState(Print* stream, byte t) { default: break; // unknown, dont care } - if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + + if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -416,47 +420,16 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() { void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { + TrackManager::setTrackPower(setProg, mode, t); - // MotorDriver * driver=track[t]; - // if (!driver) continue; - // switch (track[t]->getMode()) { - // case TRACK_MODE_MAIN: - // if (setProg) break; - // // toggle brake before turning power on - resets overcurrent error - // // on the Pololu board if brake is wired to ^D2. - // // XXX see if we can make this conditional - // driver->setBrake(true); - // driver->setBrake(false); // DCC runs with brake off - // driver->setPower(mode); - // break; - // case TRACK_MODE_DC: - // case TRACK_MODE_DCX: - // if (setProg) break; - // driver->setBrake(true); // DC starts with brake on - // applyDCSpeed(t); // speed match DCC throttles - // driver->setPower(mode); - // break; - // case TRACK_MODE_PROG: - // if (!setProg) break; - // driver->setBrake(true); - // driver->setBrake(false); - // driver->setPower(mode); - // break; - // case TRACK_MODE_EXT: - // driver->setBrake(true); - // driver->setBrake(false); - // driver->setPower(mode); - // break; - // case TRACK_MODE_NONE: - // break; - // } } + return; } void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { - DIAG(F("SetTrackPower Processing Track %d"), thistrack); + //DIAG(F("SetTrackPower Processing Track %d"), thistrack); MotorDriver * driver=track[thistrack]; if (!driver) return; @@ -491,16 +464,22 @@ void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { case TRACK_MODE_NONE: break; } - if (mode == POWERMODE::ON) {DIAG(F("Power Track %d ON"), thistrack);} - else {DIAG(F("Power Track %d OFF"), thistrack);} - //driver->setPower(mode); } + void TrackManager::reportPowerChange(Print* stream, byte thistrack) { + // This function is for backward JMRI compatibility only + // It reports the first track only, as main, regardless of track settings. + // <c MeterName value C/V unit min max res warn> + int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); + StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"), + track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); +} + POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) if (track[t]->getMode()==TRACK_MODE_PROG) - return track[t]->getPower(); + return track[t]->getPower(); return POWERMODE::OFF; } diff --git a/TrackManager.h b/TrackManager.h index 39f708a..cf2d54b 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -64,12 +64,12 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vector<MotorDriver *>getMainDrivers(); #endif - static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); + static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} static void setMainPower(POWERMODE mode) {setPower2(false,mode);} static void setProgPower(POWERMODE mode) {setPower2(true,mode);} - + static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); static const int16_t MAX_TRACKS=8; @@ -84,6 +84,7 @@ class TrackManager { static void sampleCurrent(); static void reportGauges(Print* stream); static void reportCurrent(Print* stream); + static void reportPowerChange(Print* stream, byte thistrack); static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); From 25bbfa4c6805bf03cdb188d6d7d3457eec9b642b Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Wed, 27 Sep 2023 14:46:48 +0100 Subject: [PATCH 71/83] Fix <1 JOIN> Fixed <1 JOIN> issue in TrackManager --- DCCEXParser.cpp | 15 +++++++++------ EXRAIL2.cpp | 4 ++-- TrackManager.cpp | 18 ++++++++++-------- TrackManager.h | 9 +++++---- 4 files changed, 26 insertions(+), 20 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aee7e05..c82175b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -589,8 +589,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); - if (prog) TrackManager::setTrackPower(true, POWERMODE::ON, t); + if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t); + if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t); //CommandDistributor::broadcastPower(); //TrackManager::streamTrackState(stream, t); TrackManager::streamTrackState(NULL,t); @@ -603,8 +603,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (!singletrack) { TrackManager::setJoin(join); - if (main) TrackManager::setMainPower(POWERMODE::ON); - if (prog) TrackManager::setProgPower(POWERMODE::ON); + if (join) TrackManager::setJoinPower(POWERMODE::ON); + else { + if (main) TrackManager::setMainPower(POWERMODE::ON); + if (prog) TrackManager::setProgPower(POWERMODE::ON); + } CommandDistributor::broadcastPower(); return; @@ -646,10 +649,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } singletrack=true; TrackManager::setJoin(false); - if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); + if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, POWERMODE::OFF, t); + TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); CommandDistributor::broadcastPower(); } StringFormatter::send(stream, F("Track %d OFF\n"), t); diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 8fd9532..321872d 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -786,10 +786,10 @@ void RMFT2::loop2() { //byte thistrack=getOperand(1); switch (operand) { case TRACK_POWER_0: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::OFF, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::OFF, getOperand(1)); break; case TRACK_POWER_1: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::ON, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::ON, getOperand(1)); break; } diff --git a/TrackManager.cpp b/TrackManager.cpp index f66fb4d..dd27d85 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -417,17 +417,17 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode) { +void TrackManager::setPower2(bool setProg,bool setJoin, POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - TrackManager::setTrackPower(setProg, mode, t); + TrackManager::setTrackPower(setProg, setJoin, mode, t); } return; } -void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { +void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack) { //DIAG(F("SetTrackPower Processing Track %d"), thistrack); MotorDriver * driver=track[thistrack]; @@ -445,21 +445,23 @@ void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { break; case TRACK_MODE_DC: case TRACK_MODE_DCX: - if (setProg) break; + DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); + if (setProg || setJoin) {DIAG(F("Nowt to do")); break;} driver->setBrake(true); // DC starts with brake on applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); + DIAG(F("Doing it anyway")); break; case TRACK_MODE_PROG: - if (!setProg) break; + if (!setProg && !setJoin) break; driver->setBrake(true); driver->setBrake(false); driver->setPower(mode); break; case TRACK_MODE_EXT: - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); break; case TRACK_MODE_NONE: break; diff --git a/TrackManager.h b/TrackManager.h index cf2d54b..21b8d59 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -65,11 +65,12 @@ class TrackManager { static std::vector<MotorDriver *>getMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode); + static void setPower2(bool progTrack,bool joinTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode);} - static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); + static void setMainPower(POWERMODE mode) {setPower2(false,false,mode);} + static void setProgPower(POWERMODE mode) {setPower2(true,false,mode);} + static void setJoinPower(POWERMODE mode) {setPower2(false,true,mode);} + static void setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack); static const int16_t MAX_TRACKS=8; From ed0cfee0910fd37a78f0996ccfb2d0c2d2c88236 Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Thu, 28 Sep 2023 17:43:22 +0800 Subject: [PATCH 72/83] STM32 DCCEXanalogWrite for TrackManager PWM --- DCCTimerSTM32.cpp | 117 ++++++++++++++++++++++++++++++++++++++++------ MotorDriver.cpp | 66 ++++++++++++++++++++++++-- MotorDriver.h | 38 +++++++++++---- TrackManager.cpp | 12 +++++ version.h | 7 ++- 5 files changed, 214 insertions(+), 26 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f57499a..0f9c432 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -1,6 +1,6 @@ /* * © 2023 Neil McKechnie - * © 2022-23 Paul M. Antoine + * © 2022-2023 Paul M. Antoine * © 2021 Mike S * © 2021, 2023 Harald Barth * © 2021 Fred Decker @@ -154,13 +154,28 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 /////////////////////////////////////////////////////////////////////////////////////////////// INTERRUPT_CALLBACK interruptHandler=0; -// Let's use STM32's timer #11 until disabused of this notion -// Timer #11 is used for "servo" library, but as DCC-EX is not using -// this libary, we should be free and clear. -HardwareTimer timer(TIM11); + +// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability, +// so are good choices for general timer duties - they are used for tone and servo +// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs. +// NB: the F401, F410 and F411 do **not** have Timer 6 or 7, so we use Timer 11 +#ifndef DCC_EX_TIMER +#if defined(TIM6) +#define DCC_EX_TIMER TIM6 +#elif defined(TIM7) +#define DCC_EX_TIMER TIM7 +#elif defined(TIM11) +#define DCC_EX_TIMER TIM11 +#else +#warning This STM32F4XX variant does not have Timers 6,7 or 11!! +#endif +#endif // ifndef DCC_EX_TIMER + +HardwareTimer dcctimer(DCC_EX_TIMER); +void DCCTimer_Handler() __attribute__((interrupt)); // Timer IRQ handler -void Timer11_Handler() { +void DCCTimer_Handler() { interruptHandler(); } @@ -168,22 +183,24 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interruptHandler=callback; noInterrupts(); - // adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES); - timer.pause(); - timer.setPrescaleFactor(1); + dcctimer.pause(); + dcctimer.setPrescaleFactor(1); // timer.setOverflow(CLOCK_CYCLES * 2); - timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); - timer.attachInterrupt(Timer11_Handler); - timer.refresh(); - timer.resume(); + dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); + // dcctimer.attachInterrupt(Timer11_Handler); + dcctimer.attachInterrupt(DCCTimer_Handler); + dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority! + dcctimer.refresh(); + dcctimer.resume(); interrupts(); } bool DCCTimer::isPWMPin(byte pin) { - //TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM, + //TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, // there's no support yet for High Accuracy, so for now return false // return digitalPinHasPWM(pin); + (void) pin; return false; } @@ -235,6 +252,78 @@ void DCCTimer::reset() { while(true) {}; } +// TODO: rationalise the size of these... could really use sparse arrays etc. +static HardwareTimer * pin_timer[100] = {0}; +static uint32_t channel_frequency[100] = {0}; +static uint32_t pin_channel[100] = {0}; + +// Using the HardwareTimer library API included in stm32duino core to handle PWM duties +// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more +// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones +// currently used for HA so they don't interfere with one another. For now we'll just make PWM +// work well... then work backwards to integrate with HA mode if we can. +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) +{ + if (pin_timer[pin] == NULL) { + // Automatically retrieve TIM instance and channel associated to pin + // This is used to be compatible with all STM32 series automatically. + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM); + if (Instance == NULL) { + // We shouldn't get here (famous last words) as it ought to have been caught by brakeCanPWM()! + DIAG(F("DCCEXanalogWriteFrequency::Pin %d has no PWM function!"), pin); + return; + } + pin_channel[pin] = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pin), PinMap_PWM)); + + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, + // HardwareTimer is not destructed when setup function is finished. + pin_timer[pin] = new HardwareTimer(Instance); + // Configure and start PWM + // MyTim->setPWM(channel, pin, 5, 10, NULL, NULL); // No callback required, we can simplify the function call + if (pin_timer[pin] != NULL) + { + pin_timer[pin]->setPWM(pin_channel[pin], pin, frequency, 0); // set frequency in Hertz, 0% dutycycle + DIAG(F("DCCEXanalogWriteFrequency::Pin %d on Timer %d, frequency %d"), pin, pin_channel[pin], frequency); + } + else + DIAG(F("DCCEXanalogWriteFrequency::failed to allocate HardwareTimer instance!")); + } + else + { + // Frequency change request + if (frequency != channel_frequency[pin]) + { + pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! + pin_timer[pin]->setOverflow(frequency, HERTZ_FORMAT); // Just change the frequency if it's already running! + DIAG(F("DCCEXanalogWriteFrequency::setting frequency to %d"), frequency); + } + } + channel_frequency[pin] = frequency; + return; +} + +void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { + // Calculate percentage duty cycle from value given + uint32_t duty_cycle = (value * 100 / 256) + 1; + if (pin_timer[pin] != NULL) { + if (duty_cycle == 100) + { + pin_timer[pin]->pauseChannel(pin_channel[pin]); + DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); + } + else + { + pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! + pin_timer[pin]->resumeChannel(pin_channel[pin]); + pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle + DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle); + } + } + else + DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin); +} + + // Now we can handle more ADCs, maybe this works! #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 4644ad5..61e229f 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -34,6 +34,11 @@ unsigned long MotorDriver::globalOverloadStart = 0; volatile portreg_t shadowPORTA; volatile portreg_t shadowPORTB; volatile portreg_t shadowPORTC; +#if defined(ARDUINO_ARCH_STM32) +volatile portreg_t shadowPORTD; +volatile portreg_t shadowPORTE; +volatile portreg_t shadowPORTF; +#endif MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin, byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) { @@ -68,6 +73,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin.shadowinout = fastSignalPin.inout; fastSignalPin.inout = &shadowPORTC; } + if (HAVE_PORTD(fastSignalPin.inout == &PORTD)) { + DIAG(F("Found PORTD pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTD; + } + if (HAVE_PORTE(fastSignalPin.inout == &PORTE)) { + DIAG(F("Found PORTE pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTE; + } + if (HAVE_PORTF(fastSignalPin.inout == &PORTF)) { + DIAG(F("Found PORTF pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTF; + } signalPin2=signal_pin2; if (signalPin2!=UNUSED_PIN) { @@ -91,6 +111,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin2.shadowinout = fastSignalPin2.inout; fastSignalPin2.inout = &shadowPORTC; } + if (HAVE_PORTD(fastSignalPin2.inout == &PORTD)) { + DIAG(F("Found PORTD pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTD; + } + if (HAVE_PORTE(fastSignalPin2.inout == &PORTE)) { + DIAG(F("Found PORTE pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTE; + } + if (HAVE_PORTF(fastSignalPin2.inout == &PORTF)) { + DIAG(F("Found PORTF pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTF; + } } else dualSignal=false; @@ -279,7 +314,7 @@ void MotorDriver::startCurrentFromHW() { #pragma GCC pop_options #endif //ANALOG_READ_INTERRUPT -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) #ifdef VARIABLE_TONES uint16_t taurustones[28] = { 165, 175, 196, 220, 247, 262, 294, 330, @@ -330,7 +365,7 @@ void MotorDriver::setDCSignal(byte speedcode) { byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127 byte tDir=speedcode & 0x80; byte brake; -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) { int f = 131; #ifdef VARIABLE_TONES @@ -348,7 +383,7 @@ void MotorDriver::setDCSignal(byte speedcode) { else brake = 2 * (128-tSpeed); if (invertBrake) brake=255-brake; -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) DCCTimer::DCCEXanalogWrite(brakePin,brake); #else analogWrite(brakePin,brake); @@ -372,6 +407,24 @@ void MotorDriver::setDCSignal(byte speedcode) { setSignal(tDir); HAVE_PORTC(PORTC=shadowPORTC); interrupts(); + } else if (HAVE_PORTD(fastSignalPin.shadowinout == &PORTD)) { + noInterrupts(); + HAVE_PORTD(shadowPORTD=PORTD); + setSignal(tDir); + HAVE_PORTD(PORTD=shadowPORTD); + interrupts(); + } else if (HAVE_PORTE(fastSignalPin.shadowinout == &PORTE)) { + noInterrupts(); + HAVE_PORTE(shadowPORTE=PORTE); + setSignal(tDir); + HAVE_PORTE(PORTE=shadowPORTE); + interrupts(); + } else if (HAVE_PORTF(fastSignalPin.shadowinout == &PORTF)) { + noInterrupts(); + HAVE_PORTF(shadowPORTF=PORTF); + setSignal(tDir); + HAVE_PORTF(PORTF=shadowPORTF); + interrupts(); } else { noInterrupts(); setSignal(tDir); @@ -393,6 +446,13 @@ void MotorDriver::throttleInrush(bool on) { } else { ledcDetachPin(brakePin); } +#elif defined(ARDUINO_ARCH_STM32) + if(on) { + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500); + DCCTimer::DCCEXanalogWrite(brakePin,duty); + } else { + pinMode(brakePin, OUTPUT); + } #else if(on){ switch(brakePin) { diff --git a/MotorDriver.h b/MotorDriver.h index 21bceb6..20a91d3 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -1,5 +1,5 @@ /* - * © 2022 Paul M Antoine + * © 2022-2023 Paul M. Antoine * © 2021 Mike S * © 2021 Fred Decker * © 2020 Chris Harlow @@ -60,6 +60,16 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #define HAVE_PORTB(X) X #define PORTC GPIOC->ODR #define HAVE_PORTC(X) X +#define PORTD GPIOD->ODR +#define HAVE_PORTD(X) X +#if defined(GPIOE) +#define PORTE GPIOE->ODR +#define HAVE_PORTE(X) X +#endif +#if defined(GPIOF) +#define PORTF GPIOF->ODR +#define HAVE_PORTF(X) X +#endif #endif // if macros not defined as pass-through we define @@ -74,6 +84,15 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #ifndef HAVE_PORTC #define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 #endif +#ifndef HAVE_PORTD +#define HAVE_PORTD(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif +#ifndef HAVE_PORTE +#define HAVE_PORTE(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif +#ifndef HAVE_PORTF +#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif // Virtualised Motor shield 1-track hardware Interface @@ -110,6 +129,9 @@ struct FASTPIN { extern volatile portreg_t shadowPORTA; extern volatile portreg_t shadowPORTB; extern volatile portreg_t shadowPORTC; +extern volatile portreg_t shadowPORTD; +extern volatile portreg_t shadowPORTE; +extern volatile portreg_t shadowPORTF; enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT }; @@ -163,16 +185,16 @@ class MotorDriver { unsigned int raw2mA( int raw); unsigned int mA2raw( unsigned int mA); inline bool brakeCanPWM() { -#if defined(ARDUINO_ARCH_ESP32) || defined(__arm__) - // TODO: on ARM we can use digitalPinHasPWM, and may wish/need to - return true; -#else -#ifdef digitalPinToTimer +#if defined(ARDUINO_ARCH_ESP32) + return (brakePin != UNUSED_PIN); // This was just (true) but we probably do need to check for UNUSED_PIN! +#elif defined(__arm__) + // On ARM we can use digitalPinHasPWM + return ((brakePin!=UNUSED_PIN) && (digitalPinHasPWM(brakePin))); +#elif defined(digitalPinToTimer) return ((brakePin!=UNUSED_PIN) && (digitalPinToTimer(brakePin))); #else return (brakePin<14 && brakePin >1); -#endif //digitalPinToTimer -#endif //ESP32/ARM +#endif } inline int getRawCurrentTripValue() { return rawCurrentTripValue; diff --git a/TrackManager.cpp b/TrackManager.cpp index bd7c623..687eb8b 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -154,10 +154,16 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTC(shadowPORTC=PORTC); + HAVE_PORTD(shadowPORTD=PORTD); + HAVE_PORTE(shadowPORTE=PORTE); + HAVE_PORTF(shadowPORTF=PORTF); APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on)); HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTC(PORTC=shadowPORTC); + HAVE_PORTD(PORTD=shadowPORTD); + HAVE_PORTE(PORTE=shadowPORTE); + HAVE_PORTF(PORTF=shadowPORTF); } void TrackManager::setCutout( bool on) { @@ -172,10 +178,16 @@ void TrackManager::setPROGSignal( bool on) { HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTC(shadowPORTC=PORTC); + HAVE_PORTD(shadowPORTD=PORTD); + HAVE_PORTE(shadowPORTE=PORTE); + HAVE_PORTF(shadowPORTF=PORTF); APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on)); HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTC(PORTC=shadowPORTC); + HAVE_PORTD(PORTD=shadowPORTD); + HAVE_PORTE(PORTE=shadowPORTE); + HAVE_PORTF(PORTF=shadowPORTF); } // setDCSignal(), called from normal context diff --git a/version.h b/version.h index b7c157b..95d7461 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,12 @@ #include "StringFormatter.h" -#define VERSION "5.1.9" +#define VERSION "5.1.10" +// 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX +// - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible +// - ESP32 brakeCanPWM check now detects UNUSED_PIN +// - ARM architecture brakeCanPWM now uses digitalPinHasPWM() +// - STM32F4xx shadowpin extensions to handle pins on ports D, E and F // 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK // 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result From 52cfc187543a487cde464a40fd7c7904284dca98 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Thu, 28 Sep 2023 15:02:30 +0100 Subject: [PATCH 73/83] Remove Diags not needed Tidy up Diags and responses - use HASH_KEYWORD in place of 'A' --- DCCEXParser.cpp | 21 ++++++++++++--------- TrackManager.cpp | 7 +++---- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index c82175b..a561561 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -157,6 +157,7 @@ const int16_t HASH_KEYWORD_VPIN=-415; const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; +const int16_t HASH_KEYWORD_H='H'; const int16_t HASH_KEYWORD_I='I'; const int16_t HASH_KEYWORD_O='O'; const int16_t HASH_KEYWORD_P='P'; @@ -576,7 +577,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { @@ -591,10 +593,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) singletrack=true; if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t); if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t); + + StringFormatter::send(stream, F("<1 %c>\n"), t+'A'); //CommandDistributor::broadcastPower(); - //TrackManager::streamTrackState(stream, t); - TrackManager::streamTrackState(NULL,t); - StringFormatter::send(stream, F("Track %d ON\n"), t); + //TrackManager::streamTrackState(NULL,t); return; } @@ -635,7 +637,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { @@ -652,11 +655,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); - CommandDistributor::broadcastPower(); + TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); } - StringFormatter::send(stream, F("Track %d OFF\n"), t); - TrackManager::streamTrackState(NULL, t); + StringFormatter::send(stream, F("<0 %c>\n"), t+'A'); + //CommandDistributor::broadcastPower(); + //TrackManager::streamTrackState(NULL, t); return; } diff --git a/TrackManager.cpp b/TrackManager.cpp index dd27d85..bab202d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -358,7 +358,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) { bool pstate = TrackManager::isPowerOn(t); switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - if (pstate) {format=F("<= %c MAIN ON \n");} else {format = F("<= %c MAIN OFF \n");} + if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: @@ -445,12 +445,11 @@ void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byt break; case TRACK_MODE_DC: case TRACK_MODE_DCX: - DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); - if (setProg || setJoin) {DIAG(F("Nowt to do")); break;} + //DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); + if (setProg || setJoin) break; driver->setBrake(true); // DC starts with brake on applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); - DIAG(F("Doing it anyway")); break; case TRACK_MODE_PROG: if (!setProg && !setJoin) break; From 7afd4443d616d95526cef697e7bc7c68fd728b61 Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Mon, 2 Oct 2023 12:04:47 +0800 Subject: [PATCH 74/83] STM32 revised I2C clock setup --- I2CManager_STM32.h | 57 ++++++++++++++++++++++++++++++---------------- version.h | 3 ++- 2 files changed, 39 insertions(+), 21 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 86b9b74..7e0f547 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -117,35 +117,46 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Disable the I2C device, as TRISE can only be programmed whilst disabled s->CR1 &= ~(I2C_CR1_PE); // Disable I2C + s->CR1 |= I2C_CR1_SWRST; // reset the I2C + asm("nop"); // wait a bit... suggestion from online! + s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation - if (i2cClockSpeed > 100000L) + if (i2cClockSpeed > 100000UL) { - if (i2cClockSpeed > 400000L) - i2cClockSpeed = 400000L; + // if (i2cClockSpeed > 400000L) + // i2cClockSpeed = 400000L; t_rise = 300; // nanoseconds } else { - i2cClockSpeed = 100000L; + // i2cClockSpeed = 100000L; t_rise = 1000; // nanoseconds } - // Configure the rise time register - s->TRISE = (t_rise / (1000 / i2c_MHz)) + 1; + // Configure the rise time register - max allowed tRISE is 1000ns, + // so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. + s->TRISE = (t_rise * i2c_MHz / 1000) + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle (use 2:1) // Bit 11-0: FREQR - if (i2cClockSpeed > 100000L) { - // In fast mode, I2C period is 3 * CCR * TPCLK1. - //APB1clk1 / 3 / i2cClockSpeed = 38, but that results in 306KHz not 400! - ccr_freq = 30; // So 30 gives 396KHz or so! - s->CCR = (uint16_t)(ccr_freq | 0x8000); // We need Fast Mode set - } else { - // In standard mode, I2C period is 2 * CCR * TPCLK1 - ccr_freq = (APB1clk1 / 2 / i2cClockSpeed); // Should be 225 for 45Mhz APB1 clock - s->CCR |= (uint16_t)ccr_freq; - } + // if (i2cClockSpeed > 400000UL) { + // // In fast mode plus, I2C period is 3 * CCR * TPCLK1. + // // s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + // s->CCR = APB1clk1 / 3 / i2cClockSpeed; // Set I2C clockspeed to start! + // s->CCR |= 0xC000; // We need Fast Mode AND DUTY bits set + // } else { + // In standard and fast mode, I2C period is 2 * CCR * TPCLK1 + s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + s->CCR |= (APB1clk1 / 2 / i2cClockSpeed); // Set I2C clockspeed to start! + // s->CCR |= (i2c_MHz * 500 / (i2cClockSpeed / 1000)); // Set I2C clockspeed to start! + // if (i2cClockSpeed > 100000UL) + // s->CCR |= 0xC000; // We need Fast Mode bits set as well + // } + + // DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2); + // DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR); + // DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE); // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C @@ -159,6 +170,7 @@ void I2CManagerClass::I2C_init() // Query the clockspeed from the STM32 HAL layer APB1clk1 = HAL_RCC_GetPCLK1Freq(); i2c_MHz = APB1clk1 / 1000000UL; + // DIAG(F("I2C_init() peripheral clock speed is: %d"), i2c_MHz); // Enable clocks RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK // Reset the I2C1 peripheral to initial state @@ -181,6 +193,7 @@ void I2CManagerClass::I2C_init() GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up // Software reset the I2C peripheral + I2C1->CR1 &= ~I2C_CR1_PE; // Disable I2C1 peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C asm("nop"); // wait a bit... suggestion from online! s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation @@ -191,6 +204,7 @@ void I2CManagerClass::I2C_init() // Set I2C peripheral clock frequency // s->CR2 |= I2C_PERIPH_CLK; s->CR2 |= i2c_MHz; + // DIAG(F("I2C_init() peripheral clock is now: %d"), s->CR2); // set own address to 00 - not used in master mode I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet @@ -214,6 +228,7 @@ void I2CManagerClass::I2C_init() s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts #endif + // DIAG(F("I2C_init() setting initial I2C clock to 100KHz")); // Calculate baudrate and set default rate for now // Configure the Clock Control Register for 100KHz SCL frequency // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode @@ -221,12 +236,14 @@ void I2CManagerClass::I2C_init() // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) // s->CCR = I2C_PERIPH_CLK * 5; s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value - s->CCR |= (APB1clk1 / 2 / 100000UL); // i2c_MHz * 5; - // s->CCR = i2c_MHz * 5; + s->CCR |= (APB1clk1 / 2 / 100000UL); // Set a default of 100KHz I2C clockspeed to start! // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. - // s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 - s->TRISE = i2c_MHz + 1; + s->TRISE = (1000 * i2c_MHz / 1000) + 1; + + // DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2); + // DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR); + // DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE); // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C diff --git a/version.h b/version.h index 95d7461..21dde65 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.10" +#define VERSION "5.1.11" +// 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection // 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX // - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible // - ESP32 brakeCanPWM check now detects UNUSED_PIN From 2ff1619ad15ed43bb87eaac23b3c402d5df10923 Mon Sep 17 00:00:00 2001 From: pmantoine <pma-github@milleng.com.au> Date: Wed, 4 Oct 2023 14:54:06 +0800 Subject: [PATCH 75/83] STM32 reinstate 100% duty cycle PWM --- DCCTimerSTM32.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index 0f9c432..f2d51ff 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -306,18 +306,18 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { // Calculate percentage duty cycle from value given uint32_t duty_cycle = (value * 100 / 256) + 1; if (pin_timer[pin] != NULL) { - if (duty_cycle == 100) - { - pin_timer[pin]->pauseChannel(pin_channel[pin]); - DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); - } - else - { + // if (duty_cycle == 100) + // { + // pin_timer[pin]->pauseChannel(pin_channel[pin]); + // DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); + // } + // else + // { pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! - pin_timer[pin]->resumeChannel(pin_channel[pin]); + // pin_timer[pin]->resumeChannel(pin_channel[pin]); pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle); - } + // } } else DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin); From fe618d0b854a200dec5ce670e24dc92587735464 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Fri, 6 Oct 2023 19:11:11 +0100 Subject: [PATCH 76/83] Add getModeName() Add facility to get the name of the track mode --- .gitignore | 1 + TrackManager.cpp | 22 +++++++++++++++++++++- TrackManager.h | 2 ++ 3 files changed, 24 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index 6237359..482da70 100644 --- a/.gitignore +++ b/.gitignore @@ -13,3 +13,4 @@ myFilter.cpp my*.h !my*.example.h compile_commands.json +newcode.txt.old diff --git a/TrackManager.cpp b/TrackManager.cpp index bab202d..3ea9877 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -556,4 +556,24 @@ bool TrackManager::isProg(byte t) { if (track[t]->getMode()==TRACK_MODE_PROG) return true; return false; -} \ No newline at end of file +} + +byte TrackManager::returnMode(byte t) { + return (track[t]->getMode()); +} + +static const char* TrackManager::getModeName(byte Mode) { + + //DIAG(F("PowerMode %d"), Mode); + +switch (Mode) + { + case 1: return "NONE"; + case 2: return "MAIN"; + case 4: return "PROG"; + case 8: return "DC"; + case 16: return "DCX"; + case 32: return "EXT"; + default: return "----"; + } +} diff --git a/TrackManager.h b/TrackManager.h index 21b8d59..486057a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -90,6 +90,8 @@ class TrackManager { static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); static bool isProg(byte t); + static byte returnMode(byte t); + static const char* getModeName(byte Mode); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From bef4b2ec35063a85bc9603d3952e67e6eba1577c Mon Sep 17 00:00:00 2001 From: Asbelos <asbelos@btinternet.com> Date: Mon, 9 Oct 2023 18:09:48 +0100 Subject: [PATCH 77/83] fix <JR> default roster --- DCCEXParser.cpp | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index fe21549..7b4836e 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -121,7 +121,7 @@ Once a new OPCODE is decided upon, update this list. for (int16_t i=0;;i+=sizeof(flashList[0])) { \ int16_t value=GETHIGHFLASHW(flashList,i); \ if (value==INT16_MAX) break; \ - if (value != 0) StringFormatter::send(stream,F(" %d"),value); \ + StringFormatter::send(stream,F(" %d"),value); \ } diff --git a/version.h b/version.h index a76aef2..1610054 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.0.3" +#define VERSION "5.0.4" +// 5.0.4 - Bugfix: <JR> misses default roster. // 5.0.3 - Check bad AT firmware version // 5.0.2 - Bugfix: ESP32 30ms off time // 5.0.1 - Bugfix: execute 30ms off time before rejoin From 68fd56e7fccc74be4c06a11eae04c8bec846538e Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Tue, 10 Oct 2023 11:52:46 +0100 Subject: [PATCH 78/83] Added returnDCAddr Added function to return DC address --- TrackManager.cpp | 7 ++++++- TrackManager.h | 1 + 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 3ea9877..7d86de0 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -356,6 +356,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) { if (track[t]==NULL) return; auto format=F(""); bool pstate = TrackManager::isPowerOn(t); + switch(track[t]->getMode()) { case TRACK_MODE_MAIN: if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} @@ -562,7 +563,11 @@ byte TrackManager::returnMode(byte t) { return (track[t]->getMode()); } -static const char* TrackManager::getModeName(byte Mode) { +int16_t TrackManager::returnDCAddr(byte t) { + return (trackDCAddr[t]); +} + +const char* TrackManager::getModeName(byte Mode) { //DIAG(F("PowerMode %d"), Mode); diff --git a/TrackManager.h b/TrackManager.h index 486057a..d197751 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -91,6 +91,7 @@ class TrackManager { static bool isPowerOn(byte t); static bool isProg(byte t); static byte returnMode(byte t); + static int16_t returnDCAddr(byte t); static const char* getModeName(byte Mode); static int16_t joinRelay; From a092e06a6fec69159de22e14127524d53e65a20c Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Tue, 10 Oct 2023 12:11:49 +0100 Subject: [PATCH 79/83] Update .gitignore added UserAddin.txt to gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 482da70..759b739 100644 --- a/.gitignore +++ b/.gitignore @@ -14,3 +14,4 @@ my*.h !my*.example.h compile_commands.json newcode.txt.old +UserAddin.txt From ea4f90d5fcd76b59f2a3a4fb0daa5a6f7ceeb815 Mon Sep 17 00:00:00 2001 From: Colin Murdoch <colin.murdoch@btinternet.com> Date: Wed, 11 Oct 2023 17:06:56 +0100 Subject: [PATCH 80/83] Merged in Power changes Merge in power changes and EXRAIL command & update to version.h --- version.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 21dde65..e9e1e79 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,12 @@ #include "StringFormatter.h" -#define VERSION "5.1.11" +#define VERSION "5.1.12" +// 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> +// Added EXRAIL SET_POWER(track, ON/OFF) +// Fixed a problem whereby <1 MAIN> also powered on PROG track +// Added functions to TrackManager.cpp to allow UserAddin code for power display on OLED/LCD +// Added - returnMode(byte t), returnDCAddr(byte t) & getModeName(byte Mode) // 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection // 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX // - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible From d5978b1578ef461fdd23317ebc4f92ca47f8b00d Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Thu, 12 Oct 2023 13:28:39 +1000 Subject: [PATCH 81/83] Change broadcast --- CommandDistributor.cpp | 2 +- DCCEXParser.cpp | 12 ++++++------ version.h | 3 ++- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index a521b52..1651771 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -162,7 +162,7 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { } void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position, bool moving) { - broadcastReply(COMMAND_TYPE, F("<i %d %d %d>\n"), id, position, moving); + broadcastReply(COMMAND_TYPE, F("<I %d %d %d>\n"), id, position, moving); } void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9cff75a..e53b882 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -60,8 +60,8 @@ Once a new OPCODE is decided upon, update this list. G, h, H, Turnout state broadcast - i, Reserved for future use - Turntable object broadcast - I, Reserved for future use - Turntable object command and control + i, Server details string + I, Turntable object command, control, and broadcast j, Throttle responses J, Throttle queries k, Reserved for future use - Potentially Railcom @@ -1244,7 +1244,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (tto) { bool type = tto->isEXTT(); uint8_t position = tto->getPosition(); - StringFormatter::send(stream, F("<i %d %d>\n"), type, position); + StringFormatter::send(stream, F("<I %d %d>\n"), type, position); } else { return false; } @@ -1270,7 +1270,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[2]); - StringFormatter::send(stream, F("<i>\n")); + StringFormatter::send(stream, F("<I>\n")); } else { if (!tto) return false; if (!tto->isEXTT()) return false; @@ -1287,7 +1287,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[3]); - StringFormatter::send(stream, F("<i>\n")); + StringFormatter::send(stream, F("<I>\n")); } else { return false; } @@ -1301,7 +1301,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) // tto must exist, no more than 48 positions, angle 0 - 3600 if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; tto->addPosition(p[2], p[3], p[4]); - StringFormatter::send(stream, F("<i>\n")); + StringFormatter::send(stream, F("<I>\n")); } else { return false; } diff --git a/version.h b/version.h index e9e1e79..ee65765 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.12" +#define VERSION "5.1.13" +// 5.1.13 - Changed turntable broadcast from i to I due to server string conflict // 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> // Added EXRAIL SET_POWER(track, ON/OFF) // Fixed a problem whereby <1 MAIN> also powered on PROG track From ce84974967cd9771479116a7cde2dfd2d1b627e9 Mon Sep 17 00:00:00 2001 From: peteGSX <peteracole@outlook.com.au> Date: Thu, 12 Oct 2023 13:42:14 +1000 Subject: [PATCH 82/83] Missed one i --- Turntables.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Turntables.h b/Turntables.h index 6c15bab..aa089ef 100644 --- a/Turntables.h +++ b/Turntables.h @@ -185,7 +185,7 @@ public: for (Turntable *tto = _firstTurntable; tto != 0; tto = tto->_nextTurntable) if (!tto->isHidden()) { gotOne = true; - StringFormatter::send(stream, F("<i %d %d>\n"), tto->getId(), tto->getPosition()); + StringFormatter::send(stream, F("<I %d %d>\n"), tto->getId(), tto->getPosition()); } return gotOne; } From 8b8e9e491963bcfdd963942e0ae0abfdf1eaf918 Mon Sep 17 00:00:00 2001 From: Asbelos <asbelos@btinternet.com> Date: Thu, 12 Oct 2023 11:07:05 +0100 Subject: [PATCH 83/83] clean result from invalid <JR n> --- DCCEXParser.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7b4836e..04c0b6d 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -729,11 +729,15 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) SENDFLASHLIST(stream,RMFT2::rosterIdList) } else { - const FSH * functionNames= RMFT2::getRosterFunctions(id); - StringFormatter::send(stream,F(" %d \"%S\" \"%S\""), - id, RMFT2::getRosterName(id), - functionNames == NULL ? RMFT2::getRosterFunctions(0) : functionNames); - } + auto rosterName= RMFT2::getRosterName(id); + if (!rosterName) rosterName=F(""); + + auto functionNames= RMFT2::getRosterFunctions(id); + if (!functionNames) functionNames=RMFT2::getRosterFunctions(0); + if (!functionNames) functionNames=F(""); + StringFormatter::send(stream,F(" %d \"%S\" \"%S\""), + id, rosterName, functionNames); + } #endif StringFormatter::send(stream, F(">\n")); return;