PaulStoffregen / FreqMeasureMulti

Measures the elapsed time during each cycle of up to 8 input frequencies.
34 stars 9 forks source link

begin() overrides pull up pinMode #9

Open jacobjennings opened 5 years ago

jacobjennings commented 5 years ago

Description

.begin(…) removes pullup value. Calling pinmode(pin, INPUT_PULLUP) after begin(…) breaks measurement

Steps To Reproduce Problem

// These two lines of code will result in a pullup, but .available() is never true afterwards: gFreqMeasure0.begin(kPin_FreqMeasureMulti0); pinMode(kPin_FreqMeasureMulti0, INPUT_PULLUP);

// This works with an external pullup, but does not allow for internal pullup gFreqMeasure0.begin(kPin_FreqMeasureMulti0);

Hardware & Software

Board Teensy 3.6 Shields / modules used None Arduino IDE version 1.8.9 Teensyduino version 1.46 Operating system & version Mac OS Any other software or hardware?

Arduino Sketch

include

include

include

volatile unsigned long count=0; unsigned long prior_count=0;

// Pin selections

// These SPI pins 11 and 12 don't have PWM etc, so we aren't wasting PWM pins. static uint8_t kPin_SPI0_MOSI = 11; static uint8_t kPin_SPI0_MISO = 12;

// Using 27 instead of 13 leaves 13 open for freq counting static uint8_t kPin_SPI0_SCK = 27;

// 15 is a CS0 pin which is not also PWM. static uint8_t kPin_SPI0_CS = 15;

// Let's reserve as much i2s as possible so we can run multiple chips // with the same addresses. Accelerometer module I have can change its // address, so 2 addresses per chip * 4 i2s buses = 8 same-chips

// I2S0: Non-pwm pin selections static uint8_t kPin_I2S0_SCL = 19; static uint8_t kPin_I2S0_SDA = 18;

// All I2S1 pins overlap with PWM. static uint8_t kPin_I2S1_SCL = 37; static uint8_t kPin_I2S1_SDA = 38;

// I2S2 - one PWM stomped by SDA. static uint8_t kPin_I2S2_SCL = 26; static uint8_t kPin_I2S2_SDA = 4;

// I2S3 on the back side doesn't overlap with PWM. static uint8_t kPin_I2S3_SCL = 57; static uint8_t kPin_I2S3_SDA = 56;

// Remaining 12 PWM pins: static uint8_t kPin_PWM0 = 2; static uint8_t kPin_PWM1 = 3; static uint8_t kPin_PWM2 = 2; static uint8_t kPin_PWM3 = 7; static uint8_t kPin_PWM4 = 8; static uint8_t kPin_PWM5 = 29; static uint8_t kPin_PWM6 = 30; static uint8_t kPin_PWM7 = 17; static uint8_t kPin_PWM8 = 16; static uint8_t kPin_PWM9 = 14; static uint8_t kPin_PWM10 = 36; static uint8_t kPin_PWM11 = 35;

// General use digital I/O in order of least interesting first (avoid reserving pins that do other things) static uint8_t kPin_DIO0 = 24; static uint8_t kPin_DIO1 = 25; static uint8_t kPin_DIO2 = 28; static uint8_t kPin_DIO3 = 31; static uint8_t kPin_DIO4 = 32; static uint8_t kPin_DIO5 = 0; // rx1 static uint8_t kPin_DIO6 = 1; // tx1 static uint8_t kPin_DIO7 = 39; static uint8_t kPin_DIO8 = 34; static uint8_t kPin_DIO9 = 33; // Back side static uint8_t kPin_DIO10 = 40; static uint8_t kPin_DIO11 = 41; static uint8_t kPin_DIO12 = 42; static uint8_t kPin_DIO13 = 43; static uint8_t kPin_DIO14 = 44; static uint8_t kPin_DIO15 = 45; static uint8_t kPin_DIO16 = 46; static uint8_t kPin_DIO17 = 47; static uint8_t kPin_DIO18 = 48; static uint8_t kPin_DIO19 = 49; static uint8_t kPin_DIO20 = 50; static uint8_t kPin_DIO21 = 51; static uint8_t kPin_DIO22 = 52; static uint8_t kPin_DIO23 = 53; static uint8_t kPin_DIO24 = 54; static uint8_t kPin_DIO25 = 55;

// Pin 13 is special, leave it alone. static uint8_t kPin_Special13 = 13;

// FreqMeasureMulti library pins. static uint8_t kPin_FreqMeasureMulti0 = 22; // also pwm static uint8_t kPin_FreqMeasureMulti1 = 23; // also pwm static uint8_t kPin_FreqMeasureMulti2 = 9; // also pwm static uint8_t kPin_FreqMeasureMulti3 = 10; // also pwm static uint8_t kPin_FreqMeasureMulti4 = 6; // also pwm static uint8_t kPin_FreqMeasureMulti5 = 20; // also pwm static uint8_t kPin_FreqMeasureMulti6 = 21; // also pwm static uint8_t kPin_FreqMeasureMulti7 = 5; // also pwm

//

static uint8_t kNumberOfHalfRevolutionsToAverage = 35;

FreqMeasureMulti gFreqMeasure0; double gFreqMeasureSum0; int gFreqMeasureCount0; float gFreqMeasureRPM0;

FreqMeasureMulti gFreqMeasure1; double gFreqMeasureSum1; int gFreqMeasureCount1; float gFreqMeasureRPM1;

FreqMeasureMulti gFreqMeasure2; double gFreqMeasureSum2; int gFreqMeasureCount2; float gFreqMeasureRPM2;

FreqMeasureMulti gFreqMeasure3; double gFreqMeasureSum3; int gFreqMeasureCount3; float gFreqMeasureRPM3;

FreqMeasureMulti gFreqMeasure4; double gFreqMeasureSum4; int gFreqMeasureCount4; float gFreqMeasureRPM4;

FreqMeasureMulti gFreqMeasure5; double gFreqMeasureSum5; int gFreqMeasureCount5; float gFreqMeasureRPM5;

FreqMeasureMulti gFreqMeasure6; double gFreqMeasureSum6; int gFreqMeasureCount6; float gFreqMeasureRPM6;

FreqMeasureMulti gFreqMeasure7; double gFreqMeasureSum7; int gFreqMeasureCount7; float gFreqMeasureRPM7;

void processFreqMeasure(FreqMeasureMulti freqMeasureMulti, double sum, int *count);

void pulse() { count = count + 1; }

void setup() { SPI.setMOSI(kPin_SPI0_MOSI); SPI.setMISO(kPin_SPI0_MISO); SPI.setSCK(kPin_SPI0_SCK);

Serial.begin(57600);

gFreqMeasure0.begin(kPin_FreqMeasureMulti0); pinMode(kPin_FreqMeasureMulti0, INPUT_PULLUP);

gFreqMeasure1.begin(kPin_FreqMeasureMulti1); // pinMode(kPin_FreqMeasureMulti1, INPUT_PULLUP);

gFreqMeasure2.begin(kPin_FreqMeasureMulti2); // pinMode(kPin_FreqMeasureMulti2, INPUT_PULLUP);

gFreqMeasure3.begin(kPin_FreqMeasureMulti3); pinMode(kPin_FreqMeasureMulti3, INPUT_PULLUP);

gFreqMeasure4.begin(kPin_FreqMeasureMulti4); pinMode(kPin_FreqMeasureMulti4, INPUT_PULLUP);

gFreqMeasure5.begin(kPin_FreqMeasureMulti5); pinMode(kPin_FreqMeasureMulti5, INPUT_PULLUP);

gFreqMeasure6.begin(kPin_FreqMeasureMulti6); pinMode(kPin_FreqMeasureMulti6, INPUT_PULLUP);

gFreqMeasure7.begin(kPin_FreqMeasureMulti7); pinMode(kPin_FreqMeasureMulti7, INPUT_PULLUP);

pinMode(kPin_PWM0, OUTPUT); pinMode(kPin_PWM1, OUTPUT); pinMode(kPin_PWM2, OUTPUT); pinMode(kPin_PWM3, OUTPUT); pinMode(kPin_PWM4, OUTPUT); pinMode(kPin_PWM5, OUTPUT); pinMode(kPin_PWM6, OUTPUT); pinMode(kPin_PWM7, OUTPUT); pinMode(kPin_PWM8, OUTPUT); pinMode(kPin_PWM9, OUTPUT);

// todo: reconfigure according to freqs analogWrite(kPin_PWM0, 150); analogWrite(kPin_PWM1, 150); analogWrite(kPin_PWM2, 150); analogWrite(kPin_PWM3, 150); analogWrite(kPin_PWM4, 150); analogWrite(kPin_PWM5, 150); analogWrite(kPin_PWM6, 150); analogWrite(kPin_PWM7, 150); analogWrite(kPin_PWM8, 150); analogWrite(kPin_PWM9, 150);

// attachInterrupt(digitalPinToInterrupt(3), pulse, RISING); // NVIC_SET_PRIORITY(IRQ_PORTA, 0); }

void loop() { unsigned long new_count = count; if (new_count != prior_count) { Serial.println(new_count); prior_count = new_count; }

processFreqMeasure(&gFreqMeasure0, &gFreqMeasureSum0, &gFreqMeasureCount0, &gFreqMeasureFreq0, 0); processFreqMeasure(&gFreqMeasure1, &gFreqMeasureSum1, &gFreqMeasureCount1, &gFreqMeasureFreq1, 1); processFreqMeasure(&gFreqMeasure2, &gFreqMeasureSum2, &gFreqMeasureCount2, &gFreqMeasureFreq2, 2); processFreqMeasure(&gFreqMeasure3, &gFreqMeasureSum3, &gFreqMeasureCount3, &gFreqMeasureFreq3, 3); processFreqMeasure(&gFreqMeasure4, &gFreqMeasureSum4, &gFreqMeasureCount4, &gFreqMeasureFreq4, 4); processFreqMeasure(&gFreqMeasure5, &gFreqMeasureSum5, &gFreqMeasureCount5, &gFreqMeasureFreq5, 5); processFreqMeasure(&gFreqMeasure6, &gFreqMeasureSum6, &gFreqMeasureCount6, &gFreqMeasureFreq6, 6); processFreqMeasure(&gFreqMeasure7, &gFreqMeasureSum7, &gFreqMeasureCount7, &gFreqMeasureFreq7, 7); }

void processFreqMeasure(FreqMeasureMulti freqMeasureMulti, double sum, int count, float freq, int fanNumber) { if (freqMeasureMulti->available()) { // average several reading together sum = sum + freqMeasureMulti->read(); count = count + 1; if (count > kNumberOfHalfRevolutionsToAverage) { freq = freqMeasureMulti->countToFrequency(sum / count); Serial.print(fanNumber); Serial.print(": "); Serial.println(freq); sum = 0; *count = 0; } } }

Errors or Incorrect Output

If you see any errors or incorrect output, please show it here. Please use copy & paste to give an exact copy of the message. Details matter, so please show (not merely describe) the actual message or error exactly as it appears.

Theremingenieur commented 5 years ago

That's unfortunately inherent in the Teensy3 and Teensy LC hardware. The INPUT_PULLUP configuration applies only to GPIO pins. But the FreqMeasureMulti library uses FTM0 which is a so-called flextimer. When routing the signal from the pin to this timer, the internal pin MUX of the CPU disconnects it from the GPIO engine. If you need pull up resistors on pins which are used be FreqMeasure or FreqMeasureMulti, you'll have to add these externally.