rlogiacco / CircularBuffer

Arduino circular buffer library
GNU Lesser General Public License v3.0
312 stars 85 forks source link

Code working on Arduino (Atmel AVR) not working on Teensy 3.2 #30

Closed coreyfro closed 3 years ago

coreyfro commented 4 years ago

Hello,

I have a bit of code that works just fine on an Arduino UNO, but when I try running the same code on the Teensy 3.2, it compiles, but I get erroneous data from the ring buffer. I am considering using STL::Vector but I thought I would ping you in case the issue report would help or if there was something obviously wrong in my code.

Thanks!

/*
 BrushlessPID - Input desired RPM serial plotter, PWM is calculated through PID

 Code Example for brushless gearmotors from Shenzhen Chihai Motor C O, Ltd.
 https://chihaimotor.en.alibaba.com/productgrouplist-810760854/brushless_DC_motor.html
 https://wiki.dfrobot.com/FIT0441_Brushless_DC_Motor_with_Encoder_12V_159RPM

 Uses interrupts to count pulses from the Frequency Generator (FG) signal
 from the motor.  Uses circular buffer to record nine timestamps from
 pulses to make an average from eight pulse width measurements.  Uses PID
 Library to reach desired RPM.

 Copyright (c) 2020 Corey McGuire.
 This program is free software: you can redistribute it and/or modify
 it under the terms of the GNU Lesser General Public License as 
 published by the Free Software Foundation, either version 3 of the 
 License, or (at your option) any later version.
 This program is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FIT NESS 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 this program.  If not, see <http://www.gnu.org/licenses/>.
*/

// Using Circular Buffer library : https://github.com/rlogiacco/CircularBuffer
#define CIRCULAR_BUFFER_INT_SAFE
#include <CircularBuffer.h>

//Creating an array of length 9, one more than we will average since we must
//find the difference between 9 timestaps to get 8 values
CircularBuffer<unsigned long, 9> timings;

// Using Arduino-PID-Library : https://github.com/br3ttb/Arduino-PID-Library
#include <PID_v1.h>

double Setpoint ;                 // will be the desired RPM
double Input;                     // Frequency Generator (FG) signal from motor
double Output ;                   // Motor PWM signal to motor

// PID parameters : adjust these to get desired speed.
double Kp=.01, Ki=2, Kd=.01;

PID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, DIRECT); //create PID instance 

void setup()
{
  pinMode(11, OUTPUT); //PWM PIN 11 with PWM wire
  analogWrite(11, 0);
  Serial.begin(9600);   
    Setpoint = 75;                // Hardcode the target RPM

  myPID.SetMode(AUTOMATIC);       //Turn the PID on
  myPID.SetTunings(Kp, Ki, Kd);   //Adjust PID values

  //Attach interrupt handler to pin 2. Pins 2 and 3 have dedicated inturupts
  //More info, here : http://www.gammon.com.au/forum/?id=11488
  attachInterrupt (digitalPinToInterrupt (2), pulseRead, CHANGE);
}

//Function called on interrupt. Using a circular buffer in a FIFO fashion,
//we are storing timestamps to be calculated outside the function to keep
//the interrupt as short as possible.
void pulseRead() {
  timings.unshift(micros());
}

//Function for calculating average time between pulses. We disable inturrups
//for the brief time we are calculating the average because an inturrupt
//durring the calculation could cause a value to be recorded twice resulting
//in an errant "0" pulse length, ruining our average. There is little chance
//of this measure causing errent pulse length because the calculation should
//be so fast, that if the motor generates a pulse during this time, it will
//still be "HIGH" by the time the calculation exits and, thus, the interrupt
//is triggered.

float averagePulse(){
  long sum=0;
  noInterrupts ();
  for (int j=1 ; j < timings.size();j++){
    sum += timings[j-1]-timings[j];
  }
  interrupts ();
  return sum /(timings.size()-1.0);
}

void loop()
{
  // Read the value calculated from the average pulse width from Frequency
  // Generator (FG) to estimate RPM.
  Input = 111111/averagePulse();
  //PID calculation
  myPID.Compute();
  //Write the output (PWM) as calculated by the PID function
  analogWrite(11,Output); //LED is set to digital 3 this is a pwm pin. 
  //Send data by serial for plotting 
  Serial.print(Input);
  Serial.print(" ");
  Serial.println(Output);
  Serial.print(" ");  
  Serial.println(Setpoint);
  Serial.print(" ");
    if (Serial.available())  {
   Setpoint = Serial.parseInt();
    }
}

Output on Arduino 65.47 27.73 75.00 60.06 35.30 75.00

Output on Teensy nan nan 75.00 nan nan 75.00

coreyfro commented 4 years ago

I should note that I know this is a problem with the buffer because if I print it's size to serial, it says "0"

rlogiacco commented 4 years ago

Hi, and thank you for providing this feedback. First of all, I suggest enabling the support for interrupts via the CIRCULAR_BUFFER_INT_SAFE macro flag because you are using the library within an interrupt-driven code.

After that, if the problem still persist, as I don't have a teensy 3.2 to play with, I have only two advises left:

  1. enable the CIRCULAR_BUFFER_DEBUG macro flag and use the additional debug function to verify the contents of the buffer after the insertion
  2. mail me a teensy 3.2 to play with 😄
rlogiacco commented 3 years ago

Closing as no feedback