General

Better code example for Brushless DC Motor with Encoder 12V 159RPM

userHead anonymous 2020-03-08 02:51:26 10836 Views1 Replies
Hello DFRobot,

I have a number of your brushless gear motors and I am working toward making a PID loop for RPM control for robotics projects.

I began using your example code on the website but there is a fatal flaw with using pulseIn when the motor is at a stop (zero RPM) since the code waits indefinitely before allowing input of a value through the serial terminal.

I have written a good example of using interrupts from the Frequency Generator (FG) signal on the motor. I have produced very tight code which should be adaptable toward your customers' applications.

The only thing required, other than an Arduino, is the Circular Buffer library which is an optimized array handler: https://github.com/rlogiacco/CircularBuffer

It is possible this is optional. For performance reasons, I am including it.

Also removed is the auto reversing since that causes conditions which are hard on the motor.

Once I am done with the PID loop, I will include that example, as well.
Code: Select all
/*
 BrushlessInturrupt - Input PWM strength in serial terminal to get RPM out.
 
 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.
 
 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;

void setup() {
  pinMode(11, OUTPUT); //PWM PIN 11  with PWM wire
  analogWrite(11, 0);
  Serial.begin(115200);

//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() {
  if (Serial.available())  {
    analogWrite(11, Serial.parseInt());  //input speed (must be int)
  }

//Using average pulse width to divide a constant for RPM calculation  
  Serial.print(111111/averagePulse());
  Serial.println(" r/min");
  delay(200);
}
[/code]