Skip to content

Commit

Permalink
Merge pull request #68 from loredan/master
Browse files Browse the repository at this point in the history
New file structure, bringing the project into spec with C++ standards
  • Loading branch information
pyr0ball committed Feb 27, 2020
2 parents c4fc40f + 60a26ad commit c521adc
Show file tree
Hide file tree
Showing 9 changed files with 666 additions and 508 deletions.
Expand Up @@ -84,16 +84,12 @@ update the voltMeterConstant variable in pP_config.h with the correct value
------------------------------------------------------------*/

/* Debug output verbose mode will continuously output sensor readings
rather than waiting for user input */
#define VERBOSE true

// Headers, variables, and functions
#include <Arduino.h>
#include <EEPROM.h>
#include "LightChrono.h"
#include "pP_pins.h"
#include "pP_config.h"
// #include "pP_config.h"
#include "pP_volatile.h"
#include "pP_function.h"
#include "pP_serial.h"
Expand Down
119 changes: 119 additions & 0 deletions firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_cmd.h
@@ -0,0 +1,119 @@
#ifndef PP_CMD_H
#define PP_CMD_H

#include "pP_config.h"
#include "pP_function.h"
#include "EEPROM.h"

/*------------------------------------------------*/

void updateGainFactor(int value)
{
if (value >= 0)
{
GAIN_FACTOR = value;
adjustGain();
EEPROM.put(GAIN_FACTOR_ADDRESS, GAIN_FACTOR);
}
}

/*------------------------------------------------*/

void updateVFol(int value)
{
if (value >= 0)
{
followerThrs = value;
adjustFollow();
EEPROM.put(FOLLOWER_THRESHOLD_ADDRESS, followerThrs);
}
}
/*------------------------------------------------*/

void updateVComp(int value)
{
if (value >= 0)
{
compThrs = value;
adjustComp();
EEPROM.put(COMP_THRESHOLD_ADDRESS, compThrs);
}
}

/*------------------------------------------------*/

void updateLoopDuration(int value)
{
if (value >= 0)
{
LOOP_DUR = value;
EEPROM.put(LOOP_DUR_ADDRESS, LOOP_DUR);
}
}
/*------------------------------------------------*/

void updateTrigDuration(int value)
{
if (value >= 0)
{
TRG_DUR = value;
EEPROM.put(TRG_DUR_ADDRESS, TRG_DUR);
}
}
/*------------------------------------------------*/

void updateHysteresis(int value)
{
if (value >= 0)
{
Hyst = value;
EEPROM.put(HYST_ADDRESS, Hyst);
}
}
/*------------------------------------------------*/

void updateLogic(int value)
{
if (value >= 0)
{
LOGIC = value;
EEPROM.put(LOGIC_ADDRESS, LOGIC);
pulse();
}
}
/*------------------------------------------------*/

void updatePzDet(int value)
{
if (value >= 0)
{
PZDET = value;
EEPROM.put(PZDET_ADDRESS, PZDET);
}
}
/*------------------------------------------------*/

void updateConstant(long value)
{
if (value >= 0)
{
voltMeterConstant = value;
EEPROM.put(VM_CONST_ADDRESS, voltMeterConstant);
}
}

/*------------------------------------------------*/

void updateDebug(int value)
{
if (value > 0)
{
Debug = 1;
}
else if (value == 0)
{
Debug = 0;
}
}

#endif //PP_CMD_H
122 changes: 115 additions & 7 deletions firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_config.cpp
@@ -1,14 +1,122 @@
#include "pP_config.h"
#include "pP_function.h"
#include <EEPROM.h>

int GAIN_FACTOR = GAIN_FACTOR_DEFAULT; // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
int GAIN_FACTOR = GAIN_FACTOR_DEFAULT;
int followerThrs = FOLLOWER_THRESHOLD_DEFAULT;
int compThrs = COMP_THRESHOLD_DEFAULT;
int LOOP_DUR = LOOP_DUR_DEFAULT; // duration of time between ADC checks and other loop functions
int TRG_DUR = TRG_DUR_DEFAULT; // duration of the Z-axis pulse sent, in ms
int Hyst = HYST_DEFAULT; // Hysteresis value for ADC measurements
int LOGIC = LOGIC_DEFAULT; // Trigger output logic (active low or active high)
int PZDET = PZDET_DEFAULT; // Enable/disable piezo connection detection
int LOOP_DUR = LOOP_DUR_DEFAULT;
int TRG_DUR = TRG_DUR_DEFAULT;
int Hyst = HYST_DEFAULT;
int LOGIC = LOGIC_DEFAULT;
int PZDET = PZDET_DEFAULT;
int Debug = 0;
long voltMeterConstant = VM_CONST_DEFAULT;
uint8_t pP_i2c_address = 0xa0;

/*------------------------------------------------*/
void eraseEEPROM() {

setDefaultConfig();

EEPROM.put(GAIN_FACTOR_ADDRESS, GAIN_FACTOR);
EEPROM.put(FOLLOWER_THRESHOLD_ADDRESS, followerThrs);
EEPROM.put(COMP_THRESHOLD_ADDRESS, compThrs);
EEPROM.put(LOOP_DUR_ADDRESS, LOOP_DUR);
EEPROM.put(TRG_DUR_ADDRESS, TRG_DUR);
EEPROM.put(HYST_ADDRESS, Hyst);
EEPROM.put(PZDET_ADDRESS, PZDET);
EEPROM.put(LOGIC_ADDRESS, LOGIC);
EEPROM.put(VM_CONST_ADDRESS, voltMeterConstant);
}

// Restore config from EEPROM, otherwise erase config and write to EEPROM
void restoreConfig() {
int temp;

bool erase = false;

EEPROM.get(GAIN_FACTOR_ADDRESS, temp);
if (temp < 0 || temp > 4) {
erase = true;
} else {
GAIN_FACTOR = temp;
}

EEPROM.get(FOLLOWER_THRESHOLD_ADDRESS, temp);
if (temp < 0 || temp > 5000) {
erase = true;
} else {
followerThrs = temp;
}

EEPROM.get(COMP_THRESHOLD_ADDRESS, temp);
if (temp < 0 || temp > 5000) {
erase = true;
} else {
compThrs = temp;
}

EEPROM.get(LOOP_DUR_ADDRESS, temp);
if (temp < 0 && temp > 1000) {
erase = true;
} else {
LOOP_DUR = temp;
}

EEPROM.get(TRG_DUR_ADDRESS, temp);
if (temp < 0 || temp > 1000) {
erase = true;
} else {
TRG_DUR = temp;
}

EEPROM.get(HYST_ADDRESS, temp);
if (temp < 0 || temp > 1000) {
erase = true;
} else {
Hyst = temp;
}

EEPROM.get(PZDET_ADDRESS, temp);
if (temp < 0 || temp > 1) {
erase = true;
} else {
PZDET = temp;
}

EEPROM.get(LOGIC_ADDRESS, temp);
if (temp < 0 || temp > 1) {
erase = true;
} else {
LOGIC = temp;
}

long longTemp;
EEPROM.get(VM_CONST_ADDRESS, longTemp);
if (longTemp < 1000000L || longTemp > 1200000L) {
erase = true;
} else {
voltMeterConstant = longTemp;
}

if (erase) {
eraseEEPROM();
}

adjustFollow();
adjustComp();
}

void setDefaultConfig() {
GAIN_FACTOR = GAIN_FACTOR_DEFAULT;
followerThrs = FOLLOWER_THRESHOLD_DEFAULT;
compThrs = COMP_THRESHOLD_DEFAULT;
LOOP_DUR = LOOP_DUR_DEFAULT;
TRG_DUR = TRG_DUR_DEFAULT;
Hyst = HYST_DEFAULT;
PZDET = PZDET_DEFAULT;
LOGIC = LOGIC_DEFAULT;
voltMeterConstant = VM_CONST_DEFAULT;
adjustFollow();
adjustComp();
}
48 changes: 13 additions & 35 deletions firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_config.h
Expand Up @@ -5,71 +5,49 @@

#define GAIN_FACTOR_DEFAULT 2 // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
#define GAIN_FACTOR_ADDRESS 0
#if !(defined(GAIN_FACTOR))
extern int GAIN_FACTOR;
#endif
extern int GAIN_FACTOR;

#define FOLLOWER_THRESHOLD_DEFAULT 1450 // Voltage follower default voltage in mV
#define FOLLOWER_THRESHOLD_ADDRESS 4
#if !(defined(followerThrs))
extern int followerThrs;
#endif
extern int followerThrs;

#define COMP_THRESHOLD_DEFAULT 2850 // Comparatore Vref default voltage in mV
#define COMP_THRESHOLD_ADDRESS 8
#if !(defined(compThrs))
extern int compThrs;
#endif
extern int compThrs;

#ifndef InitCount
#define InitCount 6 // Number of times to blink the LED on start
#define InitCount 6 // Number of times to blink the LED on start
#endif

#define LOOP_DUR_DEFAULT 50 // duration of time between ADC checks and other loop functions
#define LOOP_DUR_ADDRESS 12
#if !(defined(LOOP_DUR))
extern int LOOP_DUR;
#endif
extern int LOOP_DUR;

#define TRG_DUR_DEFAULT 20 // duration of the Z-axis pulse sent, in ms
#define TRG_DUR_ADDRESS 16
#if !(defined(TRG_DUR))
extern int TRG_DUR;
#endif
extern int TRG_DUR;

#define HYST_DEFAULT 20
#define HYST_ADDRESS 20
#if !(defined(Hyst))
extern int Hyst; // Hysteresis value for ADC measurements
#endif
extern int Hyst; // Hysteresis value for ADC measurements

#define LOGIC_DEFAULT 1
#define LOGIC_ADDRESS 32
#if !(defined(LOGIC))
extern int LOGIC; // Trigger logic scheme, Active LOW is default
#endif
extern int LOGIC; // Trigger logic scheme, Active LOW is default

#define PZDET_DEFAULT 0
#define PZDET_ADDRESS 26
#if !(defined(PZDET))
extern int PZDET; // Enable or disable piezo connection detection, default is off
#endif
extern int PZDET; // Enable or disable piezo connection detection, default is off

#if !(defined(Debug))
extern int Debug;
#endif
extern int Debug;

#define VM_CONST_ADDRESS 28
#define VM_CONST_DEFAULT 1125300L
#if !(defined(voltMeterConstant))
extern long voltMeterConstant; // For fine tuning input voltage sense
#endif
extern long voltMeterConstant; // For fine tuning input voltage sense

#ifdef I2C_INPUT
#define I2C_SLAVE_ADDRESS 24
#if !(defined(pP_i2c_address))
extern uint8_t pP_i2c_address; // I2C Bus Address
#endif
#define I2C_SLAVE_ADDRESS 24
uint8_t pP_i2c_address = 0xa0; // I2C Bus Address
#endif // I2C_INPUT

void eraseEEPROM();
Expand Down

0 comments on commit c521adc

Please sign in to comment.