removed last remaining float, cleaned up unused vars
This commit is contained in:
parent
f745940904
commit
20454e7ffb
5 changed files with 43 additions and 58 deletions
|
|
@ -39,13 +39,11 @@ To change comparator trigger high threshold: VCOMP [float value]
|
|||
|
||||
|
||||
These commands should be wrapped in this format:
|
||||
<CMD, INT, FLOAT>
|
||||
|
||||
You must include the unused variable for each instance.
|
||||
<CMD, INT>
|
||||
|
||||
Examples:
|
||||
<GAIN_F, 3, 0.00>
|
||||
<VADJ, 0, 2.35>
|
||||
<GAIN_F, 3> <~ set gain factor to index 3 (6x)
|
||||
<VADJ, 2350> <~ set the vref floor to 2.35V
|
||||
|
||||
*Note for Gain Factor:
|
||||
The gain STATE is representative of these values:
|
||||
|
|
@ -63,13 +61,15 @@ int LOOP_DUR = 50; // duration of time between ADC checks and other loop
|
|||
int TRG_DUR = 20; // duration of the Z-axis pulse sent, in ms
|
||||
#define senseThrs 1450
|
||||
#define compThrs 2850
|
||||
int dAdjFac = 1; // adjustment divider. Higher number will cause the DAC output to adjust more slowly.
|
||||
int Hyst = 20; // Hysteresis value for ADC measurements
|
||||
|
||||
/*------------------------------------------------------------*/
|
||||
|
||||
// Debug output toggle. Uncomment to enable
|
||||
#define DEBUG true
|
||||
|
||||
/* Debug output verbose mode will continuously output sensor readings
|
||||
rather than waiting for user input */
|
||||
//#define VERBOSE true
|
||||
|
||||
// Headers, variables, and functions
|
||||
|
|
@ -79,41 +79,39 @@ int Hyst = 20; // Hysteresis value for ADC measurements
|
|||
#include "pP_serial.h"
|
||||
|
||||
// i2c input toggle. Uncomment to enable
|
||||
//#define I2C true
|
||||
#define I2C true
|
||||
#ifdef I2C
|
||||
#include "pP_i2c.h"
|
||||
#endif
|
||||
|
||||
void setup() {
|
||||
pinMode(TRG_OUT, OUTPUT); // declare the Trigger as as OUTPUT
|
||||
pinMode(TRG_OUT, OUTPUT); // declare the Trigger as as OUTPUT
|
||||
pinMode(ERR_LED, OUTPUT);
|
||||
pinMode(Z_TRG, INPUT_PULLUP); // declare z-sense input with pullup
|
||||
pinMode(Z_TRG, INPUT_PULLUP); // declare z-sense input with pullup
|
||||
pinMode(V_FOLLOW_PIN, INPUT);
|
||||
pinMode(VCOMP_SENSE_PIN, INPUT);
|
||||
pinMode(GADJ_R0, INPUT); // declare input to break pull to ground
|
||||
pinMode(GADJ_R1, INPUT); // declare input to break pull to ground
|
||||
pinMode(GADJ_R2, INPUT); // declare input to break pull to ground
|
||||
pinMode(GADJ_R3, INPUT); // declare input to break pull to ground
|
||||
pinMode(GADJ_R0, INPUT); // declare input to set high impedance
|
||||
pinMode(GADJ_R1, INPUT); // declare input to set high impedance
|
||||
pinMode(GADJ_R2, INPUT); // declare input to set high impedance
|
||||
pinMode(GADJ_R3, INPUT); // declare input to set high impedance
|
||||
Serial.begin(9600);
|
||||
|
||||
attachInterrupt(digitalPinToInterrupt(Z_TRG), pulse, FALLING);
|
||||
|
||||
Serial.println("Initializing Pyr0-Piezo Sensor...");
|
||||
|
||||
}
|
||||
|
||||
|
||||
/*------------------------------------------------*/
|
||||
|
||||
void loop() {
|
||||
|
||||
// Blink LED's on init
|
||||
if (BlinkCount > 0) {
|
||||
BlinkState = !BlinkState;
|
||||
digitalWrite(ERR_LED, BlinkState);
|
||||
digitalWrite(TRG_OUT, BlinkState);
|
||||
delay(LOOP_DUR);
|
||||
--BlinkCount;
|
||||
BlinkState = !BlinkState;
|
||||
digitalWrite(ERR_LED, BlinkState);
|
||||
digitalWrite(TRG_OUT, BlinkState);
|
||||
delay(LOOP_DUR);
|
||||
--BlinkCount;
|
||||
}
|
||||
|
||||
// Get Serial Input
|
||||
|
|
@ -136,7 +134,7 @@ void loop() {
|
|||
}
|
||||
|
||||
// Voltage Comparator adjustment
|
||||
if (VLast > Hyst || VLast > -Hyst) {
|
||||
if (VLast > Hyst || VLast < -Hyst) {
|
||||
adjustComp();
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -57,15 +57,14 @@ long readVcc() {
|
|||
/*------------------------------------------------*/
|
||||
|
||||
void adjustFollow() {
|
||||
/* Compares diffs of threshold vs read value
|
||||
if positive, adjusts the follower to within
|
||||
the range set above*/
|
||||
|
||||
ADJ_FOLLOW = (senseInt / 4);
|
||||
/* Compares diffs of threshold vs read value
|
||||
if positive, adjusts the follower to within
|
||||
the range set above*/
|
||||
ADJ_FOLLOW = (senseInt / 4);
|
||||
|
||||
// Analog output (PWM) of duty cycle
|
||||
analogWrite(V_FOL_PWM, ADJ_FOLLOW);
|
||||
}
|
||||
// Analog output (PWM) of duty cycle
|
||||
analogWrite(V_FOL_PWM, ADJ_FOLLOW);
|
||||
}
|
||||
|
||||
/*------------------------------------------------*/
|
||||
|
||||
|
|
|
|||
|
|
@ -1,5 +1,14 @@
|
|||
#include <Wire.h>
|
||||
|
||||
/*------------------------------------------------*/
|
||||
#ifdef I2C
|
||||
void i2cReply() {
|
||||
if (serialIncoming) {
|
||||
Wire.write("OK");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*------------------------------------------------*/
|
||||
|
||||
#ifdef I2C
|
||||
|
|
@ -14,12 +23,3 @@
|
|||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*------------------------------------------------*/
|
||||
#ifdef I2C
|
||||
void i2cReply() {
|
||||
if (serialIncoming) {
|
||||
Wire.write("OK");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
@ -12,9 +12,6 @@ void parseData() {
|
|||
|
||||
strtokIndx = strtok(NULL, ","); // this continues where the previous call left off
|
||||
serialInt = atoi(strtokIndx); // convert this part to an integer
|
||||
|
||||
strtokIndx = strtok(NULL, ",");
|
||||
serialFloat = atof(strtokIndx); // convert this part to a float
|
||||
|
||||
}
|
||||
/*------------------------------------------------*/
|
||||
|
|
@ -84,7 +81,7 @@ void updateGainFactor() {
|
|||
|
||||
void updateVComp() {
|
||||
if (serialInt >= 0) {
|
||||
compInt = (serialFloat * 1024) / Vin;
|
||||
compInt = serialInt;
|
||||
//senseInt = compInt; // syncing these params til #24 is fixed
|
||||
}
|
||||
}
|
||||
|
|
@ -92,7 +89,7 @@ void updateVComp() {
|
|||
|
||||
void updateVAdj() {
|
||||
if (serialInt >= 0) {
|
||||
senseInt = (serialFloat * 1024) / Vin;
|
||||
senseInt = serialInt;
|
||||
//compInt = senseInt; // syncing these params til #24 is fixed
|
||||
}
|
||||
}
|
||||
|
|
@ -105,8 +102,6 @@ void updateHysteresis() {
|
|||
}
|
||||
/*------------------------------------------------*/
|
||||
|
||||
/*------------------------------------------------*/
|
||||
|
||||
void updateParams() {
|
||||
if (strcmp(serialMessageIn, "TRG_D") == 0) {
|
||||
updateTrigDuration();
|
||||
|
|
@ -120,8 +115,13 @@ void updateParams() {
|
|||
else if (strcmp(serialMessageIn, "VADJ") == 0) {
|
||||
updateVAdj();
|
||||
}
|
||||
else if (strcmp(serialMessageIn, "HYST") == 0) {
|
||||
updateHysteresis();
|
||||
}
|
||||
}
|
||||
|
||||
/*------------------------------------------------*/
|
||||
|
||||
void serialInput() {
|
||||
|
||||
// receive data from Serial and save it into inputBuffer
|
||||
|
|
@ -152,12 +152,6 @@ void serialReply() {
|
|||
Serial.print(" ");
|
||||
Serial.println(compInt);
|
||||
|
||||
Serial.print("Diff");
|
||||
Serial.print(" ");
|
||||
Serial.print(diffCompL);
|
||||
Serial.print(" ");
|
||||
Serial.println(diffCompH);
|
||||
|
||||
Serial.print("Amp Sense:");
|
||||
Serial.print(VAdj);
|
||||
Serial.print(" ");
|
||||
|
|
@ -166,11 +160,6 @@ void serialReply() {
|
|||
Serial.print(" ");
|
||||
Serial.println(senseInt);
|
||||
|
||||
Serial.print("Diff");
|
||||
Serial.print(" ");
|
||||
Serial.print(diffAdjL);
|
||||
Serial.print(" ");
|
||||
Serial.println(diffAdjH);
|
||||
#endif
|
||||
|
||||
Serial.print("Delay:");
|
||||
|
|
|
|||
|
|
@ -37,5 +37,4 @@ byte bytesRecvd = 0;
|
|||
bool readInProgress = false;
|
||||
bool serialIncoming = false;
|
||||
char serialMessageIn[buffSize] = {0};
|
||||
int serialInt = 0;
|
||||
float serialFloat = 0.00;
|
||||
int serialInt = 0;
|
||||
Loading…
Reference in a new issue