Proof of concept encoder analysis. Still to not have a solid gear ratio but it's clear the encoder is very likely 11 PPR. Rotations take ~650 pulses, maybe 660 but it's hard to tell because the gearing makes stopping inconsistent.

This commit is contained in:
Matt McWilliams 2024-01-12 23:33:04 -05:00
parent 45f76500f9
commit 6eb06ca724
1 changed files with 45 additions and 4 deletions

View File

@ -4,7 +4,8 @@
* SKU - JGY-370 * SKU - JGY-370
* DC12V100RPM - SKU-GS00127-05 * DC12V100RPM - SKU-GS00127-05
* *
* Gear ratio: 40:1 * Gear ratio: 40:1(?) 60:1(?)
* 11 PPR Encoder - (!)
* *
* RedMotor power + (exchange can control rotating and reversing) * RedMotor power + (exchange can control rotating and reversing)
* BlackCoding power- negative (3.3-5V) polarity cannot be wrong * BlackCoding power- negative (3.3-5V) polarity cannot be wrong
@ -25,24 +26,64 @@
#define MOTORB 11 #define MOTORB 11
volatile int posi = 0; // specify posi as volatile volatile int posi = 0; // specify posi as volatile
const long maxTime = 10000;
const int maxPulses = 660;
const int speed = 40;
volatile long start = 0;
volatile bool done = false;
volatile bool stop = false;
volatile int incoming;
volatile float rpm;
void setup() { void setup() {
Serial.begin(9600); Serial.begin(57600);
Serial.flush();
pinMode(ENCA, INPUT); pinMode(ENCA, INPUT);
pinMode(ENCB, INPUT); pinMode(ENCB, INPUT);
pinMode(MOTORA, OUTPUT);
pinMode(MOTORB, OUTPUT);
attachInterrupt(digitalPinToInterrupt(ENCA), readEncoder,RISING); attachInterrupt(digitalPinToInterrupt(ENCA), readEncoder,RISING);
} }
void loop() { void loop() {
int pos;
if (Serial.available() > 0) {
incoming = Serial.read();
start = -1;
posi = 0;
done = false;
stop = false;
}
// Read the position in an atomic block to avoid a potential // Read the position in an atomic block to avoid a potential
// misread if the interrupt coincides with this code running // misread if the interrupt coincides with this code running
// see: https://www.arduino.cc/reference/en/language/variables/variable-scope-qualifiers/volatile/ // see: https://www.arduino.cc/reference/en/language/variables/variable-scope-qualifiers/volatile/
int pos = 0;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) { ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
pos = posi; pos = posi;
} }
Serial.println(pos); if (abs(pos) == maxPulses) {
stop = true;
}
if (start == -1) {
delay(1000);
analogWrite(MOTORA, speed);
digitalWrite(MOTORB, LOW);
start = millis();
} else if ((stop || millis() - start >= maxTime) && !done) {
digitalWrite(MOTORA, LOW);
digitalWrite(MOTORB, LOW);
Serial.print("Final: ");
Serial.println(pos);
Serial.print("Time: ");
Serial.println(millis() - start);
rpm = (float) 60000 / (float) (millis() - start);
Serial.print("RPM: ");
Serial.println(rpm);
done = true;
}
} }
void readEncoder(){ void readEncoder(){