Merge pull request #70 from loredan/master
This should fix #2 & #22 Thanks for all the hard work @loredan !
This commit is contained in:
commit
ce91ff63dd
30 changed files with 960 additions and 598 deletions
|
|
@ -0,0 +1,3 @@
|
||||||
|
BasedOnStyle: LLVM
|
||||||
|
ColumnLimit: 200
|
||||||
|
AllowShortFunctionsOnASingleLine: false
|
||||||
|
|
@ -32,15 +32,15 @@
|
||||||
#endif
|
#endif
|
||||||
#include "LightChrono.h"
|
#include "LightChrono.h"
|
||||||
|
|
||||||
LightChrono::LightChrono()
|
LightChrono::LightChrono() {
|
||||||
{
|
|
||||||
restart();
|
restart();
|
||||||
}
|
}
|
||||||
|
|
||||||
void LightChrono::start() { restart(); }
|
void LightChrono::start() {
|
||||||
|
restart();
|
||||||
|
}
|
||||||
|
|
||||||
void LightChrono::restart()
|
void LightChrono::restart() {
|
||||||
{
|
|
||||||
_startTime = millis();
|
_startTime = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -48,8 +48,7 @@ LightChrono::chrono_t LightChrono::elapsed() const {
|
||||||
return (millis() - _startTime);
|
return (millis() - _startTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool LightChrono::hasPassed(LightChrono::chrono_t timeout) const
|
bool LightChrono::hasPassed(LightChrono::chrono_t timeout) const {
|
||||||
{
|
|
||||||
return (elapsed() >= timeout);
|
return (elapsed() >= timeout);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -58,10 +57,7 @@ bool LightChrono::hasPassed(LightChrono::chrono_t timeout, bool restartIfPassed)
|
||||||
if (restartIfPassed)
|
if (restartIfPassed)
|
||||||
restart();
|
restart();
|
||||||
return true;
|
return true;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -39,8 +39,7 @@
|
||||||
* // do something
|
* // do something
|
||||||
* // ...
|
* // ...
|
||||||
*/
|
*/
|
||||||
class LightChrono
|
class LightChrono {
|
||||||
{
|
|
||||||
public:
|
public:
|
||||||
#if defined(ARDUINO_ARC32_TOOLS)
|
#if defined(ARDUINO_ARC32_TOOLS)
|
||||||
typedef uint64_t chrono_t;
|
typedef uint64_t chrono_t;
|
||||||
|
|
@ -68,5 +67,3 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -86,26 +86,26 @@ update the voltMeterConstant variable in pP_config.h with the correct value
|
||||||
|
|
||||||
------------------------------------------------------------*/
|
------------------------------------------------------------*/
|
||||||
|
|
||||||
// Headers, variables, and functions
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include <EEPROM.h>
|
|
||||||
#include "LightChrono.h"
|
|
||||||
#include "pP_pins.h"
|
|
||||||
// #include "pP_config.h"
|
|
||||||
#include "pP_volatile.h"
|
|
||||||
#include "pP_function.h"
|
|
||||||
#include "pP_serial.h"
|
|
||||||
|
|
||||||
// i2c input toggle. Uncomment to enable
|
// i2c input toggle. Uncomment to enable
|
||||||
#define I2C_INPUT
|
#define I2C_INPUT
|
||||||
|
|
||||||
|
// Headers, variables, and functions
|
||||||
|
#include "LightChrono.h"
|
||||||
|
#include "pP_pins.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <EEPROM.h>
|
||||||
|
#include "pP_function.h"
|
||||||
|
#include "pP_i2c.hpp"
|
||||||
|
#include "pP_serial.h"
|
||||||
|
#include "pP_volatile.h"
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
//Setup PWM on voltage follower (PD3)
|
// Setup PWM on voltage follower (PD3)
|
||||||
TCCR2A = (1 << COM2B1) | (0 << COM2B0) | (0 << WGM21) | (1 << WGM20);
|
TCCR2A = (1 << COM2B1) | (0 << COM2B0) | (0 << WGM21) | (1 << WGM20);
|
||||||
TCCR2B = (0 << WGM22) | (0 << CS22) | (0 << CS21) | (1 << CS20);
|
TCCR2B = (0 << WGM22) | (0 << CS22) | (0 << CS21) | (1 << CS20);
|
||||||
DDRD |= (1 << DDD3);
|
DDRD |= (1 << DDD3);
|
||||||
|
|
||||||
//Setup PWM on comparator (PB1)
|
// Setup PWM on comparator (PB1)
|
||||||
TCCR1A = (1 << COM1A1) | (0 << COM1A0) | (1 << WGM11) | (1 << WGM10);
|
TCCR1A = (1 << COM1A1) | (0 << COM1A0) | (1 << WGM11) | (1 << WGM10);
|
||||||
TCCR1B = (0 << WGM13) | (0 << WGM12) | (0 << CS12) | (0 << CS11) | (1 << CS10);
|
TCCR1B = (0 << WGM13) | (0 << WGM12) | (0 << CS12) | (0 << CS11) | (1 << CS10);
|
||||||
DDRB |= (1 << DDB1);
|
DDRB |= (1 << DDB1);
|
||||||
|
|
@ -126,6 +126,8 @@ void setup() {
|
||||||
Serial.begin(9600);
|
Serial.begin(9600);
|
||||||
Serial.println("Initializing Pyr0-Piezo Sensor...");
|
Serial.println("Initializing Pyr0-Piezo Sensor...");
|
||||||
|
|
||||||
|
i2cInit();
|
||||||
|
|
||||||
restoreConfig();
|
restoreConfig();
|
||||||
|
|
||||||
adjustGain();
|
adjustGain();
|
||||||
|
|
@ -144,7 +146,7 @@ void loop() {
|
||||||
if (BlinkCount > 0) {
|
if (BlinkCount > 0) {
|
||||||
BlinkState = !BlinkState;
|
BlinkState = !BlinkState;
|
||||||
digitalWriteFast(ERR_LED, BlinkState);
|
digitalWriteFast(ERR_LED, BlinkState);
|
||||||
//digitalWriteFast(TRG_OUT, BlinkState);
|
// digitalWriteFast(TRG_OUT, BlinkState);
|
||||||
--BlinkCount;
|
--BlinkCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -186,11 +188,11 @@ void loop() {
|
||||||
if (BlinkCount > 0) {
|
if (BlinkCount > 0) {
|
||||||
BlinkState = !BlinkState;
|
BlinkState = !BlinkState;
|
||||||
digitalWriteFast(ERR_LED, BlinkState);
|
digitalWriteFast(ERR_LED, BlinkState);
|
||||||
// digitalWriteFast(TRG_OUT, BlinkState);
|
// digitalWriteFast(TRG_OUT, BlinkState);
|
||||||
--BlinkCount;
|
--BlinkCount;
|
||||||
// } else {
|
// } else {
|
||||||
// Check for error state
|
// Check for error state
|
||||||
// checkError();
|
// checkError();
|
||||||
} else {
|
} else {
|
||||||
digitalWriteFast(ERR_LED, 0);
|
digitalWriteFast(ERR_LED, 0);
|
||||||
}
|
}
|
||||||
|
|
@ -200,7 +202,7 @@ void loop() {
|
||||||
serialPrintState();
|
serialPrintState();
|
||||||
}
|
}
|
||||||
// Sets trigger output state to false after completing loop
|
// Sets trigger output state to false after completing loop
|
||||||
//digitalWriteFast(TRG_OUT, HIGH);
|
// digitalWriteFast(TRG_OUT, HIGH);
|
||||||
sensorHReading = 0;
|
sensorHReading = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
||||||
99
firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_cmd.cpp
Normal file
99
firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_cmd.cpp
Normal file
|
|
@ -0,0 +1,99 @@
|
||||||
|
#include "EEPROM.h"
|
||||||
|
#include "pP_config.h"
|
||||||
|
#include "pP_function.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 updateVccSwitch(int value) {
|
||||||
|
if (value >= 0) {
|
||||||
|
VCCSW = value;
|
||||||
|
EEPROM.put(VCCSW_ADDRESS, VCCSW);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
@ -1,129 +1,16 @@
|
||||||
#ifndef PP_CMD_H
|
#ifndef PP_CMD_H
|
||||||
#define PP_CMD_H
|
#define PP_CMD_H
|
||||||
|
|
||||||
#include "pP_config.h"
|
void updateGainFactor(int value);
|
||||||
#include "pP_function.h"
|
void updateVFol(int value);
|
||||||
#include "EEPROM.h"
|
void updateVComp(int value);
|
||||||
|
void updateLoopDuration(int value);
|
||||||
|
void updateTrigDuration(int value);
|
||||||
|
void updateHysteresis(int value);
|
||||||
|
void updateLogic(int value);
|
||||||
|
void updatePzDet(int value);
|
||||||
|
void updateVccSwitch(int value);
|
||||||
|
void updateConstant(long value);
|
||||||
|
void updateDebug(int value);
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
#endif // PP_CMD_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 updateVccSwitch(int value)
|
|
||||||
{
|
|
||||||
if (value >= 0)
|
|
||||||
{
|
|
||||||
VCCSW = value;
|
|
||||||
EEPROM.put(VCCSW_ADDRESS, VCCSW);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
/*------------------------------------------------*/
|
|
||||||
|
|
||||||
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
|
|
||||||
|
|
|
||||||
|
|
@ -13,6 +13,7 @@ int PZDET = PZDET_DEFAULT;
|
||||||
int VCCSW = VCCSW_DEFAULT;
|
int VCCSW = VCCSW_DEFAULT;
|
||||||
int Debug = 0;
|
int Debug = 0;
|
||||||
long voltMeterConstant = VM_CONST_DEFAULT;
|
long voltMeterConstant = VM_CONST_DEFAULT;
|
||||||
|
uint8_t pP_i2c_address = 0x10;
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
void eraseEEPROM() {
|
void eraseEEPROM() {
|
||||||
|
|
|
||||||
|
|
@ -1,6 +1,8 @@
|
||||||
#ifndef PP_CONFIG_H
|
#ifndef PP_CONFIG_H
|
||||||
#define PP_CONFIG_H
|
#define PP_CONFIG_H
|
||||||
|
|
||||||
|
#include "stdint.h"
|
||||||
|
|
||||||
// Configurable settings:
|
// Configurable settings:
|
||||||
|
|
||||||
#define GAIN_FACTOR_DEFAULT 2 // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
|
#define GAIN_FACTOR_DEFAULT 2 // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
|
||||||
|
|
@ -49,10 +51,8 @@ extern int Debug;
|
||||||
#define VM_CONST_DEFAULT 1125300L
|
#define VM_CONST_DEFAULT 1125300L
|
||||||
extern long voltMeterConstant; // For fine tuning input voltage sense
|
extern long voltMeterConstant; // For fine tuning input voltage sense
|
||||||
|
|
||||||
#ifdef I2C_INPUT
|
|
||||||
#define I2C_SLAVE_ADDRESS 24
|
#define I2C_SLAVE_ADDRESS 24
|
||||||
uint8_t pP_i2c_address = 0xa0; // I2C Bus Address
|
extern uint8_t pP_i2c_address;
|
||||||
#endif // I2C_INPUT
|
|
||||||
|
|
||||||
void eraseEEPROM();
|
void eraseEEPROM();
|
||||||
void setDefaultConfig();
|
void setDefaultConfig();
|
||||||
|
|
|
||||||
|
|
@ -9,24 +9,19 @@
|
||||||
#include "pP_function.h"
|
#include "pP_function.h"
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#include "pP_config.h"
|
#include "pP_config.h"
|
||||||
#include "pP_volatile.h"
|
|
||||||
#include "pP_pins.h"
|
#include "pP_pins.h"
|
||||||
|
#include "pP_volatile.h"
|
||||||
#include "stdint.h"
|
#include "stdint.h"
|
||||||
|
|
||||||
void digitalWriteFast(uint8_t pin, uint8_t x)
|
void digitalWriteFast(uint8_t pin, uint8_t x) {
|
||||||
{
|
if (pin / 8) { // pin >= 8
|
||||||
if (pin / 8)
|
|
||||||
{ // pin >= 8
|
|
||||||
PORTB ^= (-x ^ PORTB) & (1 << (pin % 8));
|
PORTB ^= (-x ^ PORTB) & (1 << (pin % 8));
|
||||||
}
|
} else {
|
||||||
else
|
|
||||||
{
|
|
||||||
PORTD ^= (-x ^ PORTD) & (1 << (pin % 8));
|
PORTD ^= (-x ^ PORTD) & (1 << (pin % 8));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int analogReadFast(uint8_t ADCpin)
|
int analogReadFast(uint8_t ADCpin) {
|
||||||
{
|
|
||||||
byte ADCSRAoriginal = ADCSRA;
|
byte ADCSRAoriginal = ADCSRA;
|
||||||
ADCSRA = (ADCSRA & B11111000) | 4;
|
ADCSRA = (ADCSRA & B11111000) | 4;
|
||||||
int adc = analogRead(ADCpin);
|
int adc = analogRead(ADCpin);
|
||||||
|
|
@ -36,15 +31,13 @@ int analogReadFast(uint8_t ADCpin)
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void doubleFlash()
|
void doubleFlash() {
|
||||||
{
|
|
||||||
BlinkCount = 4;
|
BlinkCount = 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void pulse()
|
void pulse() {
|
||||||
{
|
|
||||||
digitalWriteFast(TRG_OUT, LOGIC);
|
digitalWriteFast(TRG_OUT, LOGIC);
|
||||||
sensorHReading = 1;
|
sensorHReading = 1;
|
||||||
delay(TRG_DUR);
|
delay(TRG_DUR);
|
||||||
|
|
@ -55,8 +48,7 @@ void pulse()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
long readVcc()
|
long readVcc() {
|
||||||
{
|
|
||||||
// Read 1.1V reference against AVcc
|
// Read 1.1V reference against AVcc
|
||||||
|
|
||||||
// Atmega's Secret Voltmeter setup:
|
// Atmega's Secret Voltmeter setup:
|
||||||
|
|
@ -103,8 +95,7 @@ If the scale_constant calculated is different from the default 1125300,
|
||||||
update the voltMeterConstant variable in pP_config.h with the correct value
|
update the voltMeterConstant variable in pP_config.h with the correct value
|
||||||
--------------------------------------------------*/
|
--------------------------------------------------*/
|
||||||
|
|
||||||
void readVin()
|
void readVin() {
|
||||||
{
|
|
||||||
VOld = Vin;
|
VOld = Vin;
|
||||||
Vin = readVcc();
|
Vin = readVcc();
|
||||||
followerLong = followerThrs * 1023L;
|
followerLong = followerThrs * 1023L;
|
||||||
|
|
@ -117,8 +108,7 @@ void readVin()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void adjustFollow()
|
void adjustFollow() {
|
||||||
{
|
|
||||||
/* Compares diffs of threshold vs read value
|
/* Compares diffs of threshold vs read value
|
||||||
if positive, adjusts the follower to within
|
if positive, adjusts the follower to within
|
||||||
the range set above*/
|
the range set above*/
|
||||||
|
|
@ -133,8 +123,7 @@ void adjustFollow()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void adjustComp()
|
void adjustComp() {
|
||||||
{
|
|
||||||
compLong = compThrs * 1023L;
|
compLong = compThrs * 1023L;
|
||||||
compInt = (long long)compLong / Vin;
|
compInt = (long long)compLong / Vin;
|
||||||
compInt = (int)compInt;
|
compInt = (int)compInt;
|
||||||
|
|
@ -143,21 +132,17 @@ void adjustComp()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void calibrateAlert()
|
void calibrateAlert() {
|
||||||
{
|
|
||||||
VLast = VOld - Vin;
|
VLast = VOld - Vin;
|
||||||
if (VLast > Hyst || VLast < -Hyst)
|
if (VLast > Hyst || VLast < -Hyst) {
|
||||||
{
|
|
||||||
ERR_STATE = 1;
|
ERR_STATE = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void adjustGain()
|
void adjustGain() {
|
||||||
{
|
switch (GAIN_FACTOR) {
|
||||||
switch (GAIN_FACTOR)
|
|
||||||
{
|
|
||||||
case 4:
|
case 4:
|
||||||
pinMode(GADJ_R0, OUTPUT);
|
pinMode(GADJ_R0, OUTPUT);
|
||||||
digitalWriteFast(GADJ_R0, LOW);
|
digitalWriteFast(GADJ_R0, LOW);
|
||||||
|
|
@ -192,10 +177,8 @@ void adjustGain()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void adjustVcc()
|
void adjustVcc() {
|
||||||
{
|
switch (VCCSW) {
|
||||||
switch (VCCSW)
|
|
||||||
{
|
|
||||||
case 0:
|
case 0:
|
||||||
pinMode(VCCSW_PIN, OUTPUT);
|
pinMode(VCCSW_PIN, OUTPUT);
|
||||||
digitalWriteFast(VCCSW_PIN, LOW);
|
digitalWriteFast(VCCSW_PIN, LOW);
|
||||||
|
|
@ -209,7 +192,7 @@ void adjustVcc()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
//void checkError () {
|
// void checkError () {
|
||||||
// if (ERR_STATE == 1) {
|
// if (ERR_STATE == 1) {
|
||||||
// digitalWriteFast(ERR_LED, BlinkState);
|
// digitalWriteFast(ERR_LED, BlinkState);
|
||||||
// BlinkState = !BlinkState;
|
// BlinkState = !BlinkState;
|
||||||
|
|
@ -222,12 +205,10 @@ void adjustVcc()
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void pzConCheck()
|
void pzConCheck() {
|
||||||
{
|
|
||||||
PZ_STATE = digitalRead(PZDET_PIN);
|
PZ_STATE = digitalRead(PZDET_PIN);
|
||||||
if (PZ_STATE == PZDET)
|
if (PZ_STATE == PZDET) {
|
||||||
{
|
// digitalWriteFast(TRG_OUT, LOGIC);
|
||||||
//digitalWriteFast(TRG_OUT, LOGIC);
|
|
||||||
ERR_STATE = 1;
|
ERR_STATE = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
@ -39,7 +39,7 @@ void adjustComp();
|
||||||
void adjustVcc();
|
void adjustVcc();
|
||||||
void calibrateAlert();
|
void calibrateAlert();
|
||||||
void adjustGain();
|
void adjustGain();
|
||||||
//void checkError () {
|
// void checkError () {
|
||||||
// if (ERR_STATE == 1) {
|
// if (ERR_STATE == 1) {
|
||||||
// digitalWriteFast(ERR_LED, BlinkState);
|
// digitalWriteFast(ERR_LED, BlinkState);
|
||||||
// BlinkState = !BlinkState;
|
// BlinkState = !BlinkState;
|
||||||
|
|
@ -51,4 +51,4 @@ void adjustGain();
|
||||||
//}
|
//}
|
||||||
void pzConCheck();
|
void pzConCheck();
|
||||||
|
|
||||||
#endif //PP_FUNCTION_H
|
#endif // PP_FUNCTION_H
|
||||||
|
|
@ -1,131 +1,134 @@
|
||||||
#ifdef I2C_INPUT
|
#include "pP_i2c.hpp"
|
||||||
|
#include "pP_cmd.h"
|
||||||
|
#include "pP_i2c_config.h"
|
||||||
|
#include "pP_volatile.h"
|
||||||
|
#include <Wire1.h>
|
||||||
|
|
||||||
#include <Arduino.h>
|
uint8_t command;
|
||||||
#include "pP_config.h"
|
uint16_t value;
|
||||||
#include "pP_i2c.h"
|
|
||||||
#include <Wire.h>
|
|
||||||
|
|
||||||
byte registerMap[regMapSize];
|
|
||||||
byte registerMapTemp[regMapSize - 1];
|
|
||||||
byte receivedCommands[maxBytes];
|
|
||||||
|
|
||||||
pP_i2c::pP_i2c(){
|
|
||||||
|
|
||||||
|
void i2cWrite(uint8_t *buffer, int offset, int data) {
|
||||||
|
buffer[offset] = (uint8_t)(data >> 8);
|
||||||
|
buffer[offset + 1] = (uint8_t)data;
|
||||||
}
|
}
|
||||||
|
|
||||||
void pP_i2c::init() {
|
void i2cWrite(uint8_t *buffer, int offset, long data) {
|
||||||
Wire.begin(pP_i2c_address);
|
buffer[offset] = (uint8_t)(data >> 24);
|
||||||
Wire.onRequest(i2cReply);
|
buffer[offset + 1] = (uint8_t)(data >> 16);
|
||||||
Wire.onReceive(i2cInput);
|
buffer[offset + 2] = (uint8_t)(data >> 8);
|
||||||
|
buffer[offset + 3] = (uint8_t)data;
|
||||||
}
|
}
|
||||||
|
|
||||||
void pP_i2c::i2cReportStatus() {
|
void i2cReportConfig() {
|
||||||
_i2cResponse = "{"
|
uint8_t length = 20 + sizeof(PP_VERSION) - 1;
|
||||||
|
if (length > 32) {
|
||||||
|
length = 32;
|
||||||
|
}
|
||||||
|
uint8_t buffer[length];
|
||||||
|
i2cWrite(buffer, 0, GAIN_FACTOR);
|
||||||
|
i2cWrite(buffer, 2, followerThrs);
|
||||||
|
i2cWrite(buffer, 4, compThrs);
|
||||||
|
i2cWrite(buffer, 6, LOOP_DUR);
|
||||||
|
i2cWrite(buffer, 8, TRG_DUR);
|
||||||
|
i2cWrite(buffer, 10, Hyst);
|
||||||
|
i2cWrite(buffer, 12, LOGIC);
|
||||||
|
i2cWrite(buffer, 14, PZDET);
|
||||||
|
i2cWrite(buffer, 16, voltMeterConstant);
|
||||||
|
memcpy(buffer + 20, PP_VERSION, length - 20);
|
||||||
|
Wire1.write(buffer, length);
|
||||||
}
|
}
|
||||||
|
|
||||||
void pP_i2c::i2cReportVersion() {
|
void i2cReportState() {
|
||||||
|
uint8_t length = 10;
|
||||||
|
uint8_t buffer[length];
|
||||||
|
i2cWrite(buffer, 0, Vin);
|
||||||
|
i2cWrite(buffer, 2, (int)((long)VComp * Vin / 1023));
|
||||||
|
i2cWrite(buffer, 4, (int)((long)VFol * Vin / 1023));
|
||||||
|
i2cWrite(buffer, 6, ERR_STATE);
|
||||||
|
i2cWrite(buffer, 8, PZ_STATE);
|
||||||
|
Wire1.write(buffer, length);
|
||||||
}
|
}
|
||||||
|
|
||||||
void pP_i2c::i2cReportConfig() {
|
void i2cReply() {
|
||||||
|
Serial.print("Requested ");
|
||||||
|
Serial.println(command);
|
||||||
|
switch (command) {
|
||||||
|
case CMD_CONFIG:
|
||||||
|
case CMD_ERASE:
|
||||||
|
i2cReportConfig();
|
||||||
|
break;
|
||||||
|
case CMD_STATE:
|
||||||
|
i2cReportState();
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pP_i2c::i2cReportIdentity() {
|
void i2cInput(int bytesReceived) {
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void pP_i2c::i2cRequestInput() {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void pP_i2c::i2cReply() {
|
|
||||||
Wire.send()
|
|
||||||
}
|
|
||||||
|
|
||||||
void pP_i2c::i2cInput(int bytesReceived) {
|
|
||||||
for (int a = 0; a < bytesReceived; a++) {
|
for (int a = 0; a < bytesReceived; a++) {
|
||||||
// Check length of message, drops anything longer than [longBytes]
|
// Check length of message, drops anything longer than [longBytes]
|
||||||
if (a <= maxBytes) {
|
if (a == 0) {
|
||||||
cmdRcvd[a] = Wire.receive();
|
command = Wire1.read();
|
||||||
}
|
} else if (a == 1) {
|
||||||
elif (a <= longBytes) {
|
value = Wire1.read();
|
||||||
longRcvd[a] = Wire.receive();
|
} else if (a == 2) {
|
||||||
}
|
value = value << 8 | Wire1.read();
|
||||||
else {
|
} else {
|
||||||
Wire.receive(); //
|
Wire1.read(); //
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check input command corresponds with register map, set 0x00 if not
|
Serial.print("Command ");
|
||||||
if (bytesReceived == 1 && (cmdRcvd[0] < regMapSize)) {
|
Serial.print(command);
|
||||||
return;
|
Serial.print(" ");
|
||||||
}
|
Serial.println(value);
|
||||||
if (bytesReceived == 1 && (cmdRcvd[0] >= regMapSize)) {
|
|
||||||
cmdRcvd[0] = 0x00;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Parse commands and apply changes or actions
|
// Parse commands and apply changes or actions
|
||||||
switch (cmdRcvd[0]) {
|
switch (command) {
|
||||||
case 0x00:
|
case CMD_GAIN_F:
|
||||||
i2cReportStatus();
|
updateGainFactor(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x01:
|
case CMD_VFOL:
|
||||||
followerInt = (int) cmdRcvd[1];
|
updateVFol(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x02:
|
case CMD_VCOMP:
|
||||||
compInt = (int) cmdRcvd[1];
|
updateVComp(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x03:
|
case CMD_LOOP_D:
|
||||||
GAIN_FACTOR = (int) cmdRcvd[1];
|
updateLoopDuration(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x04:
|
case CMD_TRG_D:
|
||||||
Hyst = (int) cmdRcvd[1];
|
updateTrigDuration(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x05:
|
case CMD_HYST:
|
||||||
LOOP_DUR = (int) cmdRcvd[1];
|
updateHysteresis(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x06:
|
case CMD_LOGIC:
|
||||||
LOGIC = (int) cmdRcvd[1];
|
updateLogic(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x07:
|
case CMD_PZDET:
|
||||||
PZDET = (int) cmdRcvd[1];
|
updatePzDet(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x08:
|
case CMD_CONST:
|
||||||
TRG_DUR = (int) cmdRcvd[1];
|
updateConstant(value);
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x09:
|
case CMD_CONFIG:
|
||||||
DEBUG = (int) cmdRcvd[1];
|
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x0a:
|
case CMD_ERASE:
|
||||||
voltMeterConstant = longRcvd[0]*65536+longRcvd[1]*256+longRcvd[2];
|
eraseEEPROM();
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case 0x0b:
|
case CMD_STATE:
|
||||||
reportVersion();
|
|
||||||
return;
|
|
||||||
break;
|
|
||||||
case 0x0c:
|
|
||||||
reportConfig();
|
|
||||||
return;
|
|
||||||
break;
|
|
||||||
case 0x0d:
|
|
||||||
reportIdentity();
|
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
|
case CMD_VCCSW:
|
||||||
|
updateVccSwitch(value);
|
||||||
default:
|
default:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
void i2cInit() {
|
||||||
|
Wire1.begin(pP_i2c_address);
|
||||||
|
Wire1.onRequest(i2cReply);
|
||||||
|
Wire1.onReceive(i2cInput);
|
||||||
|
}
|
||||||
|
|
|
||||||
|
|
@ -1,42 +0,0 @@
|
||||||
#ifndef _pP_i2c_h_
|
|
||||||
#define _pP_i2c_h_
|
|
||||||
#ifdef I2C_INPUT
|
|
||||||
|
|
||||||
#define status_Offset 0x00 // Status register
|
|
||||||
#define senseInt_Offset 0x01 // Integer of sense threshold in millivolts
|
|
||||||
#define compInt_Offset 0x02 // Integer of comparator threshold in millivolts
|
|
||||||
#define gainFactor_Offset 0x03 // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
|
|
||||||
#define hysteresis_Offset 0x04 // Hysteresis value for ADC measurements
|
|
||||||
#define loopDuration_Offset 0x05 // duration of time between ADC checks and other loop functions
|
|
||||||
#define logicLevel_Offset 0x06
|
|
||||||
#define piezoDetect_Offset 0x07
|
|
||||||
#define triggerDuration_Offset 0x08 // duration of the Z-axis pulse sent, in ms
|
|
||||||
#define debugEnable_Offset 0x09
|
|
||||||
#define voltMeterLong_Offset 0x0a // For fine-tuning the input volt master
|
|
||||||
#define versionRegister_Offset 0x0b
|
|
||||||
#define configRegister_Offset 0x0c
|
|
||||||
#define identRegister_Offset 0x0d
|
|
||||||
|
|
||||||
/*-------------------------Variables------------------------*/
|
|
||||||
#define regMapSize 14
|
|
||||||
#define maxBytes 2
|
|
||||||
#define longBytes 4
|
|
||||||
byte regMap[regMapSize];
|
|
||||||
byte regMapTemp[regMapSize];
|
|
||||||
byte cmdRcvd[maxBytes];
|
|
||||||
byte longRcvd[longBytes];
|
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
|
||||||
|
|
||||||
class pP_i2c {
|
|
||||||
public:
|
|
||||||
pP_i2c(uint8_t address=pP_i2c_address);
|
|
||||||
void init();
|
|
||||||
void i2cInput(int bytesReceived);
|
|
||||||
private:
|
|
||||||
char _i2cResponse;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // I2C_INPUT
|
|
||||||
#endif // _pP_i2c_h_
|
|
||||||
24
firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_i2c.hpp
Normal file
24
firmware/AVR-Source/Pyr0_Piezo_Sensor_v2.x.x/src/pP_i2c.hpp
Normal file
|
|
@ -0,0 +1,24 @@
|
||||||
|
#ifndef _pP_i2c_h_
|
||||||
|
#define _pP_i2c_h_
|
||||||
|
|
||||||
|
#include "pP_config.h"
|
||||||
|
#include "stdint.h"
|
||||||
|
|
||||||
|
#define status_Offset 0x00 // Status register
|
||||||
|
#define senseInt_Offset 0x01 // Integer of sense threshold in millivolts
|
||||||
|
#define compInt_Offset 0x02 // Integer of comparator threshold in millivolts
|
||||||
|
#define gainFactor_Offset 0x03 // Gain adjustment factor. 0=3x, 1=3.5x, 2=4.33x, 3=6x, 4=11x
|
||||||
|
#define hysteresis_Offset 0x04 // Hysteresis value for ADC measurements
|
||||||
|
#define loopDuration_Offset 0x05 // duration of time between ADC checks and other loop functions
|
||||||
|
#define logicLevel_Offset 0x06
|
||||||
|
#define piezoDetect_Offset 0x07
|
||||||
|
#define triggerDuration_Offset 0x08 // duration of the Z-axis pulse sent, in ms
|
||||||
|
#define debugEnable_Offset 0x09
|
||||||
|
#define voltMeterLong_Offset 0x0a // For fine-tuning the input volt master
|
||||||
|
#define versionRegister_Offset 0x0b
|
||||||
|
#define configRegister_Offset 0x0c
|
||||||
|
#define identRegister_Offset 0x0d
|
||||||
|
|
||||||
|
void i2cInit();
|
||||||
|
|
||||||
|
#endif // _pP_i2c_h_
|
||||||
|
|
@ -0,0 +1,13 @@
|
||||||
|
#define CMD_GAIN_F 0x00
|
||||||
|
#define CMD_VFOL 0x01
|
||||||
|
#define CMD_VCOMP 0x02
|
||||||
|
#define CMD_LOOP_D 0x03
|
||||||
|
#define CMD_TRG_D 0x04
|
||||||
|
#define CMD_HYST 0x05
|
||||||
|
#define CMD_LOGIC 0x06
|
||||||
|
#define CMD_PZDET 0x07
|
||||||
|
#define CMD_CONST 0x08
|
||||||
|
#define CMD_CONFIG 0x09
|
||||||
|
#define CMD_ERASE 0x0a
|
||||||
|
#define CMD_STATE 0x0b
|
||||||
|
#define CMD_VCCSW 0x0c
|
||||||
|
|
@ -1,7 +1,7 @@
|
||||||
#include "pP_cmd.h"
|
#include "pP_cmd.h"
|
||||||
|
#include "pP_volatile.h"
|
||||||
|
|
||||||
void parseData()
|
void parseData() {
|
||||||
{
|
|
||||||
|
|
||||||
// split the data into its parts
|
// split the data into its parts
|
||||||
|
|
||||||
|
|
@ -15,59 +15,30 @@ void parseData()
|
||||||
}
|
}
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void identifyMarkers()
|
void identifyMarkers() {
|
||||||
{
|
|
||||||
|
|
||||||
char x = Serial.read();
|
char x = Serial.read();
|
||||||
#ifdef I2C_INPUT
|
|
||||||
char y = Wire.read();
|
|
||||||
#endif // I2C_INPUT
|
|
||||||
|
|
||||||
if (x == '\n' || x == '\r')
|
if (x == '\n' || x == '\r') {
|
||||||
{
|
|
||||||
serialIncoming = true;
|
serialIncoming = true;
|
||||||
inputBuffer[bytesRecvd] = 0;
|
inputBuffer[bytesRecvd] = 0;
|
||||||
parseData();
|
parseData();
|
||||||
bytesRecvd = 0;
|
bytesRecvd = 0;
|
||||||
}
|
} else {
|
||||||
else
|
|
||||||
{
|
|
||||||
inputBuffer[bytesRecvd] = x;
|
inputBuffer[bytesRecvd] = x;
|
||||||
bytesRecvd++;
|
bytesRecvd++;
|
||||||
if (bytesRecvd == buffSize)
|
if (bytesRecvd == buffSize) {
|
||||||
{
|
|
||||||
bytesRecvd = buffSize - 1;
|
bytesRecvd = buffSize - 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef I2C_INPUT
|
|
||||||
if (y == '\n' || y == '\r')
|
|
||||||
{
|
|
||||||
serialIncoming = true;
|
|
||||||
inputBuffer[bytesRecvd] = 0;
|
|
||||||
parseData();
|
|
||||||
bytesRecvd = 0;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
inputBuffer[bytesRecvd] = y;
|
|
||||||
bytesRecvd++;
|
|
||||||
if (bytesRecvd == buffSize)
|
|
||||||
{
|
|
||||||
bytesRecvd = buffSize - 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*------------------------------------------------*/
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
void serialPrintConfig()
|
void serialPrintConfig() {
|
||||||
{
|
|
||||||
Serial.print("GAIN_F ");
|
Serial.print("GAIN_F ");
|
||||||
Serial.print(GAIN_FACTOR);
|
Serial.print(GAIN_FACTOR);
|
||||||
switch (GAIN_FACTOR)
|
switch (GAIN_FACTOR) {
|
||||||
{
|
|
||||||
case 0:
|
case 0:
|
||||||
Serial.println(" 3x");
|
Serial.println(" 3x");
|
||||||
break;
|
break;
|
||||||
|
|
@ -111,8 +82,7 @@ void serialPrintConfig()
|
||||||
|
|
||||||
Serial.print("VCCSW ");
|
Serial.print("VCCSW ");
|
||||||
Serial.print(VCCSW);
|
Serial.print(VCCSW);
|
||||||
switch (VCCSW)
|
switch (VCCSW) {
|
||||||
{
|
|
||||||
case 0:
|
case 0:
|
||||||
Serial.println(" 3.3v");
|
Serial.println(" 3.3v");
|
||||||
break;
|
break;
|
||||||
|
|
@ -131,8 +101,7 @@ void serialPrintConfig()
|
||||||
Serial.println(PP_VERSION);
|
Serial.println(PP_VERSION);
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialPrintState()
|
void serialPrintState() {
|
||||||
{
|
|
||||||
Serial.print("{");
|
Serial.print("{");
|
||||||
|
|
||||||
Serial.print("\"Vcc\":");
|
Serial.print("\"Vcc\":");
|
||||||
|
|
@ -153,77 +122,42 @@ void serialPrintState()
|
||||||
|
|
||||||
Serial.print("\"PzCon\":");
|
Serial.print("\"PzCon\":");
|
||||||
Serial.print(PZ_STATE);
|
Serial.print(PZ_STATE);
|
||||||
Serial.print(",");
|
|
||||||
|
|
||||||
Serial.print("\"Firm_Ver\":");
|
|
||||||
Serial.print(PP_VERSION);
|
|
||||||
Serial.print(",");
|
|
||||||
|
|
||||||
Serial.println("}");
|
Serial.println("}");
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateParams()
|
void updateParams() {
|
||||||
{
|
|
||||||
serialIncoming = false;
|
serialIncoming = false;
|
||||||
if (strcmp(serialMessageIn, "GAIN_F") == 0)
|
if (strcmp(serialMessageIn, "GAIN_F") == 0) {
|
||||||
{
|
|
||||||
updateGainFactor(serialLong);
|
updateGainFactor(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "VFOL") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "VFOL") == 0)
|
|
||||||
{
|
|
||||||
updateVFol(serialLong);
|
updateVFol(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "VCOMP") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "VCOMP") == 0)
|
|
||||||
{
|
|
||||||
updateVComp(serialLong);
|
updateVComp(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "LOOP_D") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "LOOP_D") == 0)
|
|
||||||
{
|
|
||||||
updateLoopDuration(serialLong);
|
updateLoopDuration(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "TRG_D") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "TRG_D") == 0)
|
|
||||||
{
|
|
||||||
updateTrigDuration(serialLong);
|
updateTrigDuration(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "HYST") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "HYST") == 0)
|
|
||||||
{
|
|
||||||
updateHysteresis(serialLong);
|
updateHysteresis(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "LOGIC") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "LOGIC") == 0)
|
|
||||||
{
|
|
||||||
updateLogic(serialLong);
|
updateLogic(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "PZDET") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "PZDET") == 0)
|
|
||||||
{
|
|
||||||
updatePzDet(serialLong);
|
updatePzDet(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "VCCSW") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "VCCSW") == 0)
|
|
||||||
{
|
|
||||||
updateVccSwitch(serialLong);
|
updateVccSwitch(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "CONST") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "CONST") == 0)
|
|
||||||
{
|
|
||||||
updateConstant(serialLong);
|
updateConstant(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "DEBUG") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "DEBUG") == 0)
|
|
||||||
{
|
|
||||||
updateDebug(serialLong);
|
updateDebug(serialLong);
|
||||||
}
|
} else if (strcmp(serialMessageIn, "CONFIG") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "CONFIG") == 0)
|
|
||||||
{
|
|
||||||
serialPrintConfig();
|
serialPrintConfig();
|
||||||
}
|
} else if (strcmp(serialMessageIn, "ERASE") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "ERASE") == 0)
|
|
||||||
{
|
|
||||||
eraseEEPROM();
|
eraseEEPROM();
|
||||||
serialPrintConfig();
|
serialPrintConfig();
|
||||||
}
|
} else if (strcmp(serialMessageIn, "STATE") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "STATE") == 0)
|
|
||||||
{
|
|
||||||
serialPrintState();
|
serialPrintState();
|
||||||
}
|
} else if (strcmp(serialMessageIn, "HELP") == 0) {
|
||||||
else if (strcmp(serialMessageIn, "HELP") == 0)
|
|
||||||
{
|
|
||||||
#if defined(ARDUINO_AVR_ATmega328PB)
|
#if defined(ARDUINO_AVR_ATmega328PB)
|
||||||
Serial.println("To change gain factor: GAIN_F [integer for gain state - see note*]");
|
Serial.println("To change gain factor: GAIN_F [integer for gain state - see note*]");
|
||||||
Serial.println("To change voltage follower voltage (low threshold): VFOL [float value]");
|
Serial.println("To change voltage follower voltage (low threshold): VFOL [float value]");
|
||||||
|
|
@ -234,7 +168,7 @@ void updateParams()
|
||||||
Serial.println(" (0 for active low, 1 for active high)");
|
Serial.println(" (0 for active low, 1 for active high)");
|
||||||
Serial.println("To enable piezo plugged detection: PZDET [0|1]");
|
Serial.println("To enable piezo plugged detection: PZDET [0|1]");
|
||||||
Serial.println(" (0 for disabled, 1 for enabled)");
|
Serial.println(" (0 for disabled, 1 for enabled)");
|
||||||
Serial.println("To change the main voltage of the circuit: VCCSW [0|1]")
|
Serial.println("To change the main voltage of the circuit: VCCSW [0|1]");
|
||||||
Serial.println(" (0 for 3.3v, 1 for 5v)");
|
Serial.println(" (0 for 3.3v, 1 for 5v)");
|
||||||
Serial.println("To change ADC hysteresis value: HYST [integer in millivolts]");
|
Serial.println("To change ADC hysteresis value: HYST [integer in millivolts]");
|
||||||
Serial.println("To enable or disable debug output: DEBUG [0|1]");
|
Serial.println("To enable or disable debug output: DEBUG [0|1]");
|
||||||
|
|
@ -256,11 +190,9 @@ void updateParams()
|
||||||
parseData();
|
parseData();
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialInput()
|
void serialInput() {
|
||||||
{
|
|
||||||
// receive data from Serial and save it into inputBuffer
|
// receive data from Serial and save it into inputBuffer
|
||||||
if (Serial.available() > 0)
|
if (Serial.available() > 0) {
|
||||||
{
|
|
||||||
|
|
||||||
// the order of these IF clauses is significant
|
// the order of these IF clauses is significant
|
||||||
identifyMarkers();
|
identifyMarkers();
|
||||||
|
|
|
||||||
|
|
@ -48,4 +48,4 @@ extern long serialLong;
|
||||||
// Task scheduler instances
|
// Task scheduler instances
|
||||||
extern LightChrono mainLoop;
|
extern LightChrono mainLoop;
|
||||||
|
|
||||||
#endif //PP_VOLATILE_H
|
#endif // PP_VOLATILE_H
|
||||||
3
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.clang-format
Normal file
3
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.clang-format
Normal file
|
|
@ -0,0 +1,3 @@
|
||||||
|
BasedOnStyle: LLVM
|
||||||
|
ColumnLimit: 200
|
||||||
|
AllowShortFunctionsOnASingleLine: false
|
||||||
7
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.gitignore
vendored
Normal file
7
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.gitignore
vendored
Normal file
|
|
@ -0,0 +1,7 @@
|
||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
||||||
|
.vscode/settings.json
|
||||||
|
.travis.yml
|
||||||
7
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.vscode/extensions.json
vendored
Normal file
7
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/.vscode/extensions.json
vendored
Normal file
|
|
@ -0,0 +1,7 @@
|
||||||
|
{
|
||||||
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
|
// for the documentation about the extensions.json format
|
||||||
|
"recommendations": [
|
||||||
|
"platformio.platformio-ide"
|
||||||
|
]
|
||||||
|
}
|
||||||
39
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/include/README
Normal file
39
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/include/README
Normal file
|
|
@ -0,0 +1,39 @@
|
||||||
|
|
||||||
|
This directory is intended for project header files.
|
||||||
|
|
||||||
|
A header file is a file containing C declarations and macro definitions
|
||||||
|
to be shared between several project source files. You request the use of a
|
||||||
|
header file in your project source file (C, C++, etc) located in `src` folder
|
||||||
|
by including it, with the C preprocessing directive `#include'.
|
||||||
|
|
||||||
|
```src/main.c
|
||||||
|
|
||||||
|
#include "header.h"
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Including a header file produces the same results as copying the header file
|
||||||
|
into each source file that needs it. Such copying would be time-consuming
|
||||||
|
and error-prone. With a header file, the related declarations appear
|
||||||
|
in only one place. If they need to be changed, they can be changed in one
|
||||||
|
place, and programs that include the header file will automatically use the
|
||||||
|
new version when next recompiled. The header file eliminates the labor of
|
||||||
|
finding and changing all the copies as well as the risk that a failure to
|
||||||
|
find one copy will result in inconsistencies within a program.
|
||||||
|
|
||||||
|
In C, the usual convention is to give header files names that end with `.h'.
|
||||||
|
It is most portable to use only letters, digits, dashes, and underscores in
|
||||||
|
header file names, and at most one dot.
|
||||||
|
|
||||||
|
Read more about using header files in official GCC documentation:
|
||||||
|
|
||||||
|
* Include Syntax
|
||||||
|
* Include Operation
|
||||||
|
* Once-Only Headers
|
||||||
|
* Computed Includes
|
||||||
|
|
||||||
|
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
||||||
46
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/lib/README
Normal file
46
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/lib/README
Normal file
|
|
@ -0,0 +1,46 @@
|
||||||
|
|
||||||
|
This directory is intended for project specific (private) libraries.
|
||||||
|
PlatformIO will compile them to static libraries and link into executable file.
|
||||||
|
|
||||||
|
The source code of each library should be placed in a an own separate directory
|
||||||
|
("lib/your_library_name/[here are source files]").
|
||||||
|
|
||||||
|
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||||
|
|
||||||
|
|--lib
|
||||||
|
| |
|
||||||
|
| |--Bar
|
||||||
|
| | |--docs
|
||||||
|
| | |--examples
|
||||||
|
| | |--src
|
||||||
|
| | |- Bar.c
|
||||||
|
| | |- Bar.h
|
||||||
|
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||||
|
| |
|
||||||
|
| |--Foo
|
||||||
|
| | |- Foo.c
|
||||||
|
| | |- Foo.h
|
||||||
|
| |
|
||||||
|
| |- README --> THIS FILE
|
||||||
|
|
|
||||||
|
|- platformio.ini
|
||||||
|
|--src
|
||||||
|
|- main.c
|
||||||
|
|
||||||
|
and a contents of `src/main.c`:
|
||||||
|
```
|
||||||
|
#include <Foo.h>
|
||||||
|
#include <Bar.h>
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
PlatformIO Library Dependency Finder will find automatically dependent
|
||||||
|
libraries scanning project source files.
|
||||||
|
|
||||||
|
More information about PlatformIO Library Dependency Finder
|
||||||
|
- https://docs.platformio.org/page/librarymanager/ldf.html
|
||||||
14
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/platformio.ini
Normal file
14
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/platformio.ini
Normal file
|
|
@ -0,0 +1,14 @@
|
||||||
|
; PlatformIO Project Configuration File
|
||||||
|
;
|
||||||
|
; Build options: build flags, source filter
|
||||||
|
; Upload options: custom upload port, speed and extra flags
|
||||||
|
; Library options: dependencies, extra library storages
|
||||||
|
; Advanced options: extra scripting
|
||||||
|
;
|
||||||
|
; Please visit documentation for the other options and examples
|
||||||
|
; https://docs.platformio.org/page/projectconf.html
|
||||||
|
|
||||||
|
[env:uno]
|
||||||
|
platform = atmelavr
|
||||||
|
board = uno
|
||||||
|
framework = arduino
|
||||||
73
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/i2c.cpp
Normal file
73
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/i2c.cpp
Normal file
|
|
@ -0,0 +1,73 @@
|
||||||
|
#include "i2c.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "Wire.h"
|
||||||
|
|
||||||
|
uint16_t read16() {
|
||||||
|
return Wire.read() << 8 | Wire.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t read32() {
|
||||||
|
return (uint32_t)Wire.read() << 24 | (uint32_t)Wire.read() << 16 | Wire.read() << 8 | Wire.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
void write(uint8_t cmd) {
|
||||||
|
Wire.beginTransmission(ADDRESS);
|
||||||
|
Wire.write(cmd);
|
||||||
|
Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
void write(uint8_t cmd, uint16_t value) {
|
||||||
|
Wire.beginTransmission(ADDRESS);
|
||||||
|
Wire.write(cmd);
|
||||||
|
Wire.write(value >> 8);
|
||||||
|
Wire.write(value);
|
||||||
|
Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
void write(uint8_t cmd, uint32_t value) {
|
||||||
|
Wire.beginTransmission(ADDRESS);
|
||||||
|
Wire.write(cmd);
|
||||||
|
Wire.write(value >> 24);
|
||||||
|
Wire.write(value >> 16);
|
||||||
|
Wire.write(value >> 8);
|
||||||
|
Wire.write(value);
|
||||||
|
Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
config_t requestConfig() {
|
||||||
|
Wire.beginTransmission(ADDRESS);
|
||||||
|
Wire.write(CMD_CONFIG);
|
||||||
|
Wire.endTransmission();
|
||||||
|
|
||||||
|
uint8_t bytes = Wire.requestFrom(ADDRESS, 255);
|
||||||
|
Serial.println(bytes);
|
||||||
|
|
||||||
|
config_t config;
|
||||||
|
config.GAIN_FACTOR = read16();
|
||||||
|
config.followerThrs = read16();
|
||||||
|
config.compThrs = read16();
|
||||||
|
config.LOOP_DUR = read16();
|
||||||
|
config.TRG_DUR = read16();
|
||||||
|
config.Hyst = read16();
|
||||||
|
config.LOGIC = read16();
|
||||||
|
config.PZDET = read16();
|
||||||
|
config.voltMeterConstant = read32();
|
||||||
|
config.version = Wire.readString();
|
||||||
|
|
||||||
|
return config;
|
||||||
|
}
|
||||||
|
|
||||||
|
state_t requestState() {
|
||||||
|
Wire.beginTransmission(ADDRESS);
|
||||||
|
Wire.write(CMD_STATE);
|
||||||
|
Wire.endTransmission();
|
||||||
|
|
||||||
|
uint8_t bytes = Wire.requestFrom(ADDRESS, 10);
|
||||||
|
|
||||||
|
state_t state;
|
||||||
|
state.Vin = read16();
|
||||||
|
state.VComp = read16();
|
||||||
|
state.VFol = read16();
|
||||||
|
state.ERR_STATE = read16();
|
||||||
|
state.PZ_STATE = read16();
|
||||||
|
}
|
||||||
50
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/i2c.h
Normal file
50
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/i2c.h
Normal file
|
|
@ -0,0 +1,50 @@
|
||||||
|
#ifndef I2C
|
||||||
|
#define I2C
|
||||||
|
|
||||||
|
#define ADDRESS 0x10
|
||||||
|
|
||||||
|
#define CMD_GAIN_F 0x00
|
||||||
|
#define CMD_VFOL 0x01
|
||||||
|
#define CMD_VCOMP 0x02
|
||||||
|
#define CMD_LOOP_D 0x03
|
||||||
|
#define CMD_TRG_D 0x04
|
||||||
|
#define CMD_HYST 0x05
|
||||||
|
#define CMD_LOGIC 0x06
|
||||||
|
#define CMD_PZDET 0x07
|
||||||
|
#define CMD_CONST 0x08
|
||||||
|
#define CMD_CONFIG 0x09
|
||||||
|
#define CMD_ERASE 0x0a
|
||||||
|
#define CMD_STATE 0x0b
|
||||||
|
#define CMD_VCCSW 0x0c
|
||||||
|
|
||||||
|
#include "WString.h"
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint16_t GAIN_FACTOR;
|
||||||
|
uint16_t followerThrs;
|
||||||
|
uint16_t compThrs;
|
||||||
|
uint16_t LOOP_DUR;
|
||||||
|
uint16_t TRG_DUR;
|
||||||
|
uint16_t Hyst;
|
||||||
|
uint16_t LOGIC;
|
||||||
|
uint16_t PZDET;
|
||||||
|
uint32_t voltMeterConstant;
|
||||||
|
String version;
|
||||||
|
} config_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint16_t Vin;
|
||||||
|
uint16_t VComp;
|
||||||
|
uint16_t VFol;
|
||||||
|
uint16_t ERR_STATE;
|
||||||
|
uint16_t PZ_STATE;
|
||||||
|
} state_t;
|
||||||
|
|
||||||
|
void write(uint8_t cmd);
|
||||||
|
void write(uint8_t cmd, uint16_t value);
|
||||||
|
void write(uint8_t cmd, uint32_t value);
|
||||||
|
|
||||||
|
config_t requestConfig();
|
||||||
|
state_t requestState();
|
||||||
|
|
||||||
|
#endif
|
||||||
21
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/main.cpp
Normal file
21
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/main.cpp
Normal file
|
|
@ -0,0 +1,21 @@
|
||||||
|
#define ARDUINO_AVR_ATmega328PB
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
#include "pP_serial.h"
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(9600);
|
||||||
|
Serial.println("Initializing Pyr0-Piezo i2c Bridge...");
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
serialInput();
|
||||||
|
|
||||||
|
if (serialIncoming) {
|
||||||
|
updateParams();
|
||||||
|
}
|
||||||
|
}
|
||||||
195
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/pP_serial.h
Normal file
195
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/src/pP_serial.h
Normal file
|
|
@ -0,0 +1,195 @@
|
||||||
|
#include "i2c.h"
|
||||||
|
#include "stdint.h"
|
||||||
|
|
||||||
|
#define buffSize 40
|
||||||
|
bool serialIncoming = false;
|
||||||
|
uint8_t bytesRecvd = 0;
|
||||||
|
char inputBuffer[buffSize];
|
||||||
|
char serialMessageIn[buffSize] = {0};
|
||||||
|
uint32_t serialLong = 0;
|
||||||
|
|
||||||
|
void parseData() {
|
||||||
|
|
||||||
|
// split the data into its parts
|
||||||
|
|
||||||
|
char *strtokIndx; // this is used by strtok() as an index
|
||||||
|
|
||||||
|
strtokIndx = strtok(inputBuffer, " "); // get the first part - the string
|
||||||
|
strcpy(serialMessageIn, strtokIndx); // copy it to serialMessageIn
|
||||||
|
|
||||||
|
strtokIndx = strtok(NULL, " "); // this continues where the previous call left off
|
||||||
|
serialLong = atol(strtokIndx); // convert this part to an integer
|
||||||
|
}
|
||||||
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
|
void identifyMarkers() {
|
||||||
|
|
||||||
|
char x = Serial.read();
|
||||||
|
|
||||||
|
if (x == '\n' || x == '\r') {
|
||||||
|
serialIncoming = true;
|
||||||
|
inputBuffer[bytesRecvd] = 0;
|
||||||
|
parseData();
|
||||||
|
bytesRecvd = 0;
|
||||||
|
} else {
|
||||||
|
inputBuffer[bytesRecvd] = x;
|
||||||
|
bytesRecvd++;
|
||||||
|
if (bytesRecvd == buffSize) {
|
||||||
|
bytesRecvd = buffSize - 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*------------------------------------------------*/
|
||||||
|
|
||||||
|
void serialPrintConfig() {
|
||||||
|
config_t config = requestConfig();
|
||||||
|
|
||||||
|
Serial.print("GAIN_F ");
|
||||||
|
Serial.print(config.GAIN_FACTOR);
|
||||||
|
switch (config.GAIN_FACTOR) {
|
||||||
|
case 0:
|
||||||
|
Serial.println(" 3x");
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
Serial.println(" 3.5x");
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
Serial.println(" 4.33x");
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
Serial.println(" 6x");
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
Serial.println(" 11x");
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
Serial.println(" INVALID");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.print("VFOL ");
|
||||||
|
Serial.println(config.followerThrs);
|
||||||
|
|
||||||
|
Serial.print("VCOMP ");
|
||||||
|
Serial.println(config.compThrs);
|
||||||
|
|
||||||
|
Serial.print("LOOP_D ");
|
||||||
|
Serial.println(config.LOOP_DUR);
|
||||||
|
|
||||||
|
Serial.print("TRG_D ");
|
||||||
|
Serial.println(config.TRG_DUR);
|
||||||
|
|
||||||
|
Serial.print("HYST ");
|
||||||
|
Serial.println(config.Hyst);
|
||||||
|
|
||||||
|
Serial.print("LOGIC ");
|
||||||
|
Serial.println(config.LOGIC);
|
||||||
|
|
||||||
|
Serial.print("PZDET ");
|
||||||
|
Serial.println(config.PZDET);
|
||||||
|
|
||||||
|
Serial.print("VM_CONST ");
|
||||||
|
Serial.println(config.voltMeterConstant);
|
||||||
|
|
||||||
|
Serial.print("Firmware Version ");
|
||||||
|
Serial.println(config.version);
|
||||||
|
}
|
||||||
|
|
||||||
|
void serialPrintState() {
|
||||||
|
state_t state = requestState();
|
||||||
|
|
||||||
|
Serial.print("{");
|
||||||
|
|
||||||
|
Serial.print("\"Vcc\":");
|
||||||
|
Serial.print(state.Vin);
|
||||||
|
Serial.print(",");
|
||||||
|
|
||||||
|
Serial.print("\"VComp\":");
|
||||||
|
Serial.print((uint32_t)state.VComp * state.Vin / 1023);
|
||||||
|
Serial.print(",");
|
||||||
|
|
||||||
|
Serial.print("\"VFol\":");
|
||||||
|
Serial.print((uint32_t)state.VFol * state.Vin / 1023);
|
||||||
|
Serial.print(",");
|
||||||
|
|
||||||
|
Serial.print("\"Err\":");
|
||||||
|
Serial.print(state.ERR_STATE);
|
||||||
|
Serial.print(",");
|
||||||
|
|
||||||
|
Serial.print("\"PzCon\":");
|
||||||
|
Serial.print(state.PZ_STATE);
|
||||||
|
|
||||||
|
Serial.println("}");
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateParams() {
|
||||||
|
serialIncoming = false;
|
||||||
|
if (strcmp(serialMessageIn, "GAIN_F") == 0) {
|
||||||
|
write(CMD_GAIN_F, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "VFOL") == 0) {
|
||||||
|
write(CMD_VFOL, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "VCOMP") == 0) {
|
||||||
|
write(CMD_VCOMP, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "LOOP_D") == 0) {
|
||||||
|
write(CMD_LOOP_D, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "TRG_D") == 0) {
|
||||||
|
write(CMD_TRG_D, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "HYST") == 0) {
|
||||||
|
write(CMD_HYST, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "LOGIC") == 0) {
|
||||||
|
write(CMD_LOGIC, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "PZDET") == 0) {
|
||||||
|
write(CMD_PZDET, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "VCCSW") == 0) {
|
||||||
|
write(CMD_VCCSW, (uint16_t)serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "CONST") == 0) {
|
||||||
|
write(CMD_CONST, serialLong);
|
||||||
|
} else if (strcmp(serialMessageIn, "CONFIG") == 0) {
|
||||||
|
serialPrintConfig();
|
||||||
|
} else if (strcmp(serialMessageIn, "ERASE") == 0) {
|
||||||
|
write(CMD_ERASE);
|
||||||
|
serialPrintConfig();
|
||||||
|
} else if (strcmp(serialMessageIn, "STATE") == 0) {
|
||||||
|
serialPrintState();
|
||||||
|
} else if (strcmp(serialMessageIn, "HELP") == 0) {
|
||||||
|
#if defined(ARDUINO_AVR_ATmega328PB)
|
||||||
|
Serial.println("To change gain factor: GAIN_F [integer for gain state - see note*]");
|
||||||
|
Serial.println("To change voltage follower voltage (low threshold): VFOL [float value]");
|
||||||
|
Serial.println("To change comparator voltage (high threshold): VCOMP [float value]");
|
||||||
|
Serial.println("To change main loop period: LOOP_D [integer for milliseconds]");
|
||||||
|
Serial.println("To change trigger active duration: TRG_D [integer for milliseconds]");
|
||||||
|
Serial.println("To change the output logic: LOGIC [0|1]");
|
||||||
|
Serial.println(" (0 for active low, 1 for active high)");
|
||||||
|
Serial.println("To enable piezo plugged detection: PZDET [0|1]");
|
||||||
|
Serial.println(" (0 for disabled, 1 for enabled)");
|
||||||
|
Serial.println("To change the main voltage of the circuit: VCCSW [0|1]");
|
||||||
|
Serial.println(" (0 for 3.3v, 1 for 5v)");
|
||||||
|
Serial.println("To change ADC hysteresis value: HYST [integer in millivolts]");
|
||||||
|
Serial.println("To enable or disable debug output: DEBUG [0|1]");
|
||||||
|
Serial.println("To print current config: CONFIG");
|
||||||
|
Serial.println("To set config to defaults: ERASE");
|
||||||
|
Serial.println("To print current state: STATE");
|
||||||
|
Serial.println("");
|
||||||
|
Serial.println("Commands are entered in this format:");
|
||||||
|
Serial.println("CMD VAL");
|
||||||
|
Serial.println("Commands are confirmed with Enter key");
|
||||||
|
Serial.println("");
|
||||||
|
Serial.println("Examples:");
|
||||||
|
Serial.println("GAIN_F 3 <~ set gain factor to index 3 (6x)");
|
||||||
|
Serial.println("VFOL 2350 <~ set the vref floor to 2.35V");
|
||||||
|
#else
|
||||||
|
Serial.println("Check docs.pyroballpcbs.com/config");
|
||||||
|
#endif // defined(ARDUINO_AVR_ATmega328PB)
|
||||||
|
}
|
||||||
|
parseData();
|
||||||
|
}
|
||||||
|
|
||||||
|
void serialInput() {
|
||||||
|
// receive data from Serial and save it into inputBuffer
|
||||||
|
if (Serial.available() > 0) {
|
||||||
|
|
||||||
|
// the order of these IF clauses is significant
|
||||||
|
identifyMarkers();
|
||||||
|
}
|
||||||
|
}
|
||||||
11
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/test/README
Normal file
11
firmware/AVR-Source/Pyr0_Piezo_i2c_Bridge/test/README
Normal file
|
|
@ -0,0 +1,11 @@
|
||||||
|
|
||||||
|
This directory is intended for PIO Unit Testing and project tests.
|
||||||
|
|
||||||
|
Unit Testing is a software testing method by which individual units of
|
||||||
|
source code, sets of one or more MCU program modules together with associated
|
||||||
|
control data, usage procedures, and operating procedures, are tested to
|
||||||
|
determine whether they are fit for use. Unit testing finds problems early
|
||||||
|
in the development cycle.
|
||||||
|
|
||||||
|
More information about PIO Unit Testing:
|
||||||
|
- https://docs.platformio.org/page/plus/unit-testing.html
|
||||||
Loading…
Reference in a new issue