mirror of
https://github.com/nqrduck/ATM.git
synced 2024-11-25 19:42:30 +00:00
commit
34a82889ac
18 changed files with 1572 additions and 511 deletions
2
.gitignore
vendored
2
.gitignore
vendored
|
@ -3,3 +3,5 @@
|
|||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
||||
.vscode
|
||||
src/dummy.h
|
||||
|
|
|
@ -3,6 +3,10 @@
|
|||
#define MOSI_PIN 13
|
||||
#define MISO_PIN 12
|
||||
|
||||
// I^2C Pins - ADC/DAC Module
|
||||
#define I2C_SDA 21
|
||||
#define I2C_SCL 16
|
||||
|
||||
//ADF Pins
|
||||
#define LE_PIN 27
|
||||
#define CE_PIN 25
|
||||
|
@ -23,9 +27,12 @@
|
|||
|
||||
#define DIAG1_PIN_M2 2 // used for homing
|
||||
|
||||
//ADC Pin
|
||||
#define REFLECTION_PIN 15
|
||||
//ADC Pin - obslete
|
||||
// #define REFLECTION_PIN 15
|
||||
|
||||
// Filter Bank
|
||||
#define FILTER_SWITCH_A 22
|
||||
#define FILTER_SWITCH_B 23
|
||||
#define FILTER_SWITCH_A 23
|
||||
#define FILTER_SWITCH_B 22
|
||||
|
||||
// RF Switch
|
||||
#define RF_SWITCH_PIN 34
|
||||
|
|
|
@ -16,11 +16,14 @@ struct FrequencyRange
|
|||
uint32_t MATCHING_CENTER_POSITION;
|
||||
};
|
||||
|
||||
const Filter FG_71MHZ = {71000000U, HIGH, HIGH};
|
||||
const Filter FG_71MHZ = {71000000U, LOW, LOW};
|
||||
const Filter FG_120MHZ = {120000000U, LOW, HIGH};
|
||||
const Filter FG_180MHZ = {180000000U, LOW, LOW};
|
||||
const Filter FG_180MHZ = {180000000U, HIGH, LOW};
|
||||
const Filter FG_260MHZ = {260000000U, HIGH, LOW};
|
||||
|
||||
// All fitlers
|
||||
const Filter FILTERS[] = {FG_71MHZ, FG_120MHZ, FG_180MHZ, FG_260MHZ};
|
||||
|
||||
// Settings for 100MHz -18dB
|
||||
//#define TUNING_STEPPER_HOME 34250U
|
||||
//#define MATCHING_STEPPER_HOME 45000U
|
||||
|
|
482
lib/AD5593R/AD5593R.cpp
Normal file
482
lib/AD5593R/AD5593R.cpp
Normal file
|
@ -0,0 +1,482 @@
|
|||
#include "AD5593R.h"
|
||||
#include <Wire.h>
|
||||
|
||||
//Definitions
|
||||
#define _ADAC_NULL B00000000
|
||||
#define _ADAC_ADC_SEQUENCE B00000010 // ADC sequence register - Selects ADCs for conversion
|
||||
#define _ADAC_GP_CONTROL B00000011 // General-purpose control register - DAC and ADC control register
|
||||
#define _ADAC_ADC_CONFIG B00000100 // ADC pin configuration - Selects which pins are ADC inputs
|
||||
#define _ADAC_DAC_CONFIG B00000101 // DAC pin configuration - Selects which pins are DAC outputs
|
||||
#define _ADAC_PULL_DOWN B00000110 // Pull-down configuration - Selects which pins have an 85 kO pull-down resistor to GND
|
||||
#define _ADAC_LDAC_MODE B00000111 // LDAC mode - Selects the operation of the load DAC
|
||||
#define _ADAC_GPIO_WR_CONFIG B00001000 // GPIO write configuration - Selects which pins are general-purpose outputs
|
||||
#define _ADAC_GPIO_WR_DATA B00001001 // GPIO write data - Writes data to general-purpose outputs
|
||||
#define _ADAC_GPIO_RD_CONFIG B00001010 // GPIO read configuration - Selects which pins are general-purpose inputs
|
||||
#define _ADAC_POWER_REF_CTRL B00001011 // Power-down/reference control - Powers down the DACs and enables/disables the reference
|
||||
#define _ADAC_OPEN_DRAIN_CFG B00001100 // Open-drain configuration - Selects open-drain or push-pull for general-purpose outputs
|
||||
#define _ADAC_THREE_STATE B00001101 // Three-state pins - Selects which pins are three-stated
|
||||
#define _ADAC_RESERVED B00001110 // Reserved
|
||||
#define _ADAC_SOFT_RESET B00001111 // Software reset - Resets the AD5593R
|
||||
|
||||
/**
|
||||
* @name ADAC Configuration Data Bytes
|
||||
******************************************************************************/
|
||||
///@{
|
||||
//write into MSB after _ADAC_POWER_REF_CTRL command to enable VREF
|
||||
#define _ADAC_VREF_ON B00000010
|
||||
#define _ADAC_SEQUENCE_ON B00000010
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @name ADAC Write / Read Pointer Bytes
|
||||
******************************************************************************/
|
||||
///@{
|
||||
#define _ADAC_DAC_WRITE B00010000
|
||||
#define _ADAC_ADC_READ B01000000
|
||||
#define _ADAC_DAC_READ B01010000
|
||||
#define _ADAC_GPIO_READ B01110000
|
||||
#define _ADAC_REG_READ B01100000
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//Class constructor
|
||||
AD5593R::AD5593R(int a0, int I2C_SDA, int I2C_SCL) {
|
||||
|
||||
_a0 = a0;
|
||||
_GPRC_msbs = 0x00;
|
||||
_GPRC_lsbs = 0x00;
|
||||
_PCR_msbs = 0x00;
|
||||
_PCR_lsbs = 0x00;
|
||||
//intializing the configuration struct.
|
||||
for (int i = 0; i < _num_of_channels; i++) {
|
||||
config.ADCs[i] = 0;
|
||||
config.DACs[i] = 0;
|
||||
}
|
||||
|
||||
for (int i = 0; i < _num_of_channels; i++) {
|
||||
values.ADCs[i] = -1;
|
||||
values.DACs[i] = -1;
|
||||
}
|
||||
|
||||
//this allows for multiple devices on the same bus, see header.
|
||||
if (_a0 > -1) {
|
||||
pinMode(_a0, OUTPUT);
|
||||
digitalWrite(_a0, HIGH);
|
||||
}
|
||||
Wire.begin(I2C_SDA, I2C_SCL);
|
||||
}
|
||||
|
||||
|
||||
//int AD5593R::configure_pins(*configuration config){
|
||||
|
||||
//}
|
||||
|
||||
void AD5593R::enable_internal_Vref() {
|
||||
//Enable selected device for writing
|
||||
_Vref = 2.5;
|
||||
_ADC_max = _Vref;
|
||||
_DAC_max = _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
//check if the on bit is already fliped on
|
||||
if ((_PCR_msbs & 0x02) != 0x02) {
|
||||
_PCR_msbs = _PCR_msbs ^ 0x02;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_POWER_REF_CTRL);
|
||||
Wire.write(_PCR_msbs);
|
||||
Wire.write(_PCR_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("Internal Reference on.");
|
||||
}
|
||||
|
||||
void AD5593R::disable_internal_Vref() {
|
||||
//Enable selected device for writing
|
||||
_Vref = -1;
|
||||
_ADC_max = _Vref;
|
||||
_DAC_max = _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
//check if the on bit is already fliped off
|
||||
if ((_PCR_msbs & 0x02) == 0x02) {
|
||||
_PCR_msbs = _PCR_msbs ^ 0x02;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_POWER_REF_CTRL);
|
||||
Wire.write(_PCR_msbs);
|
||||
Wire.write(_PCR_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("Internal Reference off.");
|
||||
}
|
||||
|
||||
void AD5593R::set_ADC_max_2x_Vref() {
|
||||
//Enable selected device for writing
|
||||
_ADC_max = 2 * _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
//check if 2x bit is on in the general purpose register
|
||||
if ((_GPRC_lsbs & 0x20) != 0x20) {
|
||||
_GPRC_lsbs = _GPRC_lsbs ^ 0x20;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GP_CONTROL);
|
||||
Wire.write(_GPRC_msbs);
|
||||
Wire.write(_GPRC_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("ADC max voltage = 2xVref");
|
||||
_ADC_2x_mode = 1;
|
||||
}
|
||||
|
||||
void AD5593R::set_ADC_max_1x_Vref() {
|
||||
//Enable selected device for writing
|
||||
_ADC_max = _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
if ((_GPRC_lsbs & 0x20) == 0x20) {
|
||||
_GPRC_lsbs = _GPRC_lsbs ^ 0x20;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GP_CONTROL);
|
||||
Wire.write(_GPRC_msbs);
|
||||
Wire.write(_GPRC_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("ADC max voltage = 1xVref");
|
||||
_ADC_2x_mode = 0;
|
||||
}
|
||||
|
||||
void AD5593R::set_DAC_max_2x_Vref() {
|
||||
//Enable selected device for writing
|
||||
_DAC_max = 2 * _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
if ((_GPRC_lsbs & 0x10) != 0x10) {
|
||||
_GPRC_lsbs = _GPRC_lsbs ^ 0x10;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GP_CONTROL);
|
||||
Wire.write(_GPRC_msbs);
|
||||
Wire.write(_GPRC_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("DAC max voltage = 2xVref");
|
||||
_DAC_2x_mode = 1;
|
||||
}
|
||||
|
||||
void AD5593R::set_DAC_max_1x_Vref() {
|
||||
//Enable selected device for writing
|
||||
_DAC_max = _Vref;
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
if ((_GPRC_lsbs & 0x10) == 0x10) {
|
||||
_GPRC_lsbs = _GPRC_lsbs ^ 0x10;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GP_CONTROL);
|
||||
Wire.write(_GPRC_msbs);
|
||||
Wire.write(_GPRC_lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
//Disable selected device for writing
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINTLN("ADC max voltage = 1xVref");
|
||||
_DAC_2x_mode = 0;
|
||||
}
|
||||
|
||||
void AD5593R::set_Vref(float Vref) {
|
||||
_Vref = Vref;
|
||||
if (_ADC_2x_mode == 0) {
|
||||
_ADC_max = Vref;
|
||||
}
|
||||
else {
|
||||
_ADC_max = 2 * Vref;
|
||||
}
|
||||
|
||||
if (_DAC_2x_mode == 0) {
|
||||
_DAC_max = Vref;
|
||||
}
|
||||
else {
|
||||
_DAC_max = 2 * Vref;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void AD5593R::configure_DAC(byte channel) {
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
config.DACs[channel] = 1;
|
||||
byte channel_byte = 1 << channel;
|
||||
//check to see if the channel is a DAC already
|
||||
if ((_DAC_config & channel_byte) != channel_byte) {
|
||||
_DAC_config = _DAC_config ^ channel_byte;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_DAC_CONFIG);
|
||||
Wire.write(0x0);
|
||||
Wire.write(_DAC_config);
|
||||
Wire.endTransmission();
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is configured as a DAC");
|
||||
}
|
||||
|
||||
|
||||
void AD5593R::configure_DACs(bool* channels) {
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (channels[i] == 1) {
|
||||
configure_DAC(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int AD5593R::write_DAC(byte channel, float voltage) {
|
||||
//error checking
|
||||
if (config.DACs[channel] == 0) {
|
||||
AD5593R_PRINT("ERROR! Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is not a DAC");
|
||||
return -1;
|
||||
}
|
||||
if (_DAC_max == -1) {
|
||||
AD5593R_PRINTLN("Vref, or DAC_max is not defined");
|
||||
return -2;
|
||||
}
|
||||
if (voltage > _DAC_max) {
|
||||
AD5593R_PRINTLN("Vref, or DAC_max is lower than set voltage");
|
||||
return -3;
|
||||
}
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
//find the binary representation of the
|
||||
unsigned int data_bits = (voltage / _DAC_max) * 4095;
|
||||
|
||||
//extract the 4 most signifigant bits, and move them down to the bottom
|
||||
byte data_msbs = (data_bits & 0xf00) >> 8;
|
||||
byte lsbs = (data_bits & 0x0ff);
|
||||
//place the channel data in the most signifigant bits
|
||||
byte msbs = (B10000000 | (channel << 4)) | data_msbs;
|
||||
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write((_ADAC_DAC_WRITE | channel));
|
||||
Wire.write(msbs);
|
||||
Wire.write(lsbs);
|
||||
Wire.endTransmission();
|
||||
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINT(" is set to ");
|
||||
AD5593R_PRINT(voltage);
|
||||
AD5593R_PRINTLN(" Volts");
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
values.DACs[channel] = voltage;
|
||||
return 1;
|
||||
}
|
||||
|
||||
void AD5593R::configure_ADC(byte channel) {
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
config.ADCs[channel] = 1;
|
||||
byte channel_byte = 1 << channel;
|
||||
//check to see if the channel is a ADC already
|
||||
if ((_ADC_config & channel_byte) != channel_byte) {
|
||||
_ADC_config = _ADC_config ^ channel_byte;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_ADC_CONFIG);
|
||||
Wire.write(0x0);
|
||||
Wire.write(_ADC_config);
|
||||
Wire.endTransmission();
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is configured as a ADC");
|
||||
}
|
||||
|
||||
void AD5593R::configure_ADCs(bool* channels) {
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (channels[i] == 1) {
|
||||
configure_ADC(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
float AD5593R::read_ADC(byte channel) {
|
||||
if (config.ADCs[channel] == 0) {
|
||||
AD5593R_PRINT("ERROR! Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is not an ADC");
|
||||
return -1;
|
||||
}
|
||||
if (_ADC_max == -1) {
|
||||
AD5593R_PRINTLN("Vref, or ADC_max is not defined");
|
||||
return -2;
|
||||
}
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_ADC_SEQUENCE);
|
||||
Wire.write(0x02);
|
||||
Wire.write(byte(1 << channel));
|
||||
Wire.endTransmission();
|
||||
|
||||
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_ADC_READ);
|
||||
Wire.endTransmission();
|
||||
|
||||
unsigned int data_bits = 0;
|
||||
|
||||
Wire.requestFrom(int(_i2c_address), int(2), int(1));
|
||||
if (Wire.available()) data_bits = (Wire.read() & 0x0f) << 8;
|
||||
if (Wire.available()) data_bits = data_bits | Wire.read();
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
float data = _ADC_max * (data_bits) / 4095;
|
||||
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINT(" reads ");
|
||||
AD5593R_PRINT(data);
|
||||
AD5593R_PRINTLN(" Volts");
|
||||
return data;
|
||||
}
|
||||
|
||||
float* AD5593R::read_ADCs() {
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (config.ADCs[i] == 1) {
|
||||
read_ADC(i);
|
||||
}
|
||||
}
|
||||
return values.ADCs;
|
||||
}
|
||||
|
||||
|
||||
void AD5593R::configure_GPI(byte channel) {
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
config.DACs[channel] = 1;
|
||||
byte channel_byte = 1 << channel;
|
||||
//check to see if the channel is a gpi already
|
||||
if ((_GPI_config & channel_byte) != channel_byte) {
|
||||
_GPI_config = _GPI_config ^ _GPI_config;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
// write to gpio-read register
|
||||
Wire.write(_ADAC_GPIO_RD_CONFIG);
|
||||
Wire.write(0x0);
|
||||
Wire.write(_GPI_config);
|
||||
Wire.endTransmission();
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is configured as a GPI");
|
||||
}
|
||||
|
||||
void AD5593R::configure_GPIs(bool* channels) {
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (channels[i] == 1) {
|
||||
configure_GPI(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void AD5593R::configure_GPO(byte channel) {
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
config.DACs[channel] = 1;
|
||||
byte channel_byte = 1 << channel;
|
||||
//check to see if the channel is a gpo already
|
||||
if ((_GPO_config & channel_byte) != channel_byte) {
|
||||
_GPO_config = _GPO_config ^ _GPO_config;
|
||||
}
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
// write to gpio-write register
|
||||
Wire.write(_ADAC_GPIO_WR_CONFIG);
|
||||
Wire.write(0x0);
|
||||
Wire.write(_GPI_config);
|
||||
Wire.endTransmission();
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
AD5593R_PRINT("Channel ");
|
||||
AD5593R_PRINT(channel);
|
||||
AD5593R_PRINTLN(" is configured as a GPO");
|
||||
}
|
||||
|
||||
void AD5593R::configure_GPOs(bool* channels) {
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (channels[i] == 1) {
|
||||
configure_GPO(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// bool AD5593R::read_GPI(byte channel) {
|
||||
|
||||
|
||||
// AD5593R_PRINT("Channel ");
|
||||
// AD5593R_PRINT(channel);
|
||||
// AD5593R_PRINT(" reads ");
|
||||
// AD5593R_PRINTLN(data);
|
||||
// return data;
|
||||
// }
|
||||
|
||||
bool* AD5593R::read_GPIs() {
|
||||
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
// request the data
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GPIO_READ);
|
||||
Wire.endTransmission();
|
||||
|
||||
uint16_t data_bits = 0;
|
||||
Wire.requestFrom(int(_i2c_address), int(2), int(1));
|
||||
// mask bits, build the word
|
||||
if (Wire.available()) data_bits = (Wire.read() & 0x0f) << 8;
|
||||
if (Wire.available()) data_bits = data_bits | Wire.read();
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (config.GPIs[i] == 1) {
|
||||
values.GPI_reads[i] = bool(data_bits & 0x01);
|
||||
}
|
||||
data_bits >> 1;
|
||||
}
|
||||
return values.GPI_reads;
|
||||
}
|
||||
|
||||
void AD5593R::write_GPOs(bool* pin_states) {
|
||||
byte data_bits = 0;
|
||||
for (size_t i = 0; i < _num_of_channels; i++) {
|
||||
if (config.GPOs[i] == 1) {
|
||||
values.GPO_writes[i] = pin_states[i];
|
||||
data_bits = data_bits & pin_states[i];
|
||||
}
|
||||
data_bits << 1;
|
||||
}
|
||||
if (_a0 > -1) digitalWrite(_a0, LOW);
|
||||
Wire.beginTransmission(_i2c_address);
|
||||
Wire.write(_ADAC_GPIO_WR_DATA);
|
||||
Wire.write(0x00);
|
||||
Wire.write(data_bits);
|
||||
Wire.endTransmission();
|
||||
if (_a0 > -1) digitalWrite(_a0, HIGH);
|
||||
}
|
210
lib/AD5593R/AD5593R.h
Normal file
210
lib/AD5593R/AD5593R.h
Normal file
|
@ -0,0 +1,210 @@
|
|||
/*
|
||||
This library is for the AD5593R by analog instruments please refer to the datasheet
|
||||
https://www.analog.com/media/en/technical-documentation/data-sheets/AD5593R.pdf
|
||||
|
||||
The AD5593R is a powerful 12-bit configurable DAC/ADC/GPIO chip connected through an I2C bus.
|
||||
The chip also has an additional addressing pin dubbed a0, which will change the device's effectively
|
||||
I2C address, by connecting this pin and specifying its location in the class construction it is possible to
|
||||
connect several AD5593Rs on the same I2C bus and independently control them.
|
||||
|
||||
To enable the ADC/DAC functionality of the chip a reference voltage MUST be set, as all set voltages
|
||||
must fall into the range 0-Vref, or 0-2xVref if set_(ADC/DAC)_max_2x_Vref is called. If these functions
|
||||
return negative values please read their description as the cause will be reported by its value.
|
||||
|
||||
GPIO capabilities have not yet been added.
|
||||
|
||||
Lukas Janavicius, 2019
|
||||
For contact information, projects, or more about me, please visit my GitHub or website linked below.
|
||||
|
||||
Janavicius.org
|
||||
https://github.com/LukasJanavicius
|
||||
|
||||
*/
|
||||
|
||||
//////Definitions and imports//////
|
||||
|
||||
// To enable debugging please place the following before the library import,
|
||||
// and be sure to use Serial.begin() in the setup.
|
||||
// AD5593R_DEBUG
|
||||
#pragma once
|
||||
//comment this line to disable debugging
|
||||
//#define AD5593R_DEBUG
|
||||
|
||||
#ifdef AD5593R_DEBUG
|
||||
#define AD5593R_PRINT(...) Serial.print(__VA_ARGS__)
|
||||
#define AD5593R_PRINTLN(...) Serial.println(__VA_ARGS__)
|
||||
#else
|
||||
#define AD5593R_PRINT(...)
|
||||
#define AD5593R_PRINTLN(...)
|
||||
#endif
|
||||
|
||||
#ifndef AD5593R_h
|
||||
#define AD5593R_h
|
||||
#endif
|
||||
#include <Arduino.h>
|
||||
|
||||
|
||||
//////Classes//////
|
||||
class AD5593R {
|
||||
public:
|
||||
|
||||
// This configuration structure contains arrays of booleans,
|
||||
// each array follows the form [channel0,...,channel7]
|
||||
// where a 1 indicates the channel should be configured as the name implies
|
||||
// for example an array ADCs[8] = {1,1,0,0,0,0,0,0} will configure channels 0 and 1 as ADCs.
|
||||
// a declaration of this structure should be defined in your code, and passed into configure().
|
||||
// You should not double assign pins, as only the first declaration will be assigned.
|
||||
struct configuration {
|
||||
bool ADCs[8]; //ADC pins
|
||||
bool DACs[8]; //DAC pins
|
||||
bool GPIs[8]; //input pins
|
||||
bool GPOs[8]; //output pins
|
||||
};
|
||||
configuration config;
|
||||
|
||||
// This structure contains arrays of
|
||||
struct Read_write_values {
|
||||
float ADCs[8];
|
||||
float DACs[8];
|
||||
bool GPI_reads[8];
|
||||
bool GPO_writes[8];
|
||||
};
|
||||
Read_write_values values;
|
||||
// constructor for the class, a0 is the digital pin connected to the AD5593R
|
||||
// if no pin is specified it is assumed only one AD5593R is connected
|
||||
AD5593R(int a0 = -1, int I2C_SDA = 34, int I2C_SCL = 35);
|
||||
|
||||
// enables the internal reference voltage of 2.5 V
|
||||
void enable_internal_Vref();
|
||||
|
||||
// disables the internal reference voltage of 2.5 V
|
||||
void disable_internal_Vref();
|
||||
|
||||
// sets the maximum ADC input to 2x Vref
|
||||
void set_ADC_max_2x_Vref();
|
||||
|
||||
// sets the maximum ADC input to 1x Vref
|
||||
void set_ADC_max_1x_Vref();
|
||||
|
||||
// sets the maximum DAC output to 2x Vref
|
||||
void set_DAC_max_2x_Vref();
|
||||
|
||||
// sets the maximum DAC output to 2x Vref
|
||||
void set_DAC_max_1x_Vref();
|
||||
|
||||
// If you use an external reference voltage you should call this function. Failure to set the reference voltage,
|
||||
// or enable the internal reference will mean that any DAC/ADC function call will result in an error!
|
||||
void set_Vref(float Vref);
|
||||
|
||||
//configures the selected channel as a DAC
|
||||
void configure_DAC(byte channel);
|
||||
|
||||
void configure_DACs(bool* channels);
|
||||
// Sets the output voltage value of a given channel, returns 1 if the write is completed
|
||||
// if the function returns -1 if the specified channel is not an DAC,
|
||||
// if no reference voltage is specified a -2 will be returned,
|
||||
// and if the voltage exceeds the maximum allowable voltage a -3 will be returned.
|
||||
int write_DAC(byte channel, float voltage);
|
||||
|
||||
void write_DACs(float* voltages);
|
||||
|
||||
//configures the selected channel as a ADC
|
||||
void configure_ADC(byte channel);
|
||||
|
||||
|
||||
void configure_ADCs(bool* channels);
|
||||
|
||||
// Reads the voltage value of a given ADC channel, returns the Voltage if the write is completed
|
||||
// if the function returns -1 if the specified channel is not an ADC,
|
||||
// and if no reference voltage is specified a -2 will be returned.
|
||||
float read_ADC(byte channel);
|
||||
|
||||
float* read_ADCs();
|
||||
|
||||
|
||||
void configure_GPI(byte channel);
|
||||
void configure_GPIs(bool* channels);
|
||||
|
||||
void configure_GPO(byte channel);
|
||||
void configure_GPOs(bool* channels);
|
||||
|
||||
bool* read_GPIs();
|
||||
void write_GPOs(bool* pin_states);
|
||||
|
||||
|
||||
|
||||
/*
|
||||
|
||||
// By passing in the configuration structure this function assigns the functionality
|
||||
// to each pin, as described in the configuration. As stated above, you should not
|
||||
// assign multiple functionalities to a single pin. In this event the function will return
|
||||
// -1 and print an error if debug is enabled. A 1 will be returned if the configuration is successful
|
||||
int configure_pins(*configuration config);
|
||||
|
||||
//call this function in
|
||||
void update(DAC_Writes[8],ADC_Reads[8]);
|
||||
|
||||
// performs a software reset, generally a good idea to call in the setup
|
||||
void reset();
|
||||
|
||||
|
||||
// Reads the set value of a given DAC channel, -1 will be returned if
|
||||
float read_DAC(int channel);
|
||||
|
||||
//This follows the same functionality as read_ADC(), but instead of reading from a single channel
|
||||
//the configuration is passed in, so that all of the ADCs are read.
|
||||
// In order to extract the values read you should pass in your Read_write_values struct.
|
||||
float read_DACs(int channels[8], *Read_write_values output);
|
||||
|
||||
//power down a specific channel, if none is specified all channels are powered down.
|
||||
void power_down(int channel = -1);
|
||||
*/
|
||||
private:
|
||||
// checks if the given channel is configured as an ADC
|
||||
// returns 1 if the channel is configured, 0 if the channel is not
|
||||
bool is_ADC(int channel);
|
||||
|
||||
// checks if the given channel is configured as a DAC
|
||||
// returns 1 if the channel is configured, 0 if the channel is not
|
||||
bool is_DAC(int channel);
|
||||
|
||||
// pointers for configuring the control registers, refer to the data sheet for functionality
|
||||
// These structures are adapted from
|
||||
// https://github.com/MikroElektronika/HEXIWEAR/blob/master/SW/Click%20Examples%20mikroC/examples/ADAC/library/__ADAC_Driver.h
|
||||
|
||||
|
||||
int _num_of_channels = 8;
|
||||
|
||||
int _a0;
|
||||
|
||||
//general purpose control register data Bytes
|
||||
byte _GPRC_msbs;
|
||||
byte _GPRC_lsbs;
|
||||
|
||||
// power control register data bytes;
|
||||
byte _PCR_msbs;
|
||||
byte _PCR_lsbs;
|
||||
|
||||
byte _DAC_config;
|
||||
byte _ADC_config;
|
||||
byte _GPI_config;
|
||||
byte _GPO_config;
|
||||
|
||||
//default address of the AD5593R, multiple devices are handled by setting the desired device's a0 to LOW
|
||||
//by default the a0 pin will be pulled high, effectively changing its address. For more information on the addressing please
|
||||
//refer to the data sheet in the introduction
|
||||
byte _i2c_address = 0x10;
|
||||
|
||||
//Value of the reference voltage, if none is specified then all ADC/DAC functions will throw errors
|
||||
float _Vref = -1;
|
||||
|
||||
//flag for 2xVref mode
|
||||
bool _ADC_2x_mode = 0;
|
||||
|
||||
//flag for 2xVref mode
|
||||
bool _DAC_2x_mode = 0;
|
||||
|
||||
float _ADC_max = -1;
|
||||
|
||||
float _DAC_max = -1;
|
||||
};
|
568
src/ATM.ino
568
src/ATM.ino
|
@ -1,21 +1,25 @@
|
|||
#include <TMC2130Stepper.h>
|
||||
#include <AccelStepper.h>
|
||||
#include <MultiStepper.h>
|
||||
#include <math.h>
|
||||
#include "global.h"
|
||||
|
||||
#include "ADF4351.h"
|
||||
#include "Pins.h" // Pins are defined here
|
||||
#include "Positions.h" // Calibrated frequency positions are defined her
|
||||
#include "Stepper.h" // Stepper specific values are defined here
|
||||
#include "CommandManager.h"
|
||||
#include "commands/FrequencySweep.h"
|
||||
#include "commands/TuneMatch.h"
|
||||
#include "commands/Homing.h"
|
||||
|
||||
#define DEBUG
|
||||
|
||||
#include "Debug.h"
|
||||
|
||||
CommandManager commandManager;
|
||||
|
||||
// Commands
|
||||
FrequencySweep frequencySweep;
|
||||
TuneMatch tuneMatch;
|
||||
Homing homing;
|
||||
|
||||
// Frequency Settings
|
||||
#define FREQUENCY_STEP 100000U // 100kHz frequency steps for initial frequency sweep
|
||||
#define START_FREQUENCY 35000000U // 80MHz
|
||||
#define STOP_FREQUENCY 110000000 // 120MHz
|
||||
#define START_FREQUENCY 50000000U // 50MHz
|
||||
#define STOP_FREQUENCY 110000000 // 110MHz
|
||||
|
||||
ADF4351 adf4351(SCLK_PIN, MOSI_PIN, LE_PIN, CE_PIN); // declares object PLL of type ADF4351
|
||||
|
||||
|
@ -29,14 +33,26 @@ Stepper tuner = {tuning_stepper, tuning_driver, DIAG1_PIN_M1, "Tuner"};
|
|||
|
||||
Stepper matcher = {matching_stepper, matching_driver, DIAG1_PIN_M2, "Matcher"};
|
||||
|
||||
// ADC DAC Module
|
||||
AD5593R adac = AD5593R(23, I2C_SDA, I2C_SCL);
|
||||
bool DACs[8] = {0, 0, 1, 1, 0, 0, 0, 0};
|
||||
bool ADCs[8] = {1, 1, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
boolean homed = false;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
|
||||
// Here the commands are registered
|
||||
commandManager.registerCommand('f', &frequencySweep);
|
||||
commandManager.registerCommand('d', &tuneMatch);
|
||||
commandManager.registerCommand('h', &homing);
|
||||
|
||||
pinMode(MISO_PIN, INPUT_PULLUP); // Seems to be necessary for SPI to work
|
||||
|
||||
|
||||
// Setup fo the tuning stepper
|
||||
tuner.DRIVER.begin(); // Initiate pins
|
||||
tuner.DRIVER.rms_current(400); // Set stepper current to 400mA.
|
||||
tuner.DRIVER.microsteps(16);
|
||||
|
@ -49,9 +65,7 @@ void setup()
|
|||
|
||||
pinMode(DIAG1_PIN_M1, INPUT);
|
||||
|
||||
Serial.print("DRV_STATUS=0b");
|
||||
Serial.println(tuning_driver.DRV_STATUS(), BIN);
|
||||
|
||||
// Setup fo the matching stepper
|
||||
matcher.DRIVER.begin(); // Initiate pins and registeries
|
||||
matcher.DRIVER.rms_current(200); // Set stepper current to 200mA. The command is the same as command TMC2130.setCurrent(600, 0.11, 0.5);
|
||||
matcher.DRIVER.microsteps(16);
|
||||
|
@ -63,7 +77,6 @@ void setup()
|
|||
matcher.DRIVER.stealthChop(1); // Enable extremely quiet stepping
|
||||
|
||||
digitalWrite(EN_PIN_M1, LOW);
|
||||
|
||||
digitalWrite(EN_PIN_M2, LOW);
|
||||
|
||||
tuner.STEPPER.setMaxSpeed(12000);
|
||||
|
@ -82,23 +95,39 @@ void setup()
|
|||
|
||||
matcher.STEPPER.setCurrentPosition(0);
|
||||
|
||||
// Setup for the ADF4351 frequency synthesizer
|
||||
adf4351.begin();
|
||||
|
||||
adf4351.setrf(25000000U);
|
||||
adf4351.pwrlevel = 2; // This equals -4dBm*/
|
||||
adf4351.pwrlevel = 2; // This equals -4dBm*/ For the electrical probe coils one should use at least -20dbm so an attenuator is necessary
|
||||
adf4351.setf(START_FREQUENCY);
|
||||
|
||||
// Setup for the RF Switch for the filterbank
|
||||
pinMode(FILTER_SWITCH_A, OUTPUT);
|
||||
pinMode(FILTER_SWITCH_B, OUTPUT);
|
||||
|
||||
digitalWrite(FILTER_SWITCH_A, LOW);
|
||||
digitalWrite(FILTER_SWITCH_B, HIGH);
|
||||
|
||||
// changeFrequencyRange(HOME_RANGE);
|
||||
// ADAC module
|
||||
adac.enable_internal_Vref();
|
||||
adac.set_DAC_max_2x_Vref();
|
||||
adac.set_ADC_max_2x_Vref();
|
||||
adac.configure_DACs(DACs);
|
||||
|
||||
adac.configure_ADCs(ADCs);
|
||||
|
||||
// RF Switch for switching between preamp and tuning and matching module
|
||||
pinMode(RF_SWITCH_PIN, OUTPUT);
|
||||
digitalWrite(RF_SWITCH_PIN, HIGH);
|
||||
}
|
||||
|
||||
// Implement Serial communication ...
|
||||
// This could probably cleaned up by using structs for the inputs, pointing to the different functions- > would reduce copy-paste code and make adding functions more intuitive
|
||||
// Serial communication via USB.
|
||||
// Commands:
|
||||
// f<start frequency>f<stop frequency>f<frequency step> - Frequency Sweep
|
||||
// d<target frequency in MHz>f<start frequency>f<stop frequency>f<frequency step> - Tune and Match
|
||||
// h - Homing
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (Serial.available())
|
||||
|
@ -108,82 +137,11 @@ void loop()
|
|||
|
||||
char command = input_line.charAt(0); // gets first character of input
|
||||
|
||||
commandManager.executeCommand(command, input_line);
|
||||
commandManager.printCommandResult(command);
|
||||
// approximate call
|
||||
// CAREFULL -> if the coil has no proper matching in the frequency range this will not work! Only use this for testing -> otherwise use the automated 'decide' call.
|
||||
if (command == 'a')
|
||||
{
|
||||
DEBUG_PRINT("Not implemented");
|
||||
|
||||
// bruteforce call
|
||||
// CAREFULL -> if the current resonance frequency is not within +-5MHz of the target frequency this will not work. Only use this for testing -> otherwise use the automated 'decide' call.
|
||||
}
|
||||
else if (command == 'b')
|
||||
{
|
||||
float target_frequency_MHz = input_line.substring(1).toFloat();
|
||||
uint32_t target_frequency = validateInput(target_frequency_MHz);
|
||||
if (target_frequency == 0)
|
||||
return;
|
||||
|
||||
Serial.println("Bruteforce matching to target frequency in MHz:");
|
||||
Serial.println(target_frequency_MHz);
|
||||
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP);
|
||||
|
||||
resonance_frequency = bruteforceResonance(target_frequency, resonance_frequency);
|
||||
Serial.println("Resonance after bruteforce is at:");
|
||||
Serial.println(resonance_frequency);
|
||||
|
||||
// decide call
|
||||
// this function decides what kind of t&m mode should be used based on the relationship between target frequency and current resonance
|
||||
// it also makes sure that there a homing routine performed in case there is currently no proper resonance in the frequency range
|
||||
}
|
||||
else if (command == 'd')
|
||||
{
|
||||
float target_frequency_MHz = input_line.substring(1).toFloat();
|
||||
uint32_t target_frequency = validateInput(target_frequency_MHz);
|
||||
if (target_frequency == 0)
|
||||
return;
|
||||
|
||||
Serial.println("Tuning and Matching to target frequency in MHz (automatic mode):");
|
||||
Serial.println(target_frequency_MHz);
|
||||
|
||||
uint32_t resonance_frequency = automaticTM(target_frequency);
|
||||
|
||||
Serial.println("Resonance after tuning and matching is at:");
|
||||
Serial.println(resonance_frequency);
|
||||
|
||||
Serial.println("Matched to RL in dB:");
|
||||
Serial.println(calculateRL(resonance_frequency));
|
||||
|
||||
// home call
|
||||
// Perform the homing routine by looking for the limit of the capacitors
|
||||
// it also places the steppers in a way so there is a resonance dip inside the frequency range
|
||||
// CAREFULL -> The values are hardcoded, these need to be changed if there is a different coil in use
|
||||
}
|
||||
else if (command == 'h')
|
||||
{
|
||||
Serial.println("Homing...");
|
||||
tuner.STEPPER.setCurrentPosition(homeStepper(tuner));
|
||||
matcher.STEPPER.setCurrentPosition(homeStepper(matcher));
|
||||
homed = true;
|
||||
changeFrequencyRange(HOME_RANGE);
|
||||
|
||||
Serial.println("Resonance frequency after homing:");
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP / 2);
|
||||
Serial.println(resonance_frequency);
|
||||
|
||||
// frequency sweep call
|
||||
// scans the frequency range for the current resonance frequency
|
||||
}
|
||||
else if (command == 'f')
|
||||
{
|
||||
Serial.println("Frequency sweep...");
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP / 2);
|
||||
Serial.println("Resonance is at:");
|
||||
Serial.println(resonance_frequency);
|
||||
|
||||
// calculates Reflection loss for a given frequency
|
||||
}
|
||||
/*if (command == 'a')
|
||||
else if (command == 'r')
|
||||
{
|
||||
float frequency_MHz = input_line.substring(1).toFloat();
|
||||
|
@ -193,19 +151,19 @@ void loop()
|
|||
|
||||
float reflection_loss = calculateRL(frequency);
|
||||
|
||||
Serial.println("For frequency:");
|
||||
Serial.println(frequency);
|
||||
Serial.println("RL is:");
|
||||
Serial.println(reflection_loss);
|
||||
printInfo("For frequency:");
|
||||
printInfo(frequency);
|
||||
printInfo("RL is:");
|
||||
printInfo(reflection_loss);
|
||||
|
||||
// optimize Matching
|
||||
}
|
||||
else if (command == 'm')
|
||||
{
|
||||
Serial.println("Optimize Matching around frequency:");
|
||||
printInfo("Optimize Matching around frequency:");
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP);
|
||||
|
||||
Serial.println(resonance_frequency);
|
||||
printInfo(resonance_frequency);
|
||||
|
||||
optimizeMatching(resonance_frequency);
|
||||
|
||||
|
@ -220,421 +178,21 @@ void loop()
|
|||
return;
|
||||
|
||||
int sum = sumReflectionAroundFrequency(frequency);
|
||||
Serial.println("For frequency:");
|
||||
Serial.println(frequency);
|
||||
Serial.println("Sum of the reflection is:");
|
||||
Serial.println(sum);
|
||||
printInfo("For frequency:");
|
||||
printInfo(frequency);
|
||||
printInfo("Sum of the reflection is:");
|
||||
printInfo(sum);
|
||||
|
||||
// Calibration Call
|
||||
}
|
||||
else if (command == 'c')
|
||||
{
|
||||
Serial.println("Calibrating ...");
|
||||
printInfo("Calibrating ...");
|
||||
getCalibrationValues();
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println("Invalid Input");
|
||||
}
|
||||
printInfo("Invalid Input");
|
||||
}*/
|
||||
}
|
||||
}
|
||||
|
||||
// This helper function checks if the input frequency is plausible, if so it returns the value in Hz
|
||||
// otherwise it returns 0
|
||||
uint32_t validateInput(float frequency_MHz)
|
||||
{
|
||||
uint32_t frequency_Hz = frequency_MHz * 1000000U;
|
||||
|
||||
if (frequency_Hz < START_FREQUENCY)
|
||||
{
|
||||
Serial.println("Invalid input: frequency too low");
|
||||
return 0;
|
||||
}
|
||||
else if (frequency_Hz > STOP_FREQUENCY)
|
||||
{
|
||||
Serial.println("Invalid input: frequency too high");
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
return frequency_Hz;
|
||||
}
|
||||
}
|
||||
|
||||
int readReflection(int averages)
|
||||
{
|
||||
int reflection = 0;
|
||||
for (int i = 0; i < averages; i++)
|
||||
reflection += analogReadMilliVolts(REFLECTION_PIN);
|
||||
return reflection / averages;
|
||||
}
|
||||
|
||||
void getCalibrationValues()
|
||||
{
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP);
|
||||
|
||||
tuner.STEPPER.setCurrentPosition(0);
|
||||
matcher.STEPPER.setCurrentPosition(0);
|
||||
|
||||
int tuner_position = stallStepper(tuner);
|
||||
|
||||
int matcher_position = stallStepper(matcher);
|
||||
|
||||
Serial.println("For Resonance frequency:");
|
||||
Serial.println(resonance_frequency);
|
||||
Serial.println("Tuner Calibration is:");
|
||||
Serial.println(tuner_position);
|
||||
Serial.println("Matcher Position is:");
|
||||
Serial.println(matcher_position);
|
||||
}
|
||||
|
||||
long homeStepper(Stepper stepper)
|
||||
{
|
||||
stallStepper(stepper);
|
||||
stepper.STEPPER.setCurrentPosition(0);
|
||||
stepper.STEPPER.moveTo(1000);
|
||||
stepper.STEPPER.runToPosition();
|
||||
|
||||
stepper.STEPPER.setMaxSpeed(3000);
|
||||
stepper.STEPPER.setAcceleration(3000);
|
||||
|
||||
stepper.DRIVER.sg_stall_value(-64); // Stall value needs to be lowered because of slower stepper
|
||||
stallStepper(stepper);
|
||||
stepper.DRIVER.sg_stall_value(STALL_VALUE);
|
||||
|
||||
stepper.STEPPER.setMaxSpeed(12000);
|
||||
stepper.STEPPER.setAcceleration(12000);
|
||||
|
||||
stepper.STEPPER.setCurrentPosition(0);
|
||||
|
||||
stepper.STEPPER.moveTo(1000);
|
||||
|
||||
stepper.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(stepper.STEPPER.currentPosition());
|
||||
|
||||
return stepper.STEPPER.currentPosition();
|
||||
}
|
||||
|
||||
int stallStepper(Stepper stepper)
|
||||
{
|
||||
stepper.STEPPER.moveTo(-9999999);
|
||||
|
||||
while (!digitalRead(stepper.STALL_PIN))
|
||||
{
|
||||
stepper.STEPPER.run();
|
||||
}
|
||||
|
||||
DEBUG_PRINT(stepper.STEPPER.currentPosition());
|
||||
|
||||
stepper.STEPPER.stop();
|
||||
|
||||
return stepper.STEPPER.currentPosition(); // returns value until limit is reached
|
||||
}
|
||||
|
||||
// This function changes the filterbank settings for the selected target range
|
||||
// and drives the tuner and matcher stepper to the center of the selected frequency range
|
||||
void changeFrequencyRange(FrequencyRange target_range)
|
||||
{
|
||||
digitalWrite(FILTER_SWITCH_A, target_range.FILTER.control_input_a);
|
||||
digitalWrite(FILTER_SWITCH_B, target_range.FILTER.control_input_b);
|
||||
|
||||
tuner.STEPPER.moveTo(target_range.TUNING_CENTER_POSITION);
|
||||
tuner.STEPPER.runToPosition();
|
||||
|
||||
matcher.STEPPER.moveTo(target_range.MATCHING_CENTER_POSITION);
|
||||
matcher.STEPPER.runToPosition();
|
||||
}
|
||||
|
||||
uint32_t automaticTM(uint32_t target_frequency)
|
||||
{
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP);
|
||||
|
||||
DEBUG_PRINT("Resonance Frequency before TM");
|
||||
DEBUG_PRINT(resonance_frequency);
|
||||
|
||||
resonance_frequency = bruteforceResonance(target_frequency, resonance_frequency);
|
||||
|
||||
optimizeMatching(resonance_frequency);
|
||||
|
||||
resonance_frequency = findCurrentResonanceFrequency(resonance_frequency - 1000000U, resonance_frequency + 1000000U, FREQUENCY_STEP / 2);
|
||||
|
||||
resonance_frequency = bruteforceResonance(target_frequency, resonance_frequency);
|
||||
|
||||
return resonance_frequency;
|
||||
}
|
||||
|
||||
// calculates the Reflection Loss at a specified frequency
|
||||
// 24mV/dB slope
|
||||
float calculateRL(uint32_t frequency)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(100);
|
||||
|
||||
float reflection = readReflection(64);
|
||||
|
||||
float reflection_loss = reflection / 2.96; // Divide by the amplifier gain
|
||||
reflection_loss = reflection_loss / 24; // Divide by the logamp slope
|
||||
|
||||
return reflection_loss;
|
||||
}
|
||||
|
||||
// Finds current Resonance Frequency of the coil. There should be a substential dip already present atm.
|
||||
|
||||
int32_t findCurrentResonanceFrequency(uint32_t start_frequency, uint32_t stop_frequency, uint32_t frequency_step)
|
||||
{
|
||||
int maximum_reflection = 0;
|
||||
int current_reflection = 0;
|
||||
uint32_t minimum_frequency = 0;
|
||||
float reflection = 0;
|
||||
|
||||
adf4351.setf(start_frequency); // A frequency value needs to be set once -> there seems to be a bug with the first SPI call
|
||||
delay(50);
|
||||
|
||||
for (uint32_t frequency = start_frequency; frequency <= stop_frequency; frequency += frequency_step)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(5); // This delay is essential! There is a glitch with ADC2 that leads to wrong readings if GPIO27 is set to high for multiple microseconds.
|
||||
|
||||
current_reflection = readReflection(4);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_frequency = frequency;
|
||||
maximum_reflection = current_reflection;
|
||||
}
|
||||
}
|
||||
|
||||
adf4351.setf(minimum_frequency);
|
||||
delay(50);
|
||||
reflection = readReflection(16);
|
||||
if (reflection < 130)
|
||||
{
|
||||
Serial.println("Resonance could not be found.");
|
||||
Serial.println(reflection);
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Capacitor needs to charge - therefore rerun around area with longer delay. -> REFACTOR THIS!!!!
|
||||
maximum_reflection = 0;
|
||||
for (uint32_t frequency = minimum_frequency - 300000U; frequency <= minimum_frequency + 300000U; frequency += frequency_step)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(100); // Higher delay so the capacitor has time to charge
|
||||
|
||||
current_reflection = readReflection(64);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_frequency = frequency;
|
||||
maximum_reflection = current_reflection;
|
||||
}
|
||||
}
|
||||
|
||||
return minimum_frequency;
|
||||
}
|
||||
|
||||
// Tries out different capacitor position until iteration depth is reached OR current_resonancy frequency matches the target_frequency
|
||||
int32_t bruteforceResonance(uint32_t target_frequency, uint32_t current_resonance_frequency)
|
||||
{
|
||||
// Change Tuning Stepper -> Clockwise => Freq goes up
|
||||
// Dir = 0 => Anticlockwise movement
|
||||
int rotation = 0; // rotation == 1 -> clockwise, rotation == -1 -> counterclockwise
|
||||
|
||||
int ITERATIONS = 25; // Iteration depth
|
||||
int iteration_steps = 0;
|
||||
|
||||
float MATCHING_THRESHOLD = 140; // if the reflection at the current resonance frequency is lower than this threshold re-matching is necessary -> calibrate to ~RL-8dB
|
||||
float resonance_reflection = 0;
|
||||
|
||||
int32_t delta_frequency = target_frequency - current_resonance_frequency;
|
||||
|
||||
if (delta_frequency < 0)
|
||||
rotation = -1; // negative delta means currentresonance is too high, hence anticlockwise movement is necessary
|
||||
else
|
||||
rotation = 1;
|
||||
|
||||
int iteration_start = rotation * (STEPS_PER_ROTATION / 20);
|
||||
|
||||
iteration_steps = iteration_start;
|
||||
DEBUG_PRINT(iteration_start);
|
||||
|
||||
//'bruteforce' the stepper position to match the target frequency
|
||||
|
||||
for (int i = 0; i < ITERATIONS; i++)
|
||||
{
|
||||
tuner.STEPPER.move(iteration_steps);
|
||||
tuner.STEPPER.runToPosition();
|
||||
|
||||
// Only rematch matcher for large step width
|
||||
if (iteration_steps == iteration_start)
|
||||
{
|
||||
matcher.STEPPER.move(-iteration_steps * 3);
|
||||
matcher.STEPPER.runToPosition();
|
||||
}
|
||||
|
||||
// @ Optimization possibility: Reduce frequency range when close to target_frequency
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 5000000U, current_resonance_frequency + 5000000U, FREQUENCY_STEP / 2);
|
||||
|
||||
DEBUG_PRINT(current_resonance_frequency);
|
||||
|
||||
// Stops the iteration if the minima matches the target frequency
|
||||
if (current_resonance_frequency == target_frequency)
|
||||
break;
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
resonance_reflection = readReflection(16);
|
||||
DEBUG_PRINT(resonance_reflection);
|
||||
|
||||
if (resonance_reflection < MATCHING_THRESHOLD)
|
||||
{
|
||||
optimizeMatching(current_resonance_frequency);
|
||||
}
|
||||
|
||||
// This means the bruteforce resolution was too high and the resonance frequency overshoot
|
||||
// therfore the turn direction gets inverted and the increment halfed
|
||||
if ((current_resonance_frequency > target_frequency) && (rotation == 1))
|
||||
{
|
||||
rotation = -1;
|
||||
iteration_steps /= 2;
|
||||
iteration_steps *= rotation;
|
||||
}
|
||||
else if ((current_resonance_frequency < target_frequency) && (rotation == -1))
|
||||
{
|
||||
rotation = 1;
|
||||
iteration_steps /= 2;
|
||||
iteration_steps *= -rotation;
|
||||
}
|
||||
}
|
||||
|
||||
return current_resonance_frequency;
|
||||
}
|
||||
|
||||
//
|
||||
// Matcher clockwise lowers resonance frequency
|
||||
|
||||
int optimizeMatching(uint32_t current_resonance_frequency)
|
||||
{
|
||||
int ITERATIONS = 50;
|
||||
int iteration_steps = 0;
|
||||
|
||||
int maximum_reflection = 0;
|
||||
int current_reflection = 0;
|
||||
int minimum_matching_position = 0;
|
||||
int last_reflection = 10e5;
|
||||
int rotation = 1;
|
||||
|
||||
// Look which rotation direction improves matching.
|
||||
rotation = getMatchRotation(current_resonance_frequency);
|
||||
|
||||
DEBUG_PRINT(rotation);
|
||||
|
||||
// This tries to find the minimum reflection while ignoring the change in resonance -> it always looks for minima within
|
||||
iteration_steps = rotation * (STEPS_PER_ROTATION / 20);
|
||||
|
||||
DEBUG_PRINT(iteration_steps);
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
for (int i = 0; i < ITERATIONS; i++)
|
||||
{
|
||||
DEBUG_PRINT(i);
|
||||
current_reflection = 0;
|
||||
|
||||
matcher.STEPPER.move(iteration_steps);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
delay(50);
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 2);
|
||||
|
||||
// Skip this iteration if the resonance has been lost
|
||||
if (current_resonance_frequency == 0)
|
||||
{
|
||||
delay(1000); // Wait for one second since something has gone wrong
|
||||
continue;
|
||||
}
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
|
||||
current_reflection = readReflection(16);
|
||||
// current_reflection = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_matching_position = matcher.STEPPER.currentPosition();
|
||||
maximum_reflection = current_reflection;
|
||||
DEBUG_PRINT("Maximum");
|
||||
DEBUG_PRINT(minimum_matching_position);
|
||||
}
|
||||
|
||||
DEBUG_PRINT(matcher.STEPPER.currentPosition());
|
||||
DEBUG_PRINT(current_resonance_frequency);
|
||||
DEBUG_PRINT(last_reflection);
|
||||
|
||||
last_reflection = current_reflection;
|
||||
|
||||
if (iteration_steps == 0)
|
||||
break;
|
||||
|
||||
DEBUG_PRINT(current_reflection);
|
||||
}
|
||||
|
||||
matcher.STEPPER.moveTo(minimum_matching_position);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(matcher.STEPPER.currentPosition());
|
||||
|
||||
return (maximum_reflection);
|
||||
}
|
||||
|
||||
// probably do this for multiple positions in each direction
|
||||
int getMatchRotation(uint32_t current_resonance_frequency)
|
||||
{
|
||||
|
||||
matcher.STEPPER.move(STEPS_PER_ROTATION / 2);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 10);
|
||||
// int clockwise_match = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
if (current_resonance_frequency != 0)
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
int clockwise_match = readReflection(64);
|
||||
|
||||
matcher.STEPPER.move(-2 * (STEPS_PER_ROTATION / 2));
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 10);
|
||||
// int anticlockwise_match = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
int anticlockwise_match = readReflection(64);
|
||||
|
||||
matcher.STEPPER.move(STEPS_PER_ROTATION / 2);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(clockwise_match);
|
||||
DEBUG_PRINT(anticlockwise_match);
|
||||
|
||||
if (clockwise_match > anticlockwise_match)
|
||||
return 1;
|
||||
else
|
||||
return -1;
|
||||
}
|
||||
|
||||
int sumReflectionAroundFrequency(uint32_t center_frequency)
|
||||
{
|
||||
int sum_reflection = 0;
|
||||
|
||||
// sum approach -> cummulates reflection around resonance -> reduce influence of wrong minimum and noise
|
||||
for (uint32_t frequency = center_frequency - 500000U; frequency < center_frequency + 500000U; frequency += FREQUENCY_STEP / 10)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(10);
|
||||
sum_reflection += readReflection(16);
|
||||
}
|
||||
|
||||
return sum_reflection;
|
||||
}
|
||||
|
|
25
src/CommandManager.cpp
Normal file
25
src/CommandManager.cpp
Normal file
|
@ -0,0 +1,25 @@
|
|||
#include "CommandManager.h"
|
||||
|
||||
void CommandManager::registerCommand(char identifier, Command* command) {
|
||||
commandMap[identifier] = command;
|
||||
}
|
||||
|
||||
void CommandManager::executeCommand(char identifier, String input_line) {
|
||||
auto it = commandMap.find(identifier);
|
||||
if (it != commandMap.end()) {
|
||||
Command* command = it->second;
|
||||
command->execute(input_line);
|
||||
} else {
|
||||
Serial.println("Unknown command.");
|
||||
}
|
||||
}
|
||||
|
||||
void CommandManager::printCommandResult(char identifier) {
|
||||
auto it = commandMap.find(identifier);
|
||||
if (it != commandMap.end()) {
|
||||
Command* command = it->second;
|
||||
command->printResult();
|
||||
} else {
|
||||
Serial.println("Unknown command.");
|
||||
}
|
||||
}
|
18
src/CommandManager.h
Normal file
18
src/CommandManager.h
Normal file
|
@ -0,0 +1,18 @@
|
|||
#ifndef COMMANDMANAGER_H
|
||||
#define COMMANDMANAGER_H
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <map>
|
||||
#include "commands/Command.h"
|
||||
|
||||
class CommandManager {
|
||||
public:
|
||||
void registerCommand(char identifier, Command* command);
|
||||
void executeCommand(char identifier, String input_line);
|
||||
void printCommandResult(char identifier);
|
||||
|
||||
private:
|
||||
std::map<char, Command*> commandMap;
|
||||
};
|
||||
|
||||
#endif
|
397
src/Utilities.cpp
Normal file
397
src/Utilities.cpp
Normal file
|
@ -0,0 +1,397 @@
|
|||
#include <TMC2130Stepper.h>
|
||||
#include <AccelStepper.h>
|
||||
#include <MultiStepper.h>
|
||||
|
||||
|
||||
#include "Utilities.h"
|
||||
|
||||
// Frequency Settings
|
||||
#define FREQUENCY_STEP 100000U // 100kHz frequency steps for initial frequency sweep
|
||||
#define START_FREQUENCY 50000000U // 50MHz
|
||||
#define STOP_FREQUENCY 110000000 // 110MHz
|
||||
|
||||
int32_t findCurrentResonanceFrequency(uint32_t start_frequency, uint32_t stop_frequency, uint32_t frequency_step)
|
||||
{
|
||||
int maximum_reflection = 0;
|
||||
int current_reflection = 0;
|
||||
int current_phase = 0;
|
||||
uint32_t minimum_frequency = 0;
|
||||
float reflection = 0;
|
||||
|
||||
adf4351.setf(start_frequency); // A frequency value needs to be set once -> there seems to be a bug with the first SPI call
|
||||
delay(50);
|
||||
|
||||
for (uint32_t frequency = start_frequency; frequency <= stop_frequency; frequency += frequency_step)
|
||||
{
|
||||
//adf4351.setf(frequency);
|
||||
setFrequency(frequency);
|
||||
|
||||
// delay(5); // This delay is essential! There is a glitch with ADC2 that leads to wrong readings if GPIO27 is set to high for multiple microseconds.
|
||||
|
||||
current_reflection = readReflection(4);
|
||||
current_phase = readPhase(4);
|
||||
|
||||
// Send out the frequency identifier f with the frequency value
|
||||
Serial.println(String("f") + frequency + "r" + current_reflection + "p" + current_phase);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_frequency = frequency;
|
||||
maximum_reflection = current_reflection;
|
||||
}
|
||||
}
|
||||
|
||||
adf4351.setf(minimum_frequency);
|
||||
delay(50);
|
||||
reflection = readReflection(16);
|
||||
if (reflection < 130)
|
||||
{
|
||||
DEBUG_PRINT("Resonance could not be found.");
|
||||
DEBUG_PRINT(reflection);
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Capacitor needs to charge - therefore rerun around area with longer delay. -> REFACTOR THIS!!!!
|
||||
maximum_reflection = 0;
|
||||
for (uint32_t frequency = minimum_frequency - 300000U; frequency <= minimum_frequency + 300000U; frequency += frequency_step)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(100); // Higher delay so the capacitor has time to charge
|
||||
|
||||
current_reflection = readReflection(64);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_frequency = frequency;
|
||||
maximum_reflection = current_reflection;
|
||||
}
|
||||
}
|
||||
|
||||
return minimum_frequency;
|
||||
}
|
||||
|
||||
void setFrequency(uint32_t frequency)
|
||||
{
|
||||
// First we check what filter has to be used from the FILTERS array
|
||||
// Then we set the filterbank accordingly
|
||||
for (int i = 0; i < sizeof(FILTERS) / sizeof(FILTERS[0]); i++)
|
||||
{
|
||||
// For the first filter we just check if the frequency is below the fg
|
||||
if ((i == 0) && (frequency < FILTERS[i].fg))
|
||||
{
|
||||
digitalWrite(FILTER_SWITCH_A, FILTERS[i].control_input_a);
|
||||
digitalWrite(FILTER_SWITCH_B, FILTERS[i].control_input_b);
|
||||
break;
|
||||
}
|
||||
// For the last filter we just check if the frequency is above the fg
|
||||
else if ((i == sizeof(FILTERS) / sizeof(FILTERS[0]) - 1) && (frequency > FILTERS[i].fg))
|
||||
{
|
||||
digitalWrite(FILTER_SWITCH_A, FILTERS[i].control_input_a);
|
||||
digitalWrite(FILTER_SWITCH_B, FILTERS[i].control_input_b);
|
||||
break;
|
||||
}
|
||||
// For the filters in between we check if the frequency is between the fg and the fg of the previous filter
|
||||
else if ((frequency < FILTERS[i].fg) && (frequency > FILTERS[i - 1].fg))
|
||||
{
|
||||
digitalWrite(FILTER_SWITCH_A, FILTERS[i].control_input_a);
|
||||
digitalWrite(FILTER_SWITCH_B, FILTERS[i].control_input_b);
|
||||
break;
|
||||
}
|
||||
}
|
||||
// Finally we set the frequency
|
||||
adf4351.setf(frequency);
|
||||
|
||||
}
|
||||
|
||||
int readReflection(int averages)
|
||||
{
|
||||
int reflection = 0;
|
||||
for (int i = 0; i < averages; i++)
|
||||
// We multiply by 1000 to get the result in millivolts
|
||||
reflection += (adac.read_ADC(0) * 1000);
|
||||
return reflection / averages;
|
||||
}
|
||||
|
||||
int readPhase(int averages)
|
||||
{
|
||||
int phase = 0;
|
||||
for (int i = 0; i < averages; i++)
|
||||
phase += (adac.read_ADC(1) * 1000);
|
||||
return phase / averages;
|
||||
}
|
||||
|
||||
int sumReflectionAroundFrequency(uint32_t center_frequency)
|
||||
{
|
||||
int sum_reflection = 0;
|
||||
|
||||
// sum approach -> cummulates reflection around resonance -> reduce influence of wrong minimum and noise
|
||||
for (uint32_t frequency = center_frequency - 500000U; frequency < center_frequency + 500000U; frequency += FREQUENCY_STEP / 10)
|
||||
{
|
||||
adf4351.setf(frequency);
|
||||
delay(10);
|
||||
sum_reflection += readReflection(16);
|
||||
}
|
||||
|
||||
return sum_reflection;
|
||||
}
|
||||
|
||||
int32_t bruteforceResonance(uint32_t target_frequency, uint32_t current_resonance_frequency)
|
||||
{
|
||||
// Change Tuning Stepper -> Clockwise => Freq goes up
|
||||
// Dir = 0 => Anticlockwise movement
|
||||
int rotation = 0; // rotation == 1 -> clockwise, rotation == -1 -> counterclockwise
|
||||
|
||||
int ITERATIONS = 25; // Iteration depth
|
||||
int iteration_steps = 0;
|
||||
|
||||
float MATCHING_THRESHOLD = 140; // if the reflection at the current resonance frequency is lower than this threshold re-matching is necessary -> calibrate to ~RL-8dB
|
||||
float resonance_reflection = 0;
|
||||
|
||||
int32_t delta_frequency = target_frequency - current_resonance_frequency;
|
||||
|
||||
if (delta_frequency < 0)
|
||||
rotation = -1; // negative delta means currentresonance is too high, hence anticlockwise movement is necessary
|
||||
else
|
||||
rotation = 1;
|
||||
|
||||
int iteration_start = rotation * (STEPS_PER_ROTATION / 20);
|
||||
|
||||
iteration_steps = iteration_start;
|
||||
DEBUG_PRINT(iteration_start);
|
||||
|
||||
//'bruteforce' the stepper position to match the target frequency
|
||||
|
||||
for (int i = 0; i < ITERATIONS; i++)
|
||||
{
|
||||
tuner.STEPPER.move(iteration_steps);
|
||||
tuner.STEPPER.runToPosition();
|
||||
|
||||
// Only rematch matcher for large step width
|
||||
if (iteration_steps == iteration_start)
|
||||
{
|
||||
matcher.STEPPER.move(-iteration_steps * 3);
|
||||
matcher.STEPPER.runToPosition();
|
||||
}
|
||||
|
||||
// @ Optimization possibility: Reduce frequency range when close to target_frequency
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 5000000U, current_resonance_frequency + 5000000U, FREQUENCY_STEP / 2);
|
||||
|
||||
DEBUG_PRINT(current_resonance_frequency);
|
||||
|
||||
// Stops the iteration if the minima matches the target frequency
|
||||
if (current_resonance_frequency == target_frequency)
|
||||
break;
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
resonance_reflection = readReflection(16);
|
||||
DEBUG_PRINT(resonance_reflection);
|
||||
|
||||
if (resonance_reflection < MATCHING_THRESHOLD)
|
||||
{
|
||||
optimizeMatching(current_resonance_frequency);
|
||||
}
|
||||
|
||||
// This means the bruteforce resolution was too high and the resonance frequency overshoot
|
||||
// therfore the turn direction gets inverted and the increment halfed
|
||||
if ((current_resonance_frequency > target_frequency) && (rotation == 1))
|
||||
{
|
||||
rotation = -1;
|
||||
iteration_steps /= 2;
|
||||
iteration_steps *= rotation;
|
||||
}
|
||||
else if ((current_resonance_frequency < target_frequency) && (rotation == -1))
|
||||
{
|
||||
rotation = 1;
|
||||
iteration_steps /= 2;
|
||||
iteration_steps *= -rotation;
|
||||
}
|
||||
}
|
||||
|
||||
return current_resonance_frequency;
|
||||
}
|
||||
|
||||
int optimizeMatching(uint32_t current_resonance_frequency)
|
||||
{
|
||||
int ITERATIONS = 50;
|
||||
int iteration_steps = 0;
|
||||
|
||||
int maximum_reflection = 0;
|
||||
int current_reflection = 0;
|
||||
int minimum_matching_position = 0;
|
||||
int last_reflection = 10e5;
|
||||
int rotation = 1;
|
||||
|
||||
// Look which rotation direction improves matching.
|
||||
rotation = getMatchRotation(current_resonance_frequency);
|
||||
|
||||
DEBUG_PRINT(rotation);
|
||||
|
||||
// This tries to find the minimum reflection while ignoring the change in resonance -> it always looks for minima within
|
||||
iteration_steps = rotation * (STEPS_PER_ROTATION / 20);
|
||||
|
||||
DEBUG_PRINT(iteration_steps);
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
for (int i = 0; i < ITERATIONS; i++)
|
||||
{
|
||||
DEBUG_PRINT(i);
|
||||
current_reflection = 0;
|
||||
|
||||
matcher.STEPPER.move(iteration_steps);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
delay(50);
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 2);
|
||||
|
||||
// Skip this iteration if the resonance has been lost
|
||||
if (current_resonance_frequency == 0)
|
||||
{
|
||||
delay(1000); // Wait for one second since something has gone wrong
|
||||
continue;
|
||||
}
|
||||
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
|
||||
current_reflection = readReflection(16);
|
||||
// current_reflection = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
|
||||
if (current_reflection > maximum_reflection)
|
||||
{
|
||||
minimum_matching_position = matcher.STEPPER.currentPosition();
|
||||
maximum_reflection = current_reflection;
|
||||
DEBUG_PRINT("Maximum");
|
||||
DEBUG_PRINT(minimum_matching_position);
|
||||
}
|
||||
|
||||
DEBUG_PRINT(matcher.STEPPER.currentPosition());
|
||||
DEBUG_PRINT(current_resonance_frequency);
|
||||
DEBUG_PRINT(last_reflection);
|
||||
|
||||
last_reflection = current_reflection;
|
||||
|
||||
if (iteration_steps == 0)
|
||||
break;
|
||||
|
||||
DEBUG_PRINT(current_reflection);
|
||||
}
|
||||
|
||||
matcher.STEPPER.moveTo(minimum_matching_position);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(matcher.STEPPER.currentPosition());
|
||||
|
||||
return (maximum_reflection);
|
||||
}
|
||||
|
||||
int getMatchRotation(uint32_t current_resonance_frequency)
|
||||
{
|
||||
|
||||
matcher.STEPPER.move(STEPS_PER_ROTATION / 2);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 10);
|
||||
// int clockwise_match = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
if (current_resonance_frequency != 0)
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
int clockwise_match = readReflection(64);
|
||||
|
||||
matcher.STEPPER.move(-2 * (STEPS_PER_ROTATION / 2));
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
current_resonance_frequency = findCurrentResonanceFrequency(current_resonance_frequency - 1000000U, current_resonance_frequency + 1000000U, FREQUENCY_STEP / 10);
|
||||
// int anticlockwise_match = sumReflectionAroundFrequency(current_resonance_frequency);
|
||||
adf4351.setf(current_resonance_frequency);
|
||||
delay(100);
|
||||
int anticlockwise_match = readReflection(64);
|
||||
|
||||
matcher.STEPPER.move(STEPS_PER_ROTATION / 2);
|
||||
matcher.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(clockwise_match);
|
||||
DEBUG_PRINT(anticlockwise_match);
|
||||
|
||||
if (clockwise_match > anticlockwise_match)
|
||||
return 1;
|
||||
else
|
||||
return -1;
|
||||
}
|
||||
|
||||
int stallStepper(Stepper stepper)
|
||||
{
|
||||
stepper.STEPPER.moveTo(-9999999);
|
||||
|
||||
while (!digitalRead(stepper.STALL_PIN))
|
||||
{
|
||||
stepper.STEPPER.run();
|
||||
}
|
||||
|
||||
DEBUG_PRINT(stepper.STEPPER.currentPosition());
|
||||
|
||||
stepper.STEPPER.stop();
|
||||
|
||||
return stepper.STEPPER.currentPosition(); // returns value until limit is reached
|
||||
}
|
||||
|
||||
long homeStepper(Stepper stepper)
|
||||
{
|
||||
stallStepper(stepper);
|
||||
stepper.STEPPER.setCurrentPosition(0);
|
||||
stepper.STEPPER.moveTo(1000);
|
||||
stepper.STEPPER.runToPosition();
|
||||
|
||||
stepper.STEPPER.setMaxSpeed(3000);
|
||||
stepper.STEPPER.setAcceleration(3000);
|
||||
|
||||
stepper.DRIVER.sg_stall_value(-64); // Stall value needs to be lowered because of slower stepper
|
||||
stallStepper(stepper);
|
||||
stepper.DRIVER.sg_stall_value(STALL_VALUE);
|
||||
|
||||
stepper.STEPPER.setMaxSpeed(12000);
|
||||
stepper.STEPPER.setAcceleration(12000);
|
||||
|
||||
stepper.STEPPER.setCurrentPosition(0);
|
||||
|
||||
stepper.STEPPER.moveTo(1000);
|
||||
|
||||
stepper.STEPPER.runToPosition();
|
||||
|
||||
DEBUG_PRINT(stepper.STEPPER.currentPosition());
|
||||
|
||||
return stepper.STEPPER.currentPosition();
|
||||
}
|
||||
|
||||
uint32_t validateInput(float frequency_MHz)
|
||||
{
|
||||
uint32_t frequency_Hz = frequency_MHz * 1000000U;
|
||||
|
||||
if (frequency_Hz < START_FREQUENCY)
|
||||
{
|
||||
printError("Invalid input: frequency too low");
|
||||
return 0;
|
||||
}
|
||||
else if (frequency_Hz > 300000000U)
|
||||
{
|
||||
printError("Invalid input: frequency too high");
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
return frequency_Hz;
|
||||
}
|
||||
}
|
||||
|
||||
void printInfo(String text) {
|
||||
Serial.println("i" + text);
|
||||
}
|
||||
|
||||
void printInfo(uint32_t number) {
|
||||
Serial.println("i" + String(number)); // convert the number to a string before concatenating
|
||||
}
|
||||
|
||||
void printError(String text) {
|
||||
Serial.println("e" + text);
|
||||
}
|
148
src/Utilities.h
Normal file
148
src/Utilities.h
Normal file
|
@ -0,0 +1,148 @@
|
|||
#include <math.h>
|
||||
#include <Arduino.h>
|
||||
#include "Debug.h"
|
||||
#include "global.h"
|
||||
|
||||
/**
|
||||
* @brief This function finds the current resonance frequency of the coil. There should be a resonance already present or the algorithm might return nonsense.
|
||||
* It also returns the data of the frequency scan which can then be sent to the PC for plotting.
|
||||
*
|
||||
* @param start_frequency The frequency at which the search should start
|
||||
* @param stop_frequency The frequency at which the search should stop
|
||||
* @param frequency_step The frequency step size
|
||||
* @return int32_t The current resonance frequency
|
||||
*
|
||||
* @example findCurrentResonanceFrequency(START_FREQUENCY, STOP_FREQUENCY, FREQUENCY_STEP); // finds the current resonance frequency
|
||||
*/
|
||||
int32_t findCurrentResonanceFrequency(uint32_t start_frequency, uint32_t stop_frequency, uint32_t frequency_step);
|
||||
|
||||
/**
|
||||
* @brief This function sets the frequency of the frequency synthesizer and switches the filterbank accordingly.
|
||||
*
|
||||
* @param frequency The frequency that should be set
|
||||
* @return void
|
||||
*
|
||||
* @example setFrequency(100000000U); // sets the frequency to 100MHz
|
||||
*/
|
||||
void setFrequency(uint32_t frequency);
|
||||
|
||||
/**
|
||||
* @brief This function reads the reflection at the current frequency. It does not set the frequency.
|
||||
*
|
||||
* @param averages The number of readings that should be averaged
|
||||
* @return int The average reflection in millivolts
|
||||
*
|
||||
* @example readReflection(64); // reads the reflection at the current frequency and averages over 64 readings
|
||||
*/
|
||||
int readReflection(int averages);
|
||||
|
||||
/**
|
||||
* @brief This function reads the phase at the current frequency. It does not set the frequency.
|
||||
*
|
||||
* @param averages The number of readings that should be averaged
|
||||
* @return int The average phase in millivolts
|
||||
*
|
||||
* @example readPhase(64); // reads the phase at the current frequency and averages over 64 readings
|
||||
*/
|
||||
int readPhase(int averages);
|
||||
|
||||
/**
|
||||
* @brief This function sums up the reflection around a given frequency.
|
||||
*
|
||||
* @param center_frequency The frequency around which the reflection should be summed up
|
||||
* @return int The sum of the reflection around the given frequency
|
||||
*
|
||||
* @example sumReflectionAroundFrequency(100000000U);
|
||||
*/
|
||||
int sumReflectionAroundFrequency(uint32_t center_frequency);
|
||||
|
||||
/**
|
||||
* @brief This function tries out different capacitor positions until iteration depth is reached OR current_resonancy frequency matches the target_frequency.
|
||||
*
|
||||
* @param target_frequency The frequency that should be matched
|
||||
* @param current_resonance_frequency The current resonance frequency
|
||||
* @return int32_t The current resonance frequency
|
||||
*
|
||||
* @example bruteforceResonance(100000000U, 90000000U); // tries to match 100MHz with a current resonance frequency of 90MHz
|
||||
*/
|
||||
int32_t bruteforceResonance(uint32_t target_frequency, uint32_t current_resonance_frequency);
|
||||
|
||||
/**
|
||||
* @brief This function tries to find a matching capacitor position that will decrease the reflection at the current resonance frequency to a minimum.
|
||||
* It will then move the stepper to this position.
|
||||
*
|
||||
* @param current_resonance_frequency The current resonance frequency
|
||||
* @return int The reflection at the minimum matching position
|
||||
*
|
||||
* @example optimizeMatching(100000000); // tries to find the minimum reflection at 100 MHz and moves the stepper to this position
|
||||
*/
|
||||
int optimizeMatching(uint32_t current_resonance_frequency);
|
||||
|
||||
/**
|
||||
* @brief This function finds the direction which the matching capacitor should be turned to decrease the reflection.
|
||||
*
|
||||
* @param current_resonance_frequency The current resonance frequency
|
||||
* @return int The direction in which the matching capacitor should be turned. 1 for clockwise, -1 for anticlockwise
|
||||
*
|
||||
* @example getMatchRotation(100000000); // returns the direction in which the matching capacitor should be turned at 100MHz to decrease the reflection
|
||||
*/
|
||||
int getMatchRotation(uint32_t current_resonance_frequency);
|
||||
|
||||
/**
|
||||
* @brief This function controls the stepper so that they hit the limit and stall. It then returns the current position of the stepper.
|
||||
*
|
||||
* @param stepper The stepper that should be stalled
|
||||
* @return int The current position of the stepper
|
||||
*
|
||||
* @example stallStepper(tuner); // stalls the tuner stepper and returns the current position
|
||||
*/
|
||||
int stallStepper(Stepper stepper);
|
||||
|
||||
/**
|
||||
* @brief This function performs a homing of the steppers. It returns the current position of the stepper.
|
||||
*
|
||||
* @param stepper The stepper that should be homed
|
||||
* @return long The current position of the stepper
|
||||
*
|
||||
* @example homeStepper(tuner); // homes the tuner stepper and returns the current position
|
||||
*/
|
||||
long homeStepper(Stepper stepper);
|
||||
|
||||
/**
|
||||
* @brief This function checks if the input is valid. It checks if the frequency is within the allowed range.
|
||||
*
|
||||
* @param frequency_MHz The frequency that should be checked in MHz.
|
||||
* @return uint32_t The frequency in Hz if the input is valid, 0 otherwise.
|
||||
*
|
||||
* @example validateInput(100); // returns 100000000U
|
||||
*/
|
||||
uint32_t validateInput(float frequency_MHz);
|
||||
/**
|
||||
* * @brief This method should be called when one wants to print information to the serial port.
|
||||
*
|
||||
* @param text The text that should be printed to the serial monitor. It should be a string
|
||||
* @return void
|
||||
*
|
||||
* @example printInfo("This is a test"); // prints "iThis is a test"
|
||||
*/
|
||||
void printInfo(String text);
|
||||
|
||||
/**
|
||||
* @brief This method should be called when one wants to print information to the serial port.
|
||||
*
|
||||
* @param number The number that should be printed to the serial monitor. It should be a number
|
||||
* @return void
|
||||
*
|
||||
* @example printInfo(123U); // prints "i123"
|
||||
*/
|
||||
void printInfo(uint32_t number);
|
||||
|
||||
/**
|
||||
* @brief This method should be called when one wants to an error to the serial port.
|
||||
*
|
||||
* @param text The text that should be printed to the serial monitor. It should be a string
|
||||
* @return void
|
||||
*
|
||||
* @example printError("Duck not found"); // prints "eDuck not found"
|
||||
*/
|
||||
void printError(String text);
|
30
src/commands/Command.h
Normal file
30
src/commands/Command.h
Normal file
|
@ -0,0 +1,30 @@
|
|||
// Command.h
|
||||
#ifndef COMMAND_H
|
||||
#define COMMAND_H
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class Command {
|
||||
public:
|
||||
/**
|
||||
* @brief Executes the command.
|
||||
* Pure virtual function that must be implemented by derived classes.
|
||||
*/
|
||||
virtual void execute(String input_line) = 0;
|
||||
|
||||
/**
|
||||
* @brief Prints the result of the command.
|
||||
* Pure virtual function that must be implemented by derived classes.
|
||||
*/
|
||||
virtual void printResult() = 0;
|
||||
|
||||
/**
|
||||
* @brief Prints the help message of the command.
|
||||
* Pure virtual function that must be implemented by derived classes.
|
||||
*/
|
||||
virtual void printHelp() = 0;
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
33
src/commands/FrequencySweep.cpp
Normal file
33
src/commands/FrequencySweep.cpp
Normal file
|
@ -0,0 +1,33 @@
|
|||
#include "Utilities.h"
|
||||
#include "FrequencySweep.h"
|
||||
|
||||
void FrequencySweep::execute(String input_line) {
|
||||
printInfo("Started frequency sweep");
|
||||
// Get the start frequency which is the value until the next f character
|
||||
char delimiter = 'f';
|
||||
// Indices for each variable
|
||||
int startFreqIndex = input_line.indexOf(delimiter) + 1;
|
||||
int stopFreqIndex = input_line.indexOf(delimiter, startFreqIndex) + 1;
|
||||
int freqStepIndex = input_line.indexOf(delimiter, stopFreqIndex) + 1;
|
||||
|
||||
// Extract each variable from the string
|
||||
uint32_t startFreq = input_line.substring(startFreqIndex, stopFreqIndex - 1).toInt(); // Subtract 1 to not include the delimiter
|
||||
uint32_t stopFreq = input_line.substring(stopFreqIndex, freqStepIndex - 1).toInt();
|
||||
uint32_t freqStep = input_line.substring(freqStepIndex).toInt(); // If no second parameter is provided, substring() goes to the end of the string
|
||||
|
||||
// The find current resonance frequency also prints prints the S11 data to the serial monitor
|
||||
resonance_frequency = findCurrentResonanceFrequency(startFreq, stopFreq, freqStep);
|
||||
}
|
||||
|
||||
void FrequencySweep::printResult() {
|
||||
// This tells the PC that the frequency sweep is finished
|
||||
Serial.print("r");
|
||||
printInfo(resonance_frequency);
|
||||
}
|
||||
|
||||
void FrequencySweep::printHelp() {
|
||||
Serial.println("Frequency sweep command");
|
||||
Serial.println("Syntax: f<start frequency>f<stop frequency>f<frequency step>");
|
||||
Serial.println("Example: f100000000f200000000f50000");
|
||||
Serial.println("This will sweep the frequency from 100 MHz to 200 MHz with a step of 50 kHz");
|
||||
}
|
18
src/commands/FrequencySweep.h
Normal file
18
src/commands/FrequencySweep.h
Normal file
|
@ -0,0 +1,18 @@
|
|||
#ifndef FREQUENCYSWEEP_H
|
||||
#define FREQUENCYSWEEP_H
|
||||
|
||||
#include "Command.h"
|
||||
|
||||
/**
|
||||
* @brief This class is used to perform a frequency sweep
|
||||
*/
|
||||
class FrequencySweep : public Command {
|
||||
public:
|
||||
void execute(String input_lne) override;
|
||||
void printResult() override;
|
||||
void printHelp() override;
|
||||
private:
|
||||
uint32_t resonance_frequency;
|
||||
};
|
||||
|
||||
#endif
|
27
src/commands/Homing.cpp
Normal file
27
src/commands/Homing.cpp
Normal file
|
@ -0,0 +1,27 @@
|
|||
#include "Utilities.h"
|
||||
#include "Homing.h"
|
||||
|
||||
void Homing::execute(String input_line) {
|
||||
printInfo("Homing...");
|
||||
tuner.STEPPER.setCurrentPosition(homeStepper(tuner));
|
||||
matcher.STEPPER.setCurrentPosition(homeStepper(matcher));
|
||||
}
|
||||
|
||||
void Homing::printResult() {
|
||||
printInfo("Resonance frequency after homing:");
|
||||
uint32_t startf = 35000000U;
|
||||
uint32_t stopf = 110000000U;
|
||||
uint32_t stepf = 100000U;
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(startf, stopf, stepf / 2);
|
||||
printInfo(resonance_frequency);
|
||||
Serial.print("r");
|
||||
printInfo("Homing finished");
|
||||
}
|
||||
|
||||
void Homing::printHelp() {
|
||||
Serial.println("Homing command");
|
||||
Serial.println("Syntax: h");
|
||||
Serial.println("Example: h");
|
||||
Serial.println("This will home the tuner and matcher");
|
||||
}
|
||||
|
15
src/commands/Homing.h
Normal file
15
src/commands/Homing.h
Normal file
|
@ -0,0 +1,15 @@
|
|||
#ifndef HOMING_H
|
||||
#define HOMING_H
|
||||
|
||||
#include "Command.h"
|
||||
|
||||
class Homing : public Command {
|
||||
public:
|
||||
void execute(String input_line) override;
|
||||
void printResult() override;
|
||||
void printHelp() override;
|
||||
private:
|
||||
uint32_t resonance_frequency;
|
||||
};
|
||||
|
||||
#endif
|
50
src/commands/TuneMatch.cpp
Normal file
50
src/commands/TuneMatch.cpp
Normal file
|
@ -0,0 +1,50 @@
|
|||
#include "Utilities.h"
|
||||
#include "TuneMatch.h"
|
||||
|
||||
void TuneMatch::execute(String input_line){
|
||||
float target_frequency_MHz = input_line.substring(1).toFloat();
|
||||
uint32_t target_frequency = validateInput(target_frequency_MHz);
|
||||
if (target_frequency == 0)
|
||||
return;
|
||||
|
||||
uint32_t startf = 35000000U;
|
||||
uint32_t stopf = 110000000U;
|
||||
uint32_t stepf = 100000U;
|
||||
printInfo("Tuning and Matching to target frequency in MHz (automatic mode):");
|
||||
printInfo(target_frequency_MHz);
|
||||
|
||||
uint32_t resonance_frequency = automaticTM(target_frequency, startf, stopf, stepf);
|
||||
}
|
||||
|
||||
|
||||
uint32_t TuneMatch::automaticTM(uint32_t target_frequency, uint32_t start_frequency, uint32_t stop_frequency, uint32_t frequency_step)
|
||||
{
|
||||
uint32_t resonance_frequency = findCurrentResonanceFrequency(start_frequency, stop_frequency, frequency_step);
|
||||
|
||||
DEBUG_PRINT("Resonance Frequency before TM");
|
||||
DEBUG_PRINT(resonance_frequency);
|
||||
|
||||
resonance_frequency = bruteforceResonance(target_frequency, resonance_frequency);
|
||||
|
||||
optimizeMatching(resonance_frequency);
|
||||
|
||||
resonance_frequency = findCurrentResonanceFrequency(resonance_frequency - 1000000U, resonance_frequency + 1000000U, frequency_step / 2);
|
||||
|
||||
resonance_frequency = bruteforceResonance(target_frequency, resonance_frequency);
|
||||
|
||||
return resonance_frequency;
|
||||
}
|
||||
|
||||
void TuneMatch::printResult()
|
||||
{
|
||||
Serial.print("r");
|
||||
printInfo(resonance_frequency);
|
||||
}
|
||||
|
||||
void TuneMatch::printHelp()
|
||||
{
|
||||
Serial.println("Tune and Match command");
|
||||
Serial.println("Syntax: d<target frequency in MHz>");
|
||||
Serial.println("Example: d100");
|
||||
Serial.println("This will tune and match to 100 MHz");
|
||||
}
|
17
src/commands/TuneMatch.h
Normal file
17
src/commands/TuneMatch.h
Normal file
|
@ -0,0 +1,17 @@
|
|||
#ifndef TUNEMATCH_H
|
||||
#define TUNEMATCH_H
|
||||
|
||||
#include "Command.h"
|
||||
|
||||
class TuneMatch : public Command {
|
||||
public:
|
||||
void execute(String input_line) override;
|
||||
void printResult() override;
|
||||
void printHelp() override;
|
||||
private:
|
||||
uint32_t automaticTM(uint32_t target_frequency, uint32_t start_frequency, uint32_t stop_frequency, uint32_t frequency_step);
|
||||
uint32_t resonance_frequency;
|
||||
|
||||
};
|
||||
|
||||
#endif
|
21
src/global.h
Normal file
21
src/global.h
Normal file
|
@ -0,0 +1,21 @@
|
|||
#ifndef GLOBAL_H
|
||||
#define GLOBAL_H
|
||||
|
||||
#include <TMC2130Stepper.h>
|
||||
#include <AccelStepper.h>
|
||||
#include <MultiStepper.h>
|
||||
#include <math.h>
|
||||
#include "ADF4351.h"
|
||||
#include "AD5593R.h"
|
||||
|
||||
#include "Pins.h" // Pins are defined here
|
||||
#include "Stepper.h"
|
||||
#include "Positions.h" // Calibrated frequency positions are defined her
|
||||
|
||||
// We want these objects to be accessible from all files
|
||||
extern ADF4351 adf4351;
|
||||
extern Stepper tuner;
|
||||
extern Stepper matcher;
|
||||
extern AD5593R adac;
|
||||
|
||||
#endif
|
Loading…
Reference in a new issue