Browse Source

working to update all files

curiousmuch 4 years ago
parent
commit
9027145535

+ 103 - 18
components/aprs/afsk_demodulator.c

@@ -10,9 +10,15 @@
 #include "math.h"
 #include "afsk_demodulator.h"
 
-int8_t window[WINDOW_SIZE];
-//int32_t lpf_window[WINDOW_SIZE];
+/* Public Variables */
+int8_t window[WINDOW_SIZE];				// sliding window
+float coeff0 = 0, coeff1 = 0;			// goerztel coefficients
+float lpf_coef0[5], lpf_coef1[5];		// lpf coefficients
+float lpf_delay0[2], lpf_delay1[2];		// lpf delay line
+int raw_bit = 0;						// afsk demodulator result
 
+
+/* Private Functions */
 void goertzel_init(float freq0, float freq1, float *coeff0, float *coeff1)
 {
 	float normalizedfreq;
@@ -26,22 +32,6 @@ void goertzel_init(float freq0, float freq1, float *coeff0, float *coeff1)
 	*coeff1 = (float) 2*cos(2*M_PI*normalizedfreq);
 }
 
-float goertzelFilter(int samples[], float freq, int N) {
-    float s_prev = 0.0;
-    float s_prev2 = 0.0;
-    float coeff,normalizedfreq,power,s;
-    int i;
-    normalizedfreq = freq / SAMPLEFREQUENCY;
-    coeff = 2*cos(2*M_PI*normalizedfreq);
-    for (i=0; i<N; i++) {
-        s = samples[i] + coeff * s_prev - s_prev2;
-        s_prev2 = s_prev;
-        s_prev = s;
-    }
-    power = s_prev2*s_prev2+s_prev*s_prev-coeff*s_prev*s_prev2;
-    return power;
-}
-
 float goertzel_filter(int8_t samples[], float coeff, unsigned int N)
 {
     float s_prev = 0.0;
@@ -86,3 +76,98 @@ unsigned int window_get_size(void)
 	return sizeof(window);
 }
 
+void dsps_biquad_gen_lpf_f32(float *coeffs, float f, float qFactor)
+{
+    if (qFactor <= 0.0001) {
+        qFactor = 0.0001;
+    }
+    float Fs = 1;
+
+    float w0 = 2 * M_PI * f / Fs;
+    float c = cosf(w0);
+    float s = sinf(w0);
+    float alpha = s / (2 * qFactor);
+
+    float b0 = (1 - c) / 2;
+    float b1 = 1 - c;
+    float b2 = b0;
+    float a0 = 1 + alpha;
+    float a1 = -2 * c;
+    float a2 = 1 - alpha;
+
+    coeffs[0] = b0 / a0;
+    coeffs[1] = b1 / a0;
+    coeffs[2] = b2 / a0;
+    coeffs[3] = a1 / a0;
+    coeffs[4] = a2 / a0;
+    return;
+}
+
+void dsps_biquad_f32_ansi(const float *input, float *output, int len, float *coef, float *w)
+{
+    for (int i = 0 ; i < len ; i++) {
+        float d0 = input[i] - coef[3] * w[0] - coef[4] * w[1];
+        output[i] = coef[0] * d0 +  coef[1] * w[0] + coef[2] * w[1];
+        w[1] = w[0];
+        w[0] = d0;
+    }
+    return;
+}
+
+void lpf_init(void)
+{
+	// generate filter coef
+	dsps_biquad_gen_lpf_f32(lpf_coef0, 0.10, 0.54119610);
+	dsps_biquad_gen_lpf_f32(lpf_coef1, 0.10, 1.3065630);
+
+
+	// setup delay line and lpf_input window
+	int i;
+	for(i=0;i<2;i++)
+	{
+		lpf_delay0[i] = 0;
+		lpf_delay1[i] = 0;
+	}
+}
+
+float lpf_baseband(float input)
+{
+	float output, temp;
+	dsps_biquad_f32_ansi(&input, &temp, 1, lpf_coef0, lpf_delay0);
+	dsps_biquad_f32_ansi(&temp, &output, 1, lpf_coef1, lpf_delay1);
+
+	return output;
+}
+
+/* Public Functions */
+void afsk_demod_init(uint32_t sample_rate, uint32_t symbol0_freq, uint32_t symbol1_freq)
+{
+	goertzel_init(symbol0_freq, symbol1_freq, &coeff0, &coeff1);
+	window_init();
+	lpf_init();
+}
+
+#define THRESHOLD 5
+
+uint8_t afsk_demod_add_sample(int8_t sample)
+{
+	float E_s0, E_s1, lpf_output;
+	window_add(sample);
+	E_s0 = goertzel_filter(window, coeff0, WINDOW_SIZE);
+	E_s1 = goertzel_filter(window, coeff1, WINDOW_SIZE);
+	lpf_output = lpf_baseband((E_s0 - E_s1));
+
+	if (lpf_output > THRESHOLD)
+	{
+		raw_bit = 1;
+		//enable_debug_IO(DEBUG_2);
+
+	}
+	else if (lpf_output < THRESHOLD)
+	{
+		raw_bit = 0;
+		//disable_debug_IO(DEBUG_2);
+	}
+	return raw_bit;						// if not above threshold keep old state.
+}
+

+ 68 - 0
components/aprs/afsk_modulator.c

@@ -0,0 +1,68 @@
+/*
+ * afsk_modulator.c
+ *
+ *  Created on: Oct 10, 2019
+ *      Author: curiousmuch
+ */
+
+#include <stdio.h>
+#include <stdint.h>
+#include <math.h>
+#include "esp_log.h"
+#include "freertos/FreeRTOS.h"
+#include "sdkconfig.h"
+
+/* LUT Defines */
+#define LUT_SIZE 256		// was 7 bits, but increase to 8 for more phase resolution...
+#define DAC_MAX 64			// cc1200 DAC is only 7 bits (+/- 64)
+
+/* Public Variables */
+float delta_phi_1, delta_phi_2;		// phase deltas for two tones used in AFSK modulation
+float phase = 0;					// current phase as AFSK modulator must be phase continous
+int32_t phase_i = 0;				// integer of phase which is used by LUT
+DRAM_ATTR int8_t LUT[LUT_SIZE];		// look up table used for tone generation
+
+/* Private Functions */
+// Returns the phase for the LUT based on the current symbol being
+// sent
+static int32_t IRAM_ATTR afsk_get_phase(uint8_t tone)
+{
+	if ( tone )
+		delta_phi = delta_phi_1;
+	else
+		delta_phi = delta_phi_2;
+
+    phase_i = (int32_t)phase;        // get integer part of our phase
+
+    phase += delta_phi;              // increment phase
+
+    if (phase >= (float)LUT_SIZE)    // handle wraparound
+        phase -= (float)LUT_SIZE;
+
+    return phase_i;
+}
+
+/* Public Functions */
+// This function calculates the phase increment based on the sample rate for
+// the two freqs used for AFSK. In addition, the function setups a LUT for
+// tone generation
+void afsk_mod_init(uint32_t sample_rate, uint32_t freq0, uint32_t freq1)
+{
+	// calculate phase deltas for 1200 and 2200 frequencies
+	delta_phi_1 = (float) freq0 / sample_rate * LUT_SIZE;
+	delta_phi_2 = (float) freq1 / sample_rate * LUT_SIZE;
+
+	// calculate LUT
+	uint32_t i=0;
+	for (i=0; i<LUT_SIZE; ++i)
+	{
+		LUT[i] = (int8_t)roundf(DAC_MAX * sinf(2.0f * M_PI * (float)i / LUT_SIZE));
+	}
+}
+
+// returns the amplitude for the current tone, but must be called
+// based on the sample frequency
+int8_t IRAM_ATTR afsk_get_amplitude(uint8_t tone)
+{
+	return LUT[afsk_get_phase(tone)];
+}

+ 4 - 9
components/aprs/aprs_decoder.c

@@ -6,15 +6,11 @@
  */
 
 #include "aprs_decoder.h"
-//#include "fcs_calc.h"
-
-//#define uint8_t unsigned int
-//#define uint32_t unsigned int
 
+/* Public Variables */
 decoder_varibles_t v;
 
-#define APRS_MAX_FRAME 256
-
+/* Private Functions */
 uint32_t fcs_calc(uint8_t *data, uint32_t len)
 {
 	uint32_t crc, aprs_polynomial, i, j, byte_lsb, crc_lsb;
@@ -42,7 +38,7 @@ void frame_buffer_init(uint8_t *buf, uint32_t len)
 	v.frame_buffer_len = len;
 }
 
-void aprs_decoder_init(void)
+void aprs_decoder_reset(void)
 {
 	v.decoder_state = FLAG_SEARCH;
 	v.frame_buffer_index = 0;
@@ -79,7 +75,7 @@ uint8_t flag_found(void)
 	}
 }
 
-decoder_output_t aprs_decoder_feed_bit(uint8_t nrzi_bit)
+decoder_output_t ax25_decoder_feed_bit(uint8_t nrzi_bit)
 {
 	v.current_nrzi_bit = nrzi_bit;
 
@@ -97,7 +93,6 @@ decoder_output_t aprs_decoder_feed_bit(uint8_t nrzi_bit)
 	v.previous_nrzi_bit = v.current_nrzi_bit;
 
 	// load bit into flag buffer
-	// TODO: Is this in the correct format????
 	v.flag_buffer = (v.flag_buffer >> 1) + (v.current_bit*0x80);
 
 	switch(v.decoder_state)

+ 232 - 0
components/aprs/aprs_encoder.c

@@ -0,0 +1,232 @@
+/*
+ * aprs_encoder.c
+ *
+ *  Created on: Oct 21, 2019
+ *      Author: curiousmuch
+ */
+
+#include <stdint.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "freertos/FreeRTOS.h"
+#include "esp_log.h"
+#include "sdkconfig.h"
+
+/* Debugging Tag */
+#define ENC_TAG "AX.25 Encoder"
+
+/* Public Variables */
+ax25_enc_var_t enc_var = {.state = NOCONFIG};		// TODO: Should this be stored in DRAM?
+ax25_enc_param_t enc_param;
+
+/* Private Functions */
+void ax25_encoder_reset(void)
+{
+	// reset buffer variables
+	enc_var.frame = NULL;
+	enc_var.frame_len = 0;
+
+	// reset internal variables
+	enc_var.index = 0;
+	enc_var.bit_index = 0;
+	enc_var.one_count = 0;
+	enc_var.cur_bit = 0;
+	enc_var.prev_bit = 0;
+	enc_var.nrzi_bit = 0;
+	enc_var.byte = 0;
+
+	// reset state machine state
+	enc_var.state = PREAMBLE;
+}
+
+/* Public Functions */
+void ax25_encoder_init(uint8_t tx_delay, uint8_t tx_tail)
+{
+	// set preamble and tx_tail length
+	enc_param.tx_delay = round(tx_delay * 1.5 + 1);	// calculate the number of
+	enc_param.tx_tail = round(tx_tail * 1.5 + 1);
+
+	enc_var.state = STOP;
+}
+
+// feed frame to state machine
+ax25_enc_status_t ax25_encoder_encode(uint8_t *frame, int32_t frame_len)
+{
+	if (enc_var.status != STOP)
+	{
+		ESP_LOGE(ENC_TAG, "two packets can not be encoded at once");
+		enc_var.status = ERROR;
+		return enc_var.status;
+		// TODO: Assert???
+	}
+
+	// re-init state machine variables
+	ax25_encoder_reset();
+
+	// store frame ptr
+	enc_var.frame = frame;
+	enc_var.frame_len = frame_len;
+
+	// setup state-machine
+	enc_var.status = READY;
+  	return enc_var.status;
+}
+
+ax25_enc_state_t ax25_encoder_get_status(void)
+{
+	return enc_var.status;
+}
+
+// TODO: clean up reused code to inline functions
+uint8_t ax25_encoder_get_bit(void)
+{
+	switch (enc_var.state)
+	{
+		case PREAMBLE: {
+			// reset when index runs down
+			if (enc_var.bit_index == 0)
+			{
+				enc_var.byte = 0x7E;
+			}
+
+			enc_var.cur_bit = enc_var.byte & 0x01;
+
+			// NRZ-I encode
+			if (enc_var.cur_bit)
+			{
+				// do nothing
+				enc_var.one_count++;
+
+			}
+			else
+			{
+				enc_var.nrzi_bit = enc_var.nrzi_bit ^ 1; // switch tone
+				enc_var.one_count = 0;
+			}
+
+			// prepare for next bit
+			enc_var.byte = (enc_var.byte >> 1);
+			enc_var.bit_index++;
+
+			if (enc_var.bit_index >= 8)
+			{
+				enc_var.bit_index = 0;
+				enc_var.flag_count++;
+
+				// exit to frame when flags have been sent for tx_delay
+				if (enc_var.flag_count >= enc_param.tx_delay)
+				{
+					enc_var.state = FRAME;
+					enc_var.bit_index = 0;
+					enc_var.index = 0;
+				}
+
+			}
+			return enc_var.nrzi_bit;
+			break;
+		}
+		case FRAME: {
+
+			// load byte from frame buffer when finished sending byte
+			if (enc_var.bit_index == 0)
+			{
+				enc_var.byte = enc_var.frame[enc_var.index];
+			}
+
+			// zero-stuff if needed
+			if (enc_var.one_count == 5)
+			{
+				enc_var.nrzi_bit = enc_var.nrzi_bit ^ 1;
+				enc_var.one_count = 0;
+				return enc_var.nrzi_bit;
+			}
+
+			// select next bit from current byte
+			enc_var.cur_bit = enc_var.byte & 0x01;
+
+			// NRZI encode
+			if (enc_var.cur_bit)
+			{
+				// do nothing
+				enc_var.one_count++;
+
+			}
+			else
+			{
+				enc_var.nrzi_bit = enc_var.nrzi_bit ^ 1; // switch tone
+				enc_var.one_count = 0;
+			}
+
+			// prepare for next bit
+			enc_var.byte = (enc_var.byte >> 1);
+			enc_var.bit_index++;
+
+			if (enc_var.bit_index >= 8)
+			{
+				enc_var.bit_index = 0;
+				enc_var.index++;
+				if (enc_var.index >= enc_var.frame_len)
+				{
+					enc_var.state = TAIL;
+					enc_var.bit_index = 0;
+				}
+			}
+			return enc_var.nrzi_bit;
+			break;
+		}
+		case TAIL: {
+			// reset when index runs down
+			if (enc_var.bit_index == 0)
+			{
+				enc_var.byte = 0x7E;
+			}
+
+			enc_var.cur_bit = enc_var.byte & 0x01;
+
+			// NRZ-I encode
+			if (enc_var.cur_bit)
+			{
+				// do nothing
+				enc_var.one_count++;
+
+			}
+			else
+			{
+				enc_var.nrzi_bit = enc_var.nrzi_bit ^ 1; // switch tone
+				enc_var.one_count = 0;
+			}
+
+			// prepare for next bit
+			enc_var.byte = (enc_var.byte >> 1);
+			enc_var.bit_index++;
+
+			if (enc_var.bit_index >= 8)
+			{
+				enc_var.bit_index = 0;
+				enc_var.flag_count++;
+
+				// exit to frame when flags have been sent for tx_tail
+				if (enc_var.flag_count >= enc_param.tx_tail)
+				{
+					enc_var.state = DONE;
+					enc_var.bit_index = 0;
+					enc_var.index = 0;
+					enc_var.status = STOP;
+				}
+			}
+			return enc_var.nrzi_bit;
+			break;
+		}
+		case DONE: {
+			break;
+		}
+		default: {
+			ESP_LOGE(ENC_TAG, "undefined state");
+			enc_var.status = ERROR;
+			// TODO: Assert
+			break;
+		}
+	}
+	return 0; 			// for DONE and DEFAULT states
+}

+ 3 - 10
components/aprs/include/afsk_demodulator.h

@@ -11,15 +11,8 @@
 #define WINDOW_SIZE 11
 #define SAMPLEFREQUENCY 13200
 
-void window_init(void);
-void window_add(int8_t sample);
-int8_t* window_get(void);
-unsigned int window_get_size(void);
-float goertzel_filter(int8_t samples[], float freq, unsigned int N);
-void goertzel_init(float freq0, float freq1, float *coeff0, float *coeff1);
-float goertzelFilter(int samples[], float freq, int N);
-
-
-
+/* Public Functions */
+void afsk_demod_init(uint32_t sample_rate, uint32_t symbol0_freq, uint32_t symbol1_freq);
+uint8_t afsk_demod_add_sample(int8_t sample);
 
 #endif /* MAIN_AFSK_DECODER_H_ */

+ 17 - 0
components/aprs/include/afsk_modulator.h

@@ -0,0 +1,17 @@
+/*
+ * afsk_modulator.h
+ *
+ *  Created on: Oct 13, 2019
+ *      Author: curiousmuch
+ */
+
+#ifndef AFSK_MODULATOR_H_
+#define AFSK_MODULATOR_H_
+
+#include <stdint.h>
+
+/* Public Functions */
+void afsk_mod_init(uint32_t sample_rate, uint32_t freq0, uint32_t freq1);
+int8_t afsk_get_amplitude(uint8_t tone);
+
+#endif /* COMPONENTS_APRS_INCLUDE_AFSK_MODULATOR_H_ */

+ 14 - 0
components/aprs/include/aprs.h

@@ -0,0 +1,14 @@
+/*
+ * aprs.h
+ *
+ *  Created on: Oct 10, 2019
+ *      Author: curiousmuch
+ */
+
+#ifndef APRS_H_
+#define APRS_H_
+
+
+
+
+#endif /* COMPONENTS_APRS_INCLUDE_APRS_H_ */

+ 10 - 3
components/aprs/include/aprs_decoder.h

@@ -9,11 +9,16 @@
 #define APRS_DECODER_H_
 
 #include <stdio.h>
-#include "freertos/FreeRTOS.h"
+#include <stdint.h>
 
 //#define uint8_t unsigned int
 //#define uint32_t unsigned int
 
+/* Constants and Defines */
+#define APRS_MAX_FRAME 256
+
+/* Data Structures */
+
 typedef enum {
 	NORMAL,
 	FRAME_DECODED,
@@ -55,10 +60,12 @@ typedef struct {
 	uint8_t 		packet_rx;
 } decoder_varibles_t;
 
-
+/* Public Functions */
 uint8_t get_rx_status(void);
 void frame_buffer_init(uint8_t *buf, uint32_t len);
 void aprs_decoder_init(void);
-decoder_output_t aprs_decoder_feed_bit(uint8_t nrzi_bit);
+
+void ax25_decoder_init(uint8_t *frame_buffer, uint32_t frame_len)
+decoder_output_t ax25_decoder_feed_bit(uint8_t nrzi_bit);
 
 #endif /* APRS_DECODER_H_ */

+ 55 - 0
components/aprs/include/aprs_encoder.h

@@ -0,0 +1,55 @@
+/*
+ * aprs_encoder.h
+ *
+ *  Created on: Oct 22, 2019
+ *      Author: curiousmuch
+ */
+
+#ifndef APRS_ENCODER_H_
+#define APRS_ENCODER_H_
+
+#include <stdint.h>
+
+/* Data Structures */
+typedef struct {
+	uint8_t *frame;				// frame buffer ptr
+	uint32_t frame_len;			// frame buffer len
+	uint32_t index;				// current buffer index
+	uint8_t bit_index;			// current bit index
+	uint8_t one_count;			// stores the number of "1s" for NRZI
+	uint8_t cur_bit;			// current raw bit being processed
+	uint8_t prev_bit;			// previous raw bit
+	uint8_t nrzi_bit;			// nrzi-bit to be sent
+	uint32_t byte;				// current raw byte being processed
+	uint8_t flag_count;			// number of flags "0x7E" sent
+	ax25_enc_status_t status;	// status of the encoding process
+	ax25_enc_state_t state;		// state of the encoding state machine
+} ax25_enc_var_t;
+
+typedef struct {
+	uint8_t tx_delay;
+	uint8_t tx_tail;
+} ax25_enc_param_t;
+
+typedef enum {
+	NOCONFIG = 0,
+	STOP,
+	READY,
+	ERROR,
+} ax25_enc_status_t;
+
+typedef enum {
+	PREAMBLE = 0,
+	FRAME,
+	TAIL,
+	DONE
+} ax25_enc_state_t;
+
+/* Public Functions*/
+void ax25_encoder_init(uint8_t tx_delay , uint8_t tx_delay);
+ax25_enc_status_t ax25_encoder_encode(uint8_t *frame, int32_t frame_len);
+uint8_t ax25_encoder_get_bit(void);
+ax25_enc_state_t ax25_encoder_get_status(void);
+
+
+#endif /* COMPONENTS_APRS_INCLUDE_APRS_ENCODER_H_ */

+ 77 - 396
components/radio/cc1200.c

@@ -18,16 +18,18 @@
 #include "esp_task_wdt.h"
 #include "freertos/ringbuf.h"
 #include "esp_log.h"
-
 #include "driver/timer.h"
 
-#define CC_TAG "CC1200_Driver"
 
+/* Debugging Tag for ESP_LOG */
+#define CC_TAG "CC1200 Driver"
+
+/* SPI Constants */
 #define CC1200_WRITE_BIT 	0
 #define CC1200_READ_BIT 	BIT(1)
 #define CC1200_BURST_BIT 	BIT(0)
 
-// Public Configurations for CC1200 SPI Driver
+/* CC1200 SPI Driver Configuration */
 spi_bus_config_t bus_config =
 {
 	.miso_io_num = CC1200_MISO,
@@ -56,8 +58,8 @@ spi_device_interface_config_t interface_config =
 
 spi_device_handle_t spi;
 
-// Private CC1200 Driver Functions
-void cc1200_gpio_init(void)
+/* Private Functions */
+static void cc1200_gpio_init(void)
 {
 	gpio_config_t reset_pin_config =
 	{
@@ -84,7 +86,7 @@ void cc1200_gpio_init(void)
 
 }
 
-void cc1200_spi_init(void)
+static void cc1200_spi_init(void)
 {
 	esp_err_t ret;
 	ret = spi_bus_initialize(VSPI_HOST, &bus_config, 0);	// this uses DMA channel 1
@@ -93,7 +95,7 @@ void cc1200_spi_init(void)
 	ESP_ERROR_CHECK(ret);
 }
 
-void IRAM_ATTR cc1200_spi_write_byte(uint16_t addr, uint8_t data)
+static void IRAM_ATTR cc1200_spi_write_byte(uint16_t addr, uint8_t data)
 {
 	esp_err_t ret;
 	spi_transaction_t tx_trans =
@@ -125,7 +127,7 @@ void IRAM_ATTR cc1200_spi_write_byte(uint16_t addr, uint8_t data)
 	ESP_ERROR_CHECK(ret);
 }
 
-void IRAM_ATTR cc1200_spi_write_bytes(uint16_t addr, uint8_t* data, uint8_t len)
+static void IRAM_ATTR cc1200_spi_write_bytes(uint16_t addr, uint8_t* data, uint8_t len)
 {
 	esp_err_t ret;
 	spi_transaction_t tx_trans =
@@ -153,7 +155,7 @@ void IRAM_ATTR cc1200_spi_write_bytes(uint16_t addr, uint8_t* data, uint8_t len)
 	ESP_ERROR_CHECK(ret);
 }
 
-void IRAM_ATTR cc1200_spi_read_byte(uint16_t addr, uint8_t* data)
+static void IRAM_ATTR cc1200_spi_read_byte(uint16_t addr, uint8_t* data)
 {
 	esp_err_t ret;
 	spi_transaction_t rx_trans =
@@ -182,21 +184,7 @@ void IRAM_ATTR cc1200_spi_read_byte(uint16_t addr, uint8_t* data)
 	ESP_ERROR_CHECK(ret);
 }
 
-uint8_t IRAM_ATTR cc1200_radio_read_RSSI(void)
-{
-	uint8_t data = 0;
-	cc1200_spi_read_byte(CC120X_RSSI1, &data);
-	return data;
-}
-
-uint8_t IRAM_ATTR cc1200_radio_read_CFM(void)
-{
-	uint8_t data = 0;
-	cc1200_spi_read_byte(CC120X_CFM_RX_DATA_OUT, &data);
-	return data;
-}
-
-void cc1200_spi_read_bytes(uint16_t addr, uint8_t* data, uint8_t len)
+static void cc1200_spi_read_bytes(uint16_t addr, uint8_t* data, uint8_t len)
 {
 	esp_err_t ret;
 	spi_transaction_t rx_trans =
@@ -248,422 +236,112 @@ rf_status_t IRAM_ATTR cc1200_spi_strobe(uint8_t cmd)
 	return (temp & 0xF0);
 }
 
-// Public CC1200 Driver Functions
-// These function should have there own error codes as they're dependent upon the radio and
-// not the ESP32 :)
+// writes array or register value pairs from smart RF studio to CC1200
+// w/o reseting
+void cc1200_radio_config(const cc1200_reg_settings_t* rf_settings, uint8_t len)
+{
+	uint8_t i;
+	for (i=0;i<len;i++)
+	{
+		cc1200_spi_write_byte(rf_settings[i].addr, rf_settings[i].data);
+	}
+}
+
+/* CC1200 Driver Public Functions */
+
+uint8_t IRAM_ATTR cc1200_radio_read_RSSI(void)
+{
+	uint8_t data = 0;
+	cc1200_spi_read_byte(CC120X_RSSI1, &data);
+	return data;
+}
+
+uint8_t IRAM_ATTR cc1200_radio_read_CFM(void)
+{
+	uint8_t data = 0;
+	cc1200_spi_read_byte(CC120X_CFM_RX_DATA_OUT, &data);
+	return data;
+}
+
+void IRAM_ATTR cc1200_radio_write_CFM(uint8_t data)
+{
+	cc1200_spi_write_byte(CC120X_CFM_TX_DATA_IN, data);
+}
 
 rf_status_t cc1200_radio_reset(void)
 {
 	rf_status_t status;
 	uint8_t retry_count = 0;
-	cc1200_spi_strobe(CC120X_SRES);
-	status = cc1200_spi_strobe(CC120X_SNOP);
+
+	cc1200_spi_strobe(CC120X_SRES);					// soft reset the chip
+	status = cc1200_spi_strobe(CC120X_SNOP);		// get chip status
 
 	vTaskDelay(20 / portTICK_PERIOD_MS);
 
-	while((CC120X_RDYn_BIT & (status & 0x80)))
+	while((CC120X_RDYn_BIT & (status & 0x80)))		// if chip isn't ready, wait 10ms
 	{
 		vTaskDelay(10 / portTICK_PERIOD_MS);
 		if (retry_count > 3)
 		{
-			// place error CC1200 timeout
-			printf("CC1200 Reset Failure\n");
+			ESP_LOGE(CC_TAG, "Reset Failure");
+			// TODO: Reset ESP32
 			break;
 		}
 		status = cc1200_spi_strobe(CC120X_SNOP);
 		retry_count++;
 	}
-	printf("%x\n", retry_count);
+
 	return status;
 }
 
-// f_RF = f_VCO / LO Divider
 #define CC1200_LO_DIVIDER	24 			// 136.7 - 160 MHz Band
 #define CC1200_XOSC 		40000000	// 40MHz
-// f_VCO = FREQ / 2^16 * f_XOSX + FREQOFF / 2^18 * F_XOSC
 
-esp_err_t cc1200_radio_frequency(uint32_t freq)
+void cc1200_radio_frequency(uint32_t freq)
 {
+	// f_RF = f_VCO / LO Divider
+	// f_VCO = FREQ / 2^16 * f_XOSX + FREQOFF / 2^18 * F_XOSC
+
+	double temp_freq;
+
 	// calculate FREQ0, FREQ, FREQ2 registers
-	volatile double temp_freq;
 	temp_freq = ((double) freq * 65536 * CC1200_LO_DIVIDER) / CC1200_XOSC;
 	freq = (uint32_t)temp_freq;
+
 	cc1200_spi_write_byte(CC120X_FREQ0, ((uint8_t *)&freq)[0]);
 	cc1200_spi_write_byte(CC120X_FREQ1, ((uint8_t *)&freq)[1]);
 	cc1200_spi_write_byte(CC120X_FREQ2, ((uint8_t *)&freq)[2]);
-	return ESP_OK;
+	return ;
 }
 
-esp_err_t cc1200_radio_sleep(void)
+void cc1200_radio_sleep(void)
 {
-	return ESP_OK;
+	// TODO: Write CC1200 sleep function
+	return;
 }
 
-esp_err_t cc1200_radio_power(uint8_t txPower)
+void cc1200_radio_power(uint8_t txPower)
 {
-	return ESP_OK;
+	// TODO: Write function to set CC1200 power
+	return;
 }
 
-void cc1200_radio_write(const cc1200_reg_settings_t* rf_settings, uint8_t len)
+void cc1200_radio_idle(void)
 {
-	uint8_t i;
-	for (i=0;i<len;i++)
-	{
-		cc1200_spi_write_byte(rf_settings[i].addr, rf_settings[i].data);
-	}
+	// TODO: Create exception for failure condition
+	while (cc1200_spi_strobe(CC120X_SIDLE) != CC120X_STATE_IDLE);
 }
 
-#define HDLC_FLAG 0x7E
-#define HDLC_FLAG_LEN 10
-
-uint8_t packet_len = 0;
-uint8_t test_vector[] = {0x71, 0x01, 023, 0xAE, 0x75};
-volatile uint8_t sample_count = 0;
-uint8_t toggle;
-uint8_t toggle2;
-uint8_t prev_sample_count = 0;
-uint32_t tx_symbol = 0;
-uint8_t prev_tx_symbol = 0;
-
-
-
-#define SAMPLE_FREQUENCY 13200
-#define DAC_MAX 64
-#define LUT_SIZE 128
-
-DRAM_ATTR int8_t LUT[LUT_SIZE];
-
-int32_t phase_i = 0;
-volatile uint8_t new_sample = 0;
-
-float phase = 0.0f;
-float delta_phi = 0.0f;
-float const delta_phi_1 = (float) 1200 / SAMPLE_FREQUENCY * LUT_SIZE;
-float const delta_phi_2 = (float) 2200 / SAMPLE_FREQUENCY * LUT_SIZE;
-uint8_t data;
-
-
-// The output needs to be continous phase.
-
-typedef struct {
-	uint8_t one_count;
-	uint32_t sample_count;
-	uint32_t byte;
-	uint32_t packet_len;
-	uint8_t prev_bit;
-	uint8_t cur_bit;
-	uint8_t tone;
-} aprs_flags_t;
-
-aprs_flags_t DRAM_ATTR aprs_flags = {
-		.one_count = 0,
-		.sample_count = 0,
-		.byte = 0,
-//		.packet_len = sizeof(APRS_TEST_PACKET)/sizeof(uint8_t),
-		.prev_bit = 0,
-		.cur_bit = 0,
-		.tone = 0
-};
-
-static void IRAM_ATTR LUT_lookup(void)
+void cc1200_radio_tx(void)
 {
-	if (aprs_flags.tone)
-		delta_phi = delta_phi_1;
-	else
-		delta_phi = delta_phi_2;
-
-    phase_i = (int32_t)phase;        // get integer part of our phase
-
-    phase += delta_phi;              // increment phase
-
-    if (phase >= (float)LUT_SIZE)    // handle wraparound
-        phase -= (float)LUT_SIZE;
+	// TODO: Create exception for failure condition
+	while (cc1200_spi_strobe(CC120X_STX) != CC120X_STATE_TX);
 }
 
-void IRAM_ATTR cc1200_aprs_tx_isr(void* para)
+void cc1200_radio_rx(void)
 {
-    GPIO.out_w1ts = (1 << DEBUG_0);
-
-	int timer_idx = (int) para;
-
-    /* Clear the interrupt
-         and update the alarm time for the timer with without reload */
-    TIMERG0.int_clr_timers.t1 = 1;
-
-    // after the alarm has been triggered
-    //  we need enable it again, so it is triggered the next time
-    TIMERG0.hw_timer[1].config.alarm_en = TIMER_ALARM_EN;
-
-    cc1200_spi_write_byte(CC120X_CFM_TX_DATA_IN, LUT[phase_i]);
-
-    sample_count++;
-    new_sample = 1;
-
-	toggle = toggle ^ 1;
-
-	GPIO.out_w1tc = (1 << DEBUG_0);
-
-}
-
-void cc1200_lut_init(void)
-{
-	int16_t i=0;
-	for (i=0; i<LUT_SIZE; ++i)
-	{
-		LUT[i] = (int8_t)roundf(DAC_MAX * sinf(2.0f * M_PI * (float)i / LUT_SIZE));
-		//printf("%d,\n", LUT[i]);
-	}
-}
-
-#define PREAMBLE_LENGTH 20
-#define SUFFIX_LENGTH 1
-
-void IRAM_ATTR cc1200_radio_APRSTXPacket(uint8_t  *f, uint16_t f_len, uint8_t tx_delay, uint8_t tx_tail)
-{
-	// acquire SPI bus for fastest possible SPI transactions
-//	spi_device_acquire_bus(spi, portMAX_DELAY);
-
-	vTaskSuspendAll();
-
-	// setup data rate for CFM TX
-//	cc1200_radio_write(APRS_RX2_SETTINGS, sizeof(APRS_RX2_SETTINGS)/sizeof(cc1200_reg_settings_t));
-//	cc1200_radio_frequency(144390000-6000);
-
-
-	// start CW transmission
-//	cc1200_spi_write_byte(CC120X_FIFO, 0x12);
-	uint8_t state = 0x00;
-
-	//while(cc1200_spi_strobe(CC120X_STX) != CC120X_STATE_TX);
-	while(state != CC120X_STATE_TX)
-	{
-		state = cc1200_spi_strobe(CC120X_STX);
-	}
-
-	// enable interrupt pin for CC1200 for timing packets
-//	gpio_install_isr_service(ESP_INTR_FLAG_IRAM);
-//	gpio_isr_handler_add(CC1200_GPIO3, cc1200_aprs_tx_isr, NULL);
-//	gpio_set_intr_type(CC1200_GPIO3, GPIO_INTR_POSEDGE);
-//	gpio_intr_enable(CC1200_GPIO3);
-
-    timer_enable_intr(TIMER_GROUP_0, TIMER_1);
-    timer_set_counter_value(TIMER_GROUP_0, TIMER_1, 0x00000000ULL);
-    timer_start(TIMER_GROUP_0, TIMER_1);
-
-	int16_t i,j;
-	uint16_t p_len = tx_delay * 12;
-	uint16_t t_len = tx_tail * 12 + 1;
-
-////    // Start CW transmission
-//	cc1200_spi_write_byte(CC120X_FIFO, 0x12);
-//	cc1200_spi_strobe(CC120X_STX);
-
-	sample_count = 0;
-	new_sample = 0;
-
-	// Send HDLC Flag for TX Delay Time
-	for (i = 0; i<p_len; i++)
-	{
-		esp_task_wdt_reset();
-		aprs_flags.byte = 0x7E;
-		for(j=0; j<8; j++)
-		{
-			aprs_flags.cur_bit = aprs_flags.byte & 0x01;
-
-			// NRZ-I Encoding
-			if (aprs_flags.cur_bit)
-			{
-				// do nothing
-				aprs_flags.one_count++;
-
-			}
-			else
-			{
-				aprs_flags.tone = aprs_flags.tone ^ 1; // switch tone
-				aprs_flags.one_count = 0;
-			}
-
-			aprs_flags.byte = (aprs_flags.byte >> 1);
-
-			while(sample_count < 11)	// wait for symbol to be sent
-			{
-				if ( new_sample )
-				{
-					LUT_lookup();
-					new_sample = 0;
-				}
-			}
-			sample_count = 0;
-			//printf("Symbol: %x\n", aprs_flags.cur_bit);
-
-		}
-	}
-	aprs_flags.one_count = 0;
-
-	// Send Packet / Frame
-	//for (i=0;i<aprs_flags.packet_len;i++)
-	for (i=0;i<f_len;i++)
-	{
-		esp_task_wdt_reset();
-		aprs_flags.byte = f[i];
-		for(j=0; j<8; j++)
-		{
-			aprs_flags.cur_bit = aprs_flags.byte & 0x01;	// bool of first bit
-
-			// Zero Stuffing
-			if (aprs_flags.one_count == 5)
-			{
-				aprs_flags.tone = aprs_flags.tone ^ 1;
-				aprs_flags.one_count = 0;
-
-				// wait for symbol to be sent
-				while(sample_count < 11)
-				{
-					if ( new_sample )
-					{
-						LUT_lookup();
-						new_sample = 0;
-					}
-				}
-				toggle2 = toggle2 ^ 1;
-				//gpio_set_level(DEBUG_0, toggle2);
-				sample_count = 0;
-			}
-
-			// NRZ-I Encoding
-			if (aprs_flags.cur_bit)
-			{
-				// do nothing
-				aprs_flags.one_count++;
-
-			}
-			else
-			{
-				aprs_flags.tone = aprs_flags.tone ^ 1; // switch tone
-				aprs_flags.one_count = 0;
-			}
-
-			aprs_flags.byte = (aprs_flags.byte >> 1);
-
-			while(sample_count < 11)	// wait for symbol to be sent
-			{
-				if ( new_sample )
-				{
-					LUT_lookup();
-					new_sample = 0;
-				}
-			}
-			toggle2 = toggle2 ^ 1;
-			//gpio_set_level(DEBUG_0, toggle2);
-			sample_count = 0;
-			//printf("Symbol: %x\n", aprs_flags.cur_bit);
-		}
-	}
-	aprs_flags.one_count = 0;
-
-	// Send HDLC Flag for TX Tail
-	for (i = 0; i<t_len; i++)
-	{
-		esp_task_wdt_reset();
-		aprs_flags.byte = 0x7E;
-		for(j=0; j<8;j++)
-		{
-			aprs_flags.cur_bit = aprs_flags.byte & 0x01;
-
-			// NRZ-I Encoding
-			if (aprs_flags.cur_bit)
-			{
-				// do nothing
-				aprs_flags.one_count++;
-
-			}
-			else
-			{
-				aprs_flags.tone = aprs_flags.tone ^ 1; // switch tone
-				aprs_flags.one_count = 0;
-			}
-
-			aprs_flags.byte = (aprs_flags.byte >> 1);
-
-			while(sample_count < 11)	// wait for symbol to be sent
-			{
-				if ( new_sample )
-				{
-					LUT_lookup();
-					new_sample = 0;
-				}
-			}
-			sample_count = 0;
-
-		}
-	}
-
-//	gpio_intr_disable(CC1200_GPIO3);
-//	gpio_set_intr_type(CC1200_GPIO3, GPIO_INTR_DISABLE);
-    timer_disable_intr(TIMER_GROUP_0, TIMER_1);
-	timer_pause(TIMER_GROUP_0, TIMER_1);
-
-	while(cc1200_spi_strobe(CC120X_SIDLE)!= CC120X_STATE_IDLE);
-	xTaskResumeAll();
-//	spi_device_release_bus(spi);
-//	gpio_uninstall_isr_service();
-}
-
-extern SemaphoreHandle_t xRadioRXISRSemaphore;
-extern TaskHandle_t xRadioRXTaskHandle;
-int8_t EXTERNAL_DATA;
-
-static void IRAM_ATTR cc1200_aprs_rx_isr(void* arg)
-{
-	//uint8_t data = 0;
-    //cc1200_spi_read_byte(CC120X_CFM_RX_DATA_OUT, &data);
-
-    //GPIO.out_w1ts = (1 << DEBUG_0);
-
-	static BaseType_t xHigherPriorityTaskWoken = pdFALSE;
-
-    //vTaskNotifyGiveFromISR( xRadioRXTaskHandle, &xHigherPriorityTaskWoken );
-
-    xSemaphoreGiveFromISR(xRadioRXISRSemaphore, &xHigherPriorityTaskWoken);
-	if (xHigherPriorityTaskWoken == pdTRUE)
-	{
-		portYIELD_FROM_ISR( );
-	}
-
-	//GPIO.out_w1tc = (1 << DEBUG_0);
-}
-
-void IRAM_ATTR cc1200_radio_start_APRSRX(void)
-{
-	// acquire SPI bus for fastest possible SPI transactions
-	//spi_device_acquire_bus(spi, portMAX_DELAY);
-
-
-	// start RX transmission
-//	cc1200_radio_write(APRS_RX2_SETTINGS, sizeof(APRS_RX2_SETTINGS)/sizeof(cc1200_reg_settings_t));
-//	cc1200_radio_frequency(144390000-6000);
-
-	// enable ISR for CC1200 for timing packets
-//	gpio_install_isr_service(ESP_INTR_FLAG_IRAM);
-//	gpio_isr_handler_add(CC1200_GPIO2, cc1200_aprs_rx_isr, NULL);
-//	gpio_set_intr_type(CC1200_GPIO2, GPIO_INTR_POSEDGE);
-//	gpio_intr_enable(CC1200_GPIO2);
-
-	while(cc1200_spi_strobe(CC120X_SRX) != CC120X_STATE_RX)
-		vTaskDelay(2/portTICK_PERIOD_MS);
-}
-
-void cc1200_radio_stop_APRSRX(void)
-{
-	// disable interrupt
-//	gpio_intr_disable(CC1200_GPIO2);
-//	gpio_set_intr_type(CC1200_GPIO2, GPIO_INTR_DISABLE);
-//	gpio_uninstall_isr_service();
-
-	//spi_device_release_bus(spi);
-	vTaskDelay(2/portTICK_PERIOD_MS);
-	while(cc1200_spi_strobe(CC120X_SIDLE) != CC120X_STATE_IDLE)
-		vTaskDelay(2/portTICK_PERIOD_MS);
+	// TODO: Create exception for failure condition
+	while (cc1200_spi_strobe(CC120X_SRX) != CC120X_STATE_RX);
 }
 
 void cc1200_radio_init(const cc1200_reg_settings_t* rf_settings, uint8_t len)
@@ -671,7 +349,6 @@ void cc1200_radio_init(const cc1200_reg_settings_t* rf_settings, uint8_t len)
 
 	cc1200_gpio_init();
 	cc1200_spi_init();
-	cc1200_lut_init();
 
 	spi_device_acquire_bus(spi, portMAX_DELAY);
 
@@ -694,3 +371,7 @@ void cc1200_radio_init(const cc1200_reg_settings_t* rf_settings, uint8_t len)
 
 
 
+
+
+
+

+ 14 - 7
components/radio/include/cc1200.h

@@ -284,17 +284,24 @@ typedef struct {
 } cc1200_reg_settings_t;
 
 /* Public Functions */
+
+// Configuration
 void cc1200_radio_init(const cc1200_reg_settings_t*, uint8_t);
-esp_err_t cc1200_radio_frequency(uint32_t);
+void cc1200_radio_frequency(uint32_t);
+void cc1200_radio_config(const cc1200_reg_settings_t* , uint8_t );
 rf_status_t cc1200_radio_reset(void);
-esp_err_t cc1200_radio_sleep(void);
-void cc1200_radio_APRSTXPacket(uint8_t  *f, uint16_t f_len, uint8_t tx_delay, uint8_t tx_tail);
-void cc1200_radio_start_APRSRX(void);
-void cc1200_radio_stop_APRSRX(void);
+
+// Mode
+void cc1200_radio_tx(void);
+void cc1200_radio_rx(void);
+void cc1200_radio_idle(void);
+void cc1200_radio_sleep(void);
+
+
+// Data
 uint8_t cc1200_radio_read_RSSI(void);
 uint8_t cc1200_radio_read_CFM(void);
-void IRAM_ATTR cc1200_aprs_tx_isr(void* para);
-
+void cc1200_radio_write_CFM(int8_t);
 
 #endif// CC120X_SPI_H
 

+ 5 - 211
components/radio/include/cc1200_protocol.h

@@ -5,6 +5,10 @@
  *      Author: curiousmuch
  */
 
+#include <stdio.h>
+#include <stdint.h>
+#include "cc1200.h"
+
 //*********************************//
 // IMPORTANT GPIO SIGNALS
 // REG		DESCRIPTION
@@ -14,149 +18,6 @@
 // 0x11		Carrier Sense
 //********************************//
 
-// Address Config = No address check
-// Bit Rate = 0.825
-// Carrier Frequency = 144.174988
-// Deviation = 2.994537
-// Device Address = 0
-// Manchester Enable = false
-// Modulation Format = 2-FSK
-// Packet Bit Length = 0
-// Packet Length = 63
-// Packet Length Mode = Not supported
-// RX Filter BW = 14.880952
-// Symbol rate = 0.825
-// Whitening = false
-
-#include <stdio.h>
-#include <stdint.h>
-#include "cc1200.h"
-
-// Bit Rate = 0.825kHz
-static const cc1200_reg_settings_t APRS_TX_RATE[]=
-{
-		{CC120X_SYMBOL_RATE2, 0x35},
-		{CC120X_SYMBOL_RATE1, 0xA0},
-		{CC120X_SYMBOL_RATE0, 0x7B}
-};
-
-// Bit Rate = 13.2kHz
-static const cc1200_reg_settings_t APRS_RX_RATE[]=
-{
-		{CC120X_SYMBOL_RATE2, 0x75},
-		{CC120X_SYMBOL_RATE1, 0xA0},
-		{CC120X_SYMBOL_RATE0, 0x7B}
-};
-
-static const cc1200_reg_settings_t APRS_RX_SETTINGS[]=
-{
-  {CC120X_IOCFG3,            0x1e},	// TX Clock
-  {CC120X_IOCFG2,			 0x1d},	// RX Clock
-  {CC120X_IOCFG0,            0x09},
-  {CC120X_SYNC_CFG1,         0x00},	// Disable Sync Word [0x00]
-  {CC120X_SYNC_CFG0,		 0x13}, // Disable RX_CONFIG_LIMITATION 0x13
-  {CC120X_DEVIATION_M,       0x9D},
-  {CC120X_MODCFG_DEV_E,      0x00},
-  {CC120X_DCFILT_CFG,        0x5D},
-  {CC120X_PREAMBLE_CFG1,     0x00},
-  {CC120X_PREAMBLE_CFG0,     0x00},	// Disable Preamble [0x00]
-  {CC120X_IQIC,              0xCB},
-  {CC120X_CHAN_BW,           0x9C},
-  {CC120X_MDMCFG1, 			 0x00},	// Random guess
-  {CC120X_MDMCFG0,           0x45},
-  //{CC120X_MDMCFG0,           0x05},
-  // 6 kHz
-  {CC120X_SYMBOL_RATE2,      0x63},
-  {CC120X_SYMBOL_RATE1,      0xA9},
-  {CC120X_SYMBOL_RATE0,      0x2A},
-  {CC120X_AGC_REF,           0x30},
-  {CC120X_AGC_CS_THR,        0xEC},
-  {CC120X_AGC_CFG3, 		 0x11}, // new
-  {CC120X_AGC_CFG1,          0x51},
-  {CC120X_AGC_CFG0,          0x87},
-  {CC120X_FIFO_CFG,          0x00},
-  {CC120X_FS_CFG,            0x1B},
-  {CC120X_PKT_CFG2,          0x03},
-  {CC120X_PKT_CFG1,          0x00},
-  {CC120X_PKT_CFG0,          0x40},	// new
-  {CC120X_RFEND_CFG1,        0x0F},	// new
-  {CC120X_RFEND_CFG0,        0x00},
-  {CC120X_PA_CFG1,           0x3F},
-  {CC120X_PKT_LEN,           0xFF},
-  {CC120X_IF_MIX_CFG,        0x1C},
-  {CC120X_FREQOFF_CFG,       0x22},
-  {CC120X_MDMCFG2,           0x0B},		// need to set CFM_DATA_EN bit for CFM mode and reduce upsampler rate
-  {CC120X_FREQ2,             0x56},
-  {CC120X_FREQ1,             0x81},
-  {CC120X_FREQ0,             0x47},
-  {CC120X_IF_ADC1,           0xEE},
-  {CC120X_IF_ADC0,           0x10},
-  {CC120X_FS_DIG1,           0x07},
-  {CC120X_FS_DIG0,           0xAF},
-  {CC120X_FS_CAL1,           0x40},
-  {CC120X_FS_CAL0,           0x0E},
-  {CC120X_FS_DIVTWO,         0x03},
-  {CC120X_FS_DSM0,           0x33},
-  {CC120X_FS_DVC0,           0x17},
-  {CC120X_FS_PFD,            0x00},
-  {CC120X_FS_PRE,            0x6E},
-  {CC120X_FS_REG_DIV_CML,    0x1C},
-  {CC120X_FS_SPARE,          0xAC},
-  {CC120X_FS_VCO0,           0xB5},
-  {CC120X_XOSC5,             0x0E},
-  {CC120X_XOSC1,             0x03},
-};
-
-static const cc1200_reg_settings_t APRS_TX_SETTINGS[]=
-{
-  {CC120X_IOCFG3,            0x1e},	// 0x1e for TX 0x1D for RX
-  {CC120X_IOCFG0,            0x1d},
-  {CC120X_SYNC_CFG1,         0xAB},
-  {CC120X_DEVIATION_M,       0x9D},
-  {CC120X_MODCFG_DEV_E,      0x00},
-  {CC120X_DCFILT_CFG,        0x5D},
-  {CC120X_PREAMBLE_CFG1,     0x00},
-  {CC120X_PREAMBLE_CFG0,     0x8A},
-  {CC120X_IQIC,              0xCB},
-  {CC120X_CHAN_BW,           0x9C},
-  {CC120X_MDMCFG0,           0x05},
-  {CC120X_SYMBOL_RATE2,      0x35},
-  {CC120X_SYMBOL_RATE1,      0xA0},
-  {CC120X_SYMBOL_RATE0,      0x7B},
-  {CC120X_AGC_REF,           0x30},
-  {CC120X_AGC_CS_THR,        0xEC},
-  {CC120X_AGC_CFG1,          0x51},
-  {CC120X_AGC_CFG0,          0x87},
-  {CC120X_FIFO_CFG,          0x00},
-  {CC120X_FS_CFG,            0x1B},
-  {CC120X_PKT_CFG2,          0x02},
-  {CC120X_PKT_CFG1,          0x00},
-  {CC120X_PKT_CFG0,          0x40},
-  {CC120X_PA_CFG1,           0x3F},
-  {CC120X_PKT_LEN,           0x3F},
-  {CC120X_IF_MIX_CFG,        0x1C},
-  {CC120X_FREQOFF_CFG,       0x22},
-  {CC120X_MDMCFG2,           0x0D},		// need to set CFM_DATA_EN bit for CFM mode
-  {CC120X_FREQ2,             0x56},
-  {CC120X_FREQ1,             0x81},
-  {CC120X_FREQ0,             0x47},
-  {CC120X_IF_ADC1,           0xEE},
-  {CC120X_IF_ADC0,           0x10},
-  {CC120X_FS_DIG1,           0x07},
-  {CC120X_FS_DIG0,           0xAF},
-  {CC120X_FS_CAL1,           0x40},
-  {CC120X_FS_CAL0,           0x0E},
-  {CC120X_FS_DIVTWO,         0x03},
-  {CC120X_FS_DSM0,           0x33},
-  {CC120X_FS_DVC0,           0x17},
-  {CC120X_FS_PFD,            0x00},
-  {CC120X_FS_PRE,            0x6E},
-  {CC120X_FS_REG_DIV_CML,    0x1C},
-  {CC120X_FS_SPARE,          0xAC},
-  {CC120X_FS_VCO0,           0xB5},
-  {CC120X_XOSC5,             0x0E},
-  {CC120X_XOSC1,             0x03},
-};
 
 // Address Config = No address check
 // Bit Rate = 1.2
@@ -171,8 +32,7 @@ static const cc1200_reg_settings_t APRS_TX_SETTINGS[]=
 // RX Filter BW = 14.880952
 // Symbol rate = 1.2
 // Whitening = false
-
-static const cc1200_reg_settings_t APRS_RX2_SETTINGS[]=
+static const cc1200_reg_settings_t AX25_SETTINGS[]=
 {
   {CC120X_IOCFG2,            0x09},		// Serial RX Data
   {CC120X_IOCFG3,			 29}, 		// Serial Clock
@@ -227,70 +87,4 @@ static const cc1200_reg_settings_t APRS_RX2_SETTINGS[]=
   {CC120X_SERIAL_STATUS,     0x08},
 };
 
-// Address Config = No address check
-// Bit Rate = 1.2
-// Carrier Frequency = 144.389954
-// Deviation = 4.997253
-// Device Address = 0
-// Manchester Enable = false
-// Modulation Format = 2-FSK
-// Packet Bit Length = 0
-// Packet Length = 255
-// Packet Length Mode = Variable
-// RX Filter BW = 14.880952
-// Symbol rate = 1.2
-// Whitening = false
-
-static const cc1200_reg_settings_t APRS_TX2_SETTINGS[]=
-{
-  {CC120X_IOCFG2,            0x08},
-  {CC120X_IOCFG0,            0x09},
-  {CC120X_SYNC_CFG1,         0x0B},
-  {CC120X_DEVIATION_M,		 0x06},
-  {CC120X_MODCFG_DEV_E,      0x01},
-  {CC120X_DCFILT_CFG,        0x5D},
-  {CC120X_PREAMBLE_CFG1,     0x00},
-  {CC120X_PREAMBLE_CFG0,     0x8A},
-  {CC120X_IQIC,              0xCB},
-  {CC120X_CHAN_BW,           0x9C},
-  {CC120X_MDMCFG1,           0x00},
-  {CC120X_MDMCFG0,           0x45},
-  {CC120X_SYMBOL_RATE2,      0x3F},
-  {CC120X_SYMBOL_RATE1,      0x75},
-  {CC120X_SYMBOL_RATE0,      0x10},
-  {CC120X_AGC_REF,           0x30},
-  {CC120X_AGC_CS_THR,        0xEC},
-  {CC120X_AGC_CFG1,          0x51},
-  {CC120X_AGC_CFG0,          0x87},
-  {CC120X_FIFO_CFG,          0x00},
-  {CC120X_FS_CFG,            0x1B},
-  {CC120X_PKT_CFG2,          0x03},
-  {CC120X_PKT_CFG1,          0x00},
-  {CC120X_PKT_CFG0,          0x20},
-  {CC120X_PA_CFG1,           0x3F},
-  {CC120X_PKT_LEN,           0xFF},
-  {CC120X_IF_MIX_CFG,        0x1C},
-  {CC120X_FREQOFF_CFG,       0x22},
-  {CC120X_MDMCFG2,           0x0D},
-  {CC120X_FREQ2,             0x56},
-  {CC120X_FREQ1,             0xA2},
-  {CC120X_FREQ0,             0x4C},
-  {CC120X_IF_ADC1,           0xEE},
-  {CC120X_IF_ADC0,           0x10},
-  {CC120X_FS_DIG1,           0x07},
-  {CC120X_FS_DIG0,           0xAF},
-  {CC120X_FS_CAL1,           0x40},
-  {CC120X_FS_CAL0,           0x0E},
-  {CC120X_FS_DIVTWO,         0x03},
-  {CC120X_FS_DSM0,           0x33},
-  {CC120X_FS_DVC0,           0x17},
-  {CC120X_FS_PFD,            0x00},
-  {CC120X_FS_PRE,            0x6E},
-  {CC120X_FS_REG_DIV_CML,    0x1C},
-  {CC120X_FS_SPARE,          0xAC},
-  {CC120X_FS_VCO0,           0xB5},
-  {CC120X_XOSC5,             0x0E},
-  {CC120X_XOSC1,             0x03},
-  {CC120X_SERIAL_STATUS,     0x08},
-};
 

+ 56 - 0
components/radio/include/radio.h

@@ -0,0 +1,56 @@
+/*
+ * radio.h
+ *
+ *  Created on: Oct 11, 2019
+ *      Author: curiousmuch
+ */
+
+#include <stdint.h>
+
+#ifndef RADIO_H_
+#define RADIO_H_
+
+/* Data Structures */
+typedef enum {
+	NOT_CONFIGURED = 0,
+	AX25,
+	ARROW_MESH,
+	ESP_MESH,
+} radio_config_t;
+
+typedef enum {
+	RADIO_IDLE = 0,
+	RADIO_TX,
+	RADIO_RX,
+} radio_status_t;
+
+typedef struct {
+	radio_config_t type;
+	radio_status_t status;
+} radio_param_t;
+
+typedef struct {
+	uint8_t tx_delay;
+	uint8_t tx_tail;
+	uint32_t sample_rate;
+	uint32_t symbol0_freq;
+	uint32_t symbol1_freq;
+	uint8_t *rx_buf;
+	uint32_t rx_buf_len;
+	void *rx_cb;
+	void *tx_cb;
+} ax25_param_t;
+
+/* Public Functions */
+void radio_init(radio_config_t type, void *settings);
+void radio_set_frequency(uint32_t);
+void radio_set_power(int8_t);
+int8_t radio_set_cs(void);
+int8_t radio_get_cs(void);
+int8_t radio_get_rssi(void);
+int8_t radio_get_sample(void);
+
+void radio_packet_rx(void *settings);
+void radio_packet_tx(uint8_t *data, int32_t len, void *settings);
+
+#endif /* COMPONENTS_RADIO_INCLUDE_RADIO_H_ */

+ 257 - 0
components/radio/radio.c

@@ -0,0 +1,257 @@
+/*
+ * radio.c
+ *
+ *  Created on: Oct 11, 2019
+ *      Author: curiousmuch
+ */
+
+#include <stdio.h>
+#include <stdint.h>
+#include <math.h>
+
+#include "freertos/FreeRTOS.h"
+#include "freertos/semphr.h"
+#include "freertos/task.h"
+
+#include "sdkconfig.h"
+#include "esp_log.h"
+
+#include "radio.h"
+#include "cc1200.h"
+#include "afsk_modulator.h"
+#include "afsk_demodulator.h"
+#include "aprs_decoder.h"
+#include "aprs_encoder.h"
+
+/* Debugging Tag */
+#define RADIO_TAG "Radio"
+
+/* Public Variables */
+radio_param_t radio_param;				// radio configuraiton
+SemaphoreHandle_t xRadioSemaphore;		// semphore for sample timing
+
+/* Private Functions */
+void IRAM_ATTR radio_timer_isr(void *param)
+{
+    //GPIO.out_w1ts = (1 << DEBUG_0);
+
+	int timer_idx = (int) param; 	// cast to int for timer index
+	TIMERG0.int_clr_timers.t0 = 1; 	// clear interrupt
+	TIMERG0.hw_timer[0].config.alarm_en = TIMER_ALARM_EN; // re-enable timer alarm
+
+	// provide unblocking semaphore
+	static BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+	xSemaphoreGiveFromISR(xRadioSemaphore, &xHigherPriorityTaskWoken);
+	if (xHigherPriorityTaskWoken == pdTRUE)
+	{
+		portYIELD_FROM_ISR();
+	}
+
+	//GPIO.out_w1tc = (1 << DEBUG_0);
+}
+
+#define RADIO_TIMER_GROUP TIMER_GROUP_0
+#define RADIO_TIMER	TIMER_0
+
+void timer_radio_init(uint32_t sample_rate, void *timer_isr)
+{
+	timer_config_t timer_config;
+
+	timer_config.divider = 2;
+	timer_config.counter_dir = TIMER_COUNT_UP;
+	timer_config.counter_en = TIMER_PAUSE;
+	timer_config.alarm_en = TIMER_ALARM_EN;
+	timer_config.intr_type = TIMER_INTR_LEVEL;
+	timer_config.auto_reload = TIMER_AUTORELOAD_EN;
+
+
+	uint32_t timer_alarm;
+	timer_alarm = (uint32_t)(40000000 / sample_rate);
+
+	// TODO: confirm timer_alarm calculation
+
+    timer_init(RADIO_TIMER_GROUP, RADIO_TIMER, &timer_config);
+    timer_set_counter_value(RADIO_TIMER_GROUP, RADIO_TIMER, 0x00000000ULL);
+    timer_set_alarm_value(RADIO_TIMER_GROUP, RADIO_TIMER, 3030);
+    timer_isr_register(RADIO_TIMER_GROUP, RADIO_TIMER, timer_isr,
+    		(void *) RADIO_TIMER, ESP_INTR_FLAG_IRAM, NULL);
+}
+
+void timer_radio_start(void)
+{
+	timer_enable_intr(RADIO_TIMER_GROUP, RADIO_TIMER);
+    timer_set_counter_value(RADIO_TIMER_GROUP, RADIO_TIMER, 0x00000000ULL);
+    timer_start(RADIO_TIMER_GROUP, RADIO_TIMER);
+}
+
+void timer_radio_stop(void)
+{
+    timer_disable_intr(RADIO_TIMER_GROUP, RADIO_TIMER);
+	timer_pause(RADIO_TIMER_GROUP, RADIO_TIMER);
+}
+
+/* HAL Layer */
+void radio_tx(void)
+{
+	cc1200_radio_tx();
+	radio_param.status = RADIO_TX;
+}
+
+void radio_rx(void)
+{
+	cc1200_radio_rx();
+	radio_param.status = RADIO_RX;
+}
+
+void radio_idle(void)
+{
+	cc1200_radio_idle();
+	radio_param.status = RADIO_IDLE;
+}
+
+void radio_init(radio_config_t type, void *settings)
+{
+	switch(type)
+	{
+		case AX25: {
+			ESP_LOGI("Radio", "APRS Mode");
+			radio_param.type = AX25;
+
+			// cast setting struct
+			ax25_param_t p = (ax25_param_t)settings;
+
+			// setup LUT for AFSK demodulator
+			afsk_mod_init(p->sample_rate, p->symbol0_freq, p->symbol1_freq);
+
+			// setup frequency detectors for AFSK demodulator
+			afsk_demod_init(p->sample_rate, p->symbol0_freq, p->symbol1_freq);
+
+			// setup encoder for ax25
+			ax25_encoder_init(p->tx_delay, p->tx_tail);
+
+			// setup timer for TX / RX
+			timer_radio_init(p->sample_rate, radio_timer_isr);
+
+			// create task for sampling
+			// TODO: Reduce stack requirements?
+			// TODO: Should there be an option on which core the driver pins the task too>
+			xTaskCreatePinnedToCore(radio_rx_task, "AFSK Sample Task", 1024*4, 0, 1, NULL, 1);
+			// xTaskCreatePinnedToCore()
+			vTaskSuspend(radio_rx_task);
+
+			// configure CC1200
+			cc1200_radio_init(AX25_SETTINGS, sizeof(AX25_SETTINGS)/sizeof(cc1200_reg_settings_t));
+
+			// put chip to idle
+			radio_idle();
+
+			break;
+		}
+		default: {
+			ESP_LOGE(RADIO_TAG, "invalid configuration");
+			radio_param.type = NOT_CONFIGURED;
+			//TODO: Add assert to stop functionality
+			break;
+		}
+	}
+}
+
+// this function will block and configure
+// the cc1200 for tx using the protocol setup by "radio_init"
+// the buffer holding the packet isn't copied and therefore must be held until
+// the function returns
+// TODO: Should this be non-blocking and start up a task / wait for an interrupt
+// then fire a callback function?
+void radio_packet_tx(uint8_t *data, int32_t len, void *settings)
+{
+	switch(radio_param.type)
+	{
+		case AX25: {
+			ESP_LOGV(RADIO_TAG, "transmitting AX25 packet");
+
+			// load ax25 encoder state machine
+			ax25_encoder_encode(data, len);
+
+			// variables for symbol timing (11 samples per symbol)
+			uint32_t sample_count = 0; int8_t tone;
+			uint8_t bit = ax25_encoder_get_bit();
+
+			// configure radio to send CW
+			radio_tx();
+
+			// start sampling timer
+			timer_radio_start();
+
+			while(ax25_encoder_get_status == READY)
+			{
+				// TODO: Do we need to feed the WDT here?
+
+				// get amplitude for AFSK
+				tone = afsk_get_amplitude(bit);
+
+				// pause for semphore
+				if (xSemaphoreTake(xRadioSemaphore, portMAX_DELAY) == pdTRUE)
+				{
+					// update carrier for AFSK
+					cc1200_radio_write_CFM(tone);
+
+					// inc symbol count
+					sample_count++;
+					if (sample_count > 11)
+					{
+						bit = ax25_encoder_get_bit();
+						sample_count = 0;
+					}
+				}
+				else
+				{
+					ESP_LOGE(RADIO_TAG, "sample timeout error");
+					break;
+				}
+
+			}
+			radio_idle();
+			ESP_LOGV(RADIO_TAG, "transmit complete");
+			break;
+		}
+		default: {
+			ESP_LOGE(RADIO_TAG, "invalid configuration");
+			break;
+		}
+	}
+}
+
+void radio_rx_task(void *para)
+{
+	// setup
+
+	// task
+	while(1)
+	{
+
+
+	}
+}
+
+// Functionality will depend on protocol
+// AX.25 - Non-Block and will activate callback function
+void radio_packet_rx(void *settings)
+{
+	switch(radio_param.type)
+	{
+		case AX25: {
+			// setup sampling timer
+
+
+			// un-suspend sampling task
+
+			break;
+		}
+		default: {
+			ESP_LOGE(RADIO_TAG, "invalid configuration");
+			break;
+		}
+
+	}
+	cc1200_radio_rx();
+}

+ 0 - 0
a.out → components/timer/component.mk


+ 4 - 3
main/main.c

@@ -67,7 +67,6 @@ void IRAM_ATTR rx_timer_isr(void *para)
 {
 
     //GPIO.out_w1ts = (1 << DEBUG_0);
-
 	int timer_idx = (int) para;
 
     /* Clear the interrupt
@@ -123,7 +122,7 @@ void Radio_Task(void *pvParameters)
     		(void *) TIMER_0, ESP_INTR_FLAG_IRAM, NULL);
 
 	// Initialize Radio
-	cc1200_radio_init(APRS_RX2_SETTINGS, sizeof(APRS_RX2_SETTINGS)/sizeof(cc1200_reg_settings_t));
+	cc1200_radio_init(APRS_SETTINGS, sizeof(APRS_SETTINGS)/sizeof(cc1200_reg_settings_t));
 	cc1200_radio_frequency(144390000);
 
 
@@ -172,6 +171,7 @@ void Radio_Task(void *pvParameters)
 
 uint8_t aprs_buf[256];
 
+
 void dsps_biquad_gen_lpf_f32(float *coeffs, float f, float qFactor)
 {
     if (qFactor <= 0.0001) {
@@ -249,6 +249,7 @@ void RX_DSP_Task(void *pvParameters)
 	volatile int32_t d_pll=0, dpll_error=0, err_div=0, dpll_margin = 1;
 	uint32_t success = 0;
 	float coeff0, coeff1;
+	uint8_t EXTERNAL_DATA= 0;
 
 	volatile uint32_t count_start, count_stop; // needed for debuging
 
@@ -393,7 +394,7 @@ void IRAM_ATTR app_main()
 	// Radio Task Initialize
 	radio_init();
 
-	// AFSK Decoder and Encoder
+	// AFSK Modulator and Demodulator
 
 
 	// Kiss Decoder and Encoder