Did current sweeps for some dists, might do more
This commit is contained in:
1
TwoCellMagChar/CalibConsts.hpp
Symbolic link
1
TwoCellMagChar/CalibConsts.hpp
Symbolic link
@@ -0,0 +1 @@
|
|||||||
|
../loadCellCode/CalibConsts.hpp
|
||||||
BIN
TwoCellMagChar/MagCharTrial.xlsx
Normal file
BIN
TwoCellMagChar/MagCharTrial.xlsx
Normal file
Binary file not shown.
79
TwoCellMagChar/TwoCellMagChar.ino
Normal file
79
TwoCellMagChar/TwoCellMagChar.ino
Normal file
@@ -0,0 +1,79 @@
|
|||||||
|
#include "HX711.h"
|
||||||
|
#include "CalibConsts.hpp"
|
||||||
|
|
||||||
|
HX711 c0, c1;
|
||||||
|
|
||||||
|
// adjust pins if needed.
|
||||||
|
#define c0Data 2
|
||||||
|
#define c0Clock 3
|
||||||
|
#define c1Data 4
|
||||||
|
#define c1Clock 5
|
||||||
|
|
||||||
|
#define DIR0 7
|
||||||
|
#define PWM0 6
|
||||||
|
#define DIR1 8
|
||||||
|
#define PWM1 9
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
pinMode(DIR0, OUTPUT);
|
||||||
|
pinMode(PWM0, OUTPUT);
|
||||||
|
pinMode(DIR1, OUTPUT);
|
||||||
|
pinMode(PWM1, OUTPUT);
|
||||||
|
|
||||||
|
Serial.begin(115200);
|
||||||
|
Serial.println();
|
||||||
|
Serial.println(__FILE__);
|
||||||
|
Serial.print("HX711_LIB_VERSION: ");
|
||||||
|
Serial.println(HX711_LIB_VERSION);
|
||||||
|
Serial.println();
|
||||||
|
|
||||||
|
c0.begin(c0Data, c0Clock);
|
||||||
|
c0.set_offset(OFFSET0);
|
||||||
|
c0.set_scale(SCALE0);
|
||||||
|
|
||||||
|
c1.begin(c1Data, c1Clock);
|
||||||
|
c1.set_offset(OFFSET1);
|
||||||
|
c1.set_scale(SCALE1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
while (Serial.available()) Serial.read();
|
||||||
|
Serial.println("Enter any key to begin reading");
|
||||||
|
while (!Serial.available());
|
||||||
|
Serial.println("Reading Load Cells (Mean over 10 Readings)");
|
||||||
|
float c0Avgs[11] = {0};
|
||||||
|
float c1Avgs[11] = {0};
|
||||||
|
uint8_t ind = 0;
|
||||||
|
|
||||||
|
for (int16_t i = -250; i < 255; i+=50) {
|
||||||
|
Serial.print("Running PWM: ");
|
||||||
|
Serial.println(i);
|
||||||
|
digitalWrite(DIR0, i >= 0);
|
||||||
|
digitalWrite(DIR1, i >= 0);
|
||||||
|
analogWrite(PWM0, abs(i));
|
||||||
|
analogWrite(PWM1, abs(i));
|
||||||
|
delay(200);
|
||||||
|
for (uint8_t j = 0; j < 10; j++) c0Avgs[ind] += c0.get_units();
|
||||||
|
c0Avgs[ind] /= 10;
|
||||||
|
for (uint8_t j = 0; j < 10; j++) c1Avgs[ind] += c1.get_units();
|
||||||
|
c1Avgs[ind] /= 10;
|
||||||
|
ind++;
|
||||||
|
}
|
||||||
|
|
||||||
|
digitalWrite(DIR0, 0);
|
||||||
|
digitalWrite(DIR1, 0);
|
||||||
|
digitalWrite(PWM0, 0);
|
||||||
|
digitalWrite(PWM1, 0);
|
||||||
|
|
||||||
|
Serial.println("Average Values:");
|
||||||
|
for (uint8_t i = 0; i < 11; i++) {
|
||||||
|
Serial.print("PWM ");
|
||||||
|
Serial.print((int) -250+i*50);
|
||||||
|
Serial.print(" - Cell 0: ");
|
||||||
|
Serial.print(c0Avgs[i]);
|
||||||
|
Serial.print("g, Cell 1: ");
|
||||||
|
Serial.print(c1Avgs[i]);
|
||||||
|
Serial.println("g");
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,7 +1,10 @@
|
|||||||
#ifndef CONSTANTS_H
|
#ifndef CONSTANTS_H
|
||||||
#define CONSTANTS_H
|
#define CONSTANTS_H
|
||||||
|
|
||||||
#define OFFSET 19532
|
#define OFFSET0 19532
|
||||||
#define SCALE 108.633064
|
#define SCALE0 108.633064
|
||||||
|
|
||||||
|
#define OFFSET1 164066
|
||||||
|
#define SCALE1 102.531166
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
@@ -11,8 +11,8 @@
|
|||||||
HX711 myScale;
|
HX711 myScale;
|
||||||
|
|
||||||
// adjust pins if needed.
|
// adjust pins if needed.
|
||||||
uint8_t dataPin = 2;
|
uint8_t dataPin = 4;
|
||||||
uint8_t clockPin = 3;
|
uint8_t clockPin = 5;
|
||||||
|
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
@@ -25,8 +25,8 @@ void setup()
|
|||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
myScale.begin(dataPin, clockPin);
|
myScale.begin(dataPin, clockPin);
|
||||||
myScale.set_offset(OFFSET);
|
myScale.set_offset(OFFSET1);
|
||||||
myScale.set_scale(SCALE);
|
myScale.set_scale(SCALE1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
|
|||||||
Reference in New Issue
Block a user