Changeset - 0e169f68c994
[Not reviewed]
default
0 13 0
ethanzonca@CL-ENS241-08.cedarville.edu - 12 years ago 2013-01-09 22:10:43
ethanzonca@CL-ENS241-08.cedarville.edu
Added support for UART1, added numerous fixes. Introduction of GPS has caused several difficulties. Lowering baud rate to 4800 has made problems worse, probably change back to 115200 baud and disable serial1 interrupts when AFSK transmitting / logging.
13 files changed with 136 insertions and 84 deletions:
0 comments (0 inline, 0 general)
master/master/config.h
Show inline comments
 
@@ -19,24 +19,25 @@
 
 
#define F_CPU 11059200
 
#define MODULE_ID '1'
 
 
 
// --------------------------------------------------------------------------
 
// Error Codes config (led.c, used throughout code)
 
// --------------------------------------------------------------------------
 
 
// SD Card
 
#define ERROR_SD_INIT 2
 
#define ERROR_SD_PARTITION 3
 
#define ERROR_CRAP 6
 
 
// --------------------------------------------------------------------------
 
// Slave Sensors config (slavesensors.c)
 
// --------------------------------------------------------------------------
 
 
// NOT USED. Could integrate into slavesensors.c setup function for configurability eventually.
 
// Currently manual configuration of sensors is done in slavesensors.c
 
#define SLAVE0_SENSORS BOARDTEMP
 
#define SLAVE1_SENSORS BOARDTEMP | HUMIDITY | TEMPERATURE | PRESSURE | AMBIENTLIGHT
 
#define SLAVE2_SENSORS BOARDTEMP | GEIGER
 
#define SLAVE3_SENSORS BOARDTEMP | CAMERA
 
#define SLAVE4_SENSORS NONE
 
@@ -57,25 +58,25 @@
 
 
// Circular serial buffer size. Must be at least MAX_CMD_LEN + 5
 
#define BUFFER_SIZE 32 
 
 
// Public broadcast address
 
#define BROADCAST_ADDR 0 
 
 
// --------------------------------------------------------------------------
 
// USART config (serial.c)
 
// --------------------------------------------------------------------------
 
 
#define USART0_BAUDRATE 115200
 
#define USART1_BAUDRATE 115200
 
#define USART1_BAUDRATE 4800
 
 
 
// --------------------------------------------------------------------------
 
// AX.25 config (ax25.c)
 
// --------------------------------------------------------------------------
 

	
 
// TX delay in milliseconds
 
#define TX_DELAY      300
 

	
 
// Maximum packet delay
 
#define MAX_PACKET_LEN 512  // bytes
 
 
@@ -83,47 +84,50 @@
 
// --------------------------------------------------------------------------
 
// APRS config (aprs.c)
 
// --------------------------------------------------------------------------
 

	
 
// Set your callsign and SSID here. Common values for the SSID are
 
// (from http://zlhams.wikidot.com/aprs-ssidguide):
 
//
 
// - Balloons:  11
 
// - Cars:       9
 
// - Home:       0
 
// - IGate:      5
 
#define S_CALLSIGN      "KD8TDF"
 
#define S_CALLSIGN_ID   11
 
#define S_CALLSIGN_ID   9 // 11
 

	
 
// Destination callsign: APRS (with SSID=0) is usually okay.
 
#define D_CALLSIGN      "APRS"
 
#define D_CALLSIGN_ID   0
 

	
 
// Digipeating paths:
 
// (read more about digipeating paths here: http://wa8lmf.net/DigiPaths/ )
 
// The recommended digi path for a balloon is WIDE2-1 or pathless. The default
 
// is pathless. Uncomment the following two lines for WIDE2-1 path:
 
#define DIGI_PATH1      "WIDE2"
 
#define DIGI_PATH1_TTL  1
 

	
 
// APRS comment: this goes in the comment portion of the APRS message. You
 
// might want to keep this short. The longer the packet, the more vulnerable
 
// it is to noise.
 
#define APRS_COMMENT    "Payload data..."
 
#define APRS_COMMENT    "CedarvilleUniversity HAB"
 
 
// Transmit the APRS sentence every X milliseconds
 
#define APRS_TRANSMIT_PERIOD 5000
 
#define APRS_TRANSMIT_PERIOD 10000
 

	
 

	
 
// --------------------------------------------------------------------------
 
// Logger config (logger.c)
 
// --------------------------------------------------------------------------
 
 
#define LOGGER_ID_EEPROM_ADDR 0x10
 
 
// Written to the beginning of every log file
 
#define LOGGER_HEADERTEXT "HAB Control Master - 1.0\n"
 
 
// Log to SD card every X milliseconds
 
#define LOGGER_RATE 1000 
 
 
// LED cycle indicator speed
 
#define LEDCYCLE_RATE 100 
 
 
#endif /* CONFIG_H_ */
 
\ No newline at end of file
master/master/lib/afsk.c
Show inline comments
 
@@ -62,26 +62,29 @@ extern const uint16_t TABLE_SIZE = sizeo
 
// constants
 
#define MODEM_CLOCK_RATE F_CPU
 
#define PLAYBACK_RATE MODEM_CLOCK_RATE / 256  // Fast PWM
 

	
 
#define BAUD_RATE 1200
 
//#define SAMPLES_PER_BAUD PLAYBACK_RATE / BAUD_RATE // = 36
 
//#define SAMPLES_PER_BAUD 36
 
#define SAMPLES_PER_BAUD 36
 

	
 

	
 
// phase offset of 1800 gives ~1900 Hz
 
// phase offset of 3300 gives ~2200 Hz
 
//#define PHASE_DELTA_1200 1800
 
//#define PHASE_DELTA_2200 2200
 
#define PHASE_DELTA_1200 1800
 
#define PHASE_DELTA_2200 2200
 
#define PHASE_DELTA_2200 3300
 

	
 

	
 
// Module globals
 
volatile unsigned char current_byte;
 
volatile unsigned char current_sample_in_baud;    // 1 bit = SAMPLES_PER_BAUD samples
 
volatile bool go = false;                 
 

	
 
volatile unsigned int packet_pos;                 // Next bit to be sent out
 

	
 
volatile unsigned int afsk_packet_size = 10;
 
volatile const uint8_t *afsk_packet;
 

	
 
void afsk_ptt_off() 
 
@@ -216,16 +219,16 @@ void afsk_setup()
 
	TCCR2B = (TCCR2B & ~(_BV(CS22) | _BV(CS21))) | _BV(CS20);
 
	
 
	// Enable interrupt when TCNT2 reaches TOP (0xFF) (p.151, 163)
 
	//TIMSK2 |= _BV(TOIE2);
 
	TIMSK2 |= 0b00000001;
 
	
 
	// FIXME TODO
 
	DDRD = 0xff;
 
	PORTD = 0xff;
 
	
 
	// todo: init radio, maybe in main
 
	
 
	sei();
 
	</i>
 
	
 
	while(afsk_busy());
 
}
 
\ No newline at end of file
master/master/lib/aprs.c
Show inline comments
 
@@ -6,27 +6,27 @@
 
 * Ethan Zonca
 
 * Matthew Kanning
 
 * Kyle Ripperger
 
 * Matthew Kroening
 
 *
 
 */
 
 
#include "../config.h"
 
#include "aprs.h"
 
#include "ax25.h"
 
#include <stdio.h>
 

	
 
const char *gps_aprs_lat = "latitude";
 
const char *gps_aprs_lon = "longitude";
 
const char *gps_time = "gpstime";
 
const char *gps_aprs_lat = "39.74744N";
 
const char *gps_aprs_lon = "-83.81249W";
 
const char *gps_time = "081533/";
 
float gps_altitude = 123.5;
 
int gps_course = 5;
 
int gps_speed = 13;
 

	
 
float meters_to_feet(float m)
 
{
 
  // 10000 ft = 3048 m
 
  return m / 0.3048;
 
}
 

	
 
void aprs_send()
 
{
master/master/lib/led.c
Show inline comments
 
@@ -24,25 +24,25 @@ void led_setup()
 
	}
 
}
 
 
// Turn the specified LED on
 
void led_on(uint8_t led) 
 
{
 
	*(ledList[led].port) |= (1<<ledList[led].pin);
 
}
 
 
	// Turn the specified LED off
 
void led_off(uint8_t led) 
 
{
 
	*(ledList[led].direction) &= ~(1<<ledList[led].pin);
 
	*(ledList[led].port) &= ~(1<<ledList[led].pin);
 
}
 
 
// Flashes error LED a set amount of times, then leaves it on
 
void led_errorcode(uint8_t code) 
 
{
 
	_delay_ms(400);
 
	for(int i=0; i<code; i++) 
 
	{
 
		led_on(LED_ERROR);
 
		_delay_ms(150);
 
		led_off(LED_ERROR);
 
		_delay_ms(150);
master/master/lib/led.h
Show inline comments
 
@@ -18,47 +18,49 @@
 
 
enum leds {
 
	LED_ACT0 = 0,
 
	LED_ACT1,
 
	LED_ACT2,
 
	LED_ACT3,
 
	
 
	LED_POWER,
 
	LED_STATUS,
 
	LED_ERROR,
 
	LED_SIDEBOARD,
 
	LED_ACTIVITY,
 
	LED_CYCLE
 
	LED_CYCLE,
 
	LED_HEAT
 
};
 
 
typedef struct {uint8_t* direction; uint8_t* port; uint8_t pin;} led_t;
 
 
// Match order of leds enum
 
static led_t ledList[] = {
 
	{&DDRA, &PORTA, PA4}, // ACT0
 
	{&DDRA, &PORTA, PA5}, // ACT1
 
	{&DDRA, &PORTA, PA6}, // ACT2
 
	{&DDRA, &PORTA, PA7}, // ACT3
 
	{&DDRA, &PORTA, PA1}, // ACT0
 
	{&DDRA, &PORTA, PA2}, // ACT1
 
	{&DDRA, &PORTA, PA3}, // ACT2
 
	{&DDRA, &PORTA, PA4}, // ACT3
 
 
//pcb:
 
//	{&DDRB, &PORTB, PB4}, // POWER
 
//	{&DDRB, &PORTB, PB3}, // STATUS
 
//	{&DDRB, &PORTB, PB2}, // ERROR
 
	{&DDRB, &PORTB, PB4}, // POWER
 
	{&DDRB, &PORTB, PB3}, // STATUS
 
	{&DDRB, &PORTB, PB2}, // ERROR
 
 
//breadboard:
 
	{&DDRA, &PORTA, PA2}, // POWER
 
	{&DDRA, &PORTA, PA0}, // STATUS
 
	{&DDRA, &PORTA, PA1}, // ERROR
 
//	{&DDRA, &PORTA, PA2}, // POWER
 
//	{&DDRA, &PORTA, PA0}, // STATUS
 
//	{&DDRA, &PORTA, PA1}, // ERROR
 
 
	{&DDRD, &PORTD, PD6}, // SIDEBOARD
 
	{&DDRD, &PORTD, PD5}, // ACTIVITY
 
	{&DDRD, &PORTD, PD4}, // CYCLE
 
	{&DDRA, &PORTA, PD6}, // HEAT
 
};
 
 
#define NUM_LEDS 10
 
#define NUM_LEDS 11
 
 
void led_setup();
 
void led_on(uint8_t led);
 
void led_off(uint8_t led);
 
void led_errorcode(uint8_t code);
 
 
#endif /* LED_H_ */
master/master/lib/logger.c
Show inline comments
 
@@ -29,38 +29,39 @@
 
struct partition_struct* partition;
 
struct fat_fs_struct* fs;
 
struct fat_dir_entry_struct directory;
 
struct fat_dir_struct* dd;
 
struct fat_file_struct* fd;
 
 
void logger_setup()
 
{
 
 
	if(!sd_raw_init())
 
	{
 
		// Initializing SD card failed!
 
		// Error opening partition. MBR might be screwed up.
 
		serial0_sendString("SD: Error initializing.\r\n");
 
		led_errorcode(ERROR_SD_INIT);
 
		return;
 
	}
 
 
	// TODO: Check SD card switch to see if inserted.
 
	// this was included in the library, but is commented out right now
 
	
 
	// Open first partition
 
	partition = partition_open(sd_raw_read, sd_raw_read_interval, sd_raw_write, sd_raw_write_interval, 0);
 
	
 
	// Check that partition was created correctly
 
	if(!partition)
 
	{
 
		serial0_sendString("SD: Error opening partition.\r\n");
 
		// Error opening partition. MBR might be screwed up.
 
		led_errorcode(ERROR_SD_PARTITION);
 
		return;
 
	}
 
	
 
	
 
	// Open FAT filesystem
 
	fs = fat_open(partition);
 
	if(!fs)
 
	{
 
		// opening filesystem failed
 
		return;
master/master/lib/serial.c
Show inline comments
 
@@ -25,87 +25,76 @@ void serial0_setup() {
 
	/* Enable receiver and transmitter */
 
	UCSR0B |= (1<<RXEN0)|(1<<TXEN0); // Enable rx/tx
 
	/* Set frame format: 8data, 1stop bit */
 
	UCSR0C |= (1 << UCSZ00) | (1 << UCSZ01); // - 1 stop bit
 
	
 
	/* Set baud rate */
 
	UBRR0H = (unsigned char)(USART0_BAUD_PRESCALE>>8);
 
	UBRR0L = (unsigned char)USART0_BAUD_PRESCALE;
 
	
 
	UCSR0B |= (1 << RXCIE0); // Enable interrupt
 
	
 
	//UCSR0A |= (1<<RXC0);
 
}
 
 
volatile uint8_t charTest;
 
 
ISR(USART1_RX_vect)
 
{
 
	serial1_sendChar(UDR1);
 
}
 
 
/*
 
uint8_t test = 0;
 
ISR(USART0__RX_vect)
 
{
 
	led_on(POWER);
 
	test = UDR0;
 
}*/
 
void serial1_setup() {
 
//PROVEN in test project
 
 
void serial1_setup() {
 
	/* Enable receiver and transmitter */
 
	UCSR1B |= (1<<RXEN1)|(1<<TXEN1); // Enable rx/tx
 
	/* Set frame format: 8data, 1stop bit */
 
	UCSR1C |= (1 << UCSZ10) | (1 << UCSZ11); // - 1 stop bit
 
	
 
	/* Set baud rate */
 
	UBRR1H = (unsigned char)(USART1_BAUD_PRESCALE>>8);
 
	UBRR1L = (unsigned char)USART1_BAUD_PRESCALE;
 
	/* Enable receiver and transmitter */
 
	UCSR1B = (1<<RXEN1)|(1<<TXEN1);
 
	/* Set frame format: 8data, 1stop bit */
 
	UCSR1C = (3<<UCSZ10); // - 1 stop bit
 
	
 
	UCSR1B |= (1 << RXCIE1); // Enable interrupt
 
}
 
 
void serial0_sendChar( unsigned char byte )
 
{
 
	while (!(UCSR0A & (1<<UDRE0)));
 
	UDR0 = byte;
 
}
 
 
void serial1_sendChar( unsigned char byte )
 
{
 
	while (!(UCSR1A & (1<<UDRE1)));
 
	UDR1 = byte;
 
}
 
 
unsigned char serial0_readChar()
 
{
 
	while(!(UCSR0A &(1<<RXC0)));
 
	return UDR0;
 
}
 
 
unsigned char serial1_readChar()
 
{
 
	while(!(UCSR1A &(1<<RXC1)));
 
	return UDR1;
 
}
 
 
void serial0_sendString(const char* stringPtr){
 
	while(*stringPtr != 0x00)
 
	{
 
		serial0_sendChar(*stringPtr);
 
		stringPtr++;
 
	}
 
}
 
 
void serial1_sendString(const char* stringPtr){
 
	while(*stringPtr != 0x00)
 
	{
 
		serial1_sendChar(*stringPtr);
 
		stringPtr++;
 
	}
 
}
 
 
 
void serial_sendCommand( char moduleID, char sensorID, char* data )
 
{
 
	char checkSum = 0x00; //initialize checksum
 
	
 
	serial0_sendChar('['); //bracket indicates start of command
 
	serial0_sendChar(moduleID);
 
	checkSum+=moduleID;
 
	
 
	serial0_sendChar(sensorID);
 
	checkSum+=sensorID;
 
	
 
	// send data, null-terminated
master/master/lib/serial.h
Show inline comments
 
@@ -13,26 +13,23 @@
 
 
#ifndef SERIAL_H_
 
#define SERIAL_H_
 
 
#include <inttypes.h>
 
 
#define USART0_BAUD_PRESCALE (((F_CPU / (USART0_BAUDRATE * 16UL))) -1 )
 
#define USART1_BAUD_PRESCALE (((F_CPU / (USART1_BAUDRATE * 16UL))) -1 )
 
 
void serial0_sendChar( unsigned char byte );
 
void serial1_sendChar( unsigned char byte );
 
 
unsigned char serial0_readChar();
 
unsigned char serial1_readChar();
 
 
void serial0_setup();
 
void serial1_setup();
 
 
void serial0_sendString(const char* stringPtr);
 
void serial1_sendString(const char* stringPtr);
 
 
void serial_sendCommand( char moduleID, char sensorID, char* data );
 
void serial_sendResponseData();
 
 
 
#endif /* SERIAL_H_ */
 
\ No newline at end of file
master/master/lib/serparser.c
Show inline comments
 
@@ -69,34 +69,36 @@ static void setParserState(uint8_t state
 
		payloadLength = 0;
 
		checksumCalc = 0;
 
	}
 
	
 
	// Every time we change state, we have parsed a byte
 
	bufferParsePosition = (bufferParsePosition + 1) % BUFFER_SIZE;
 
}
 
 
// Receive data on USART
 
 
char debugBuff[16];
 
 
ISR(USART0__RX_vect)
 
 
ISR(USART0_RX_vect)
 
{
 
	buffer[bufferDataPosition % BUFFER_SIZE] = UDR0;
 
	bufferDataPosition = (bufferDataPosition + 1) % BUFFER_SIZE;
 
	/*sprintf(debugBuff, "bdp: %d, bpp: %d \r\n", bufferDataPosition, bufferParsePosition);
 
	serial0_sendString((debugBuff)); */
 
	//sprintf(debugBuff, "bdp: %d, bpp: %d \r\n", bufferDataPosition, bufferParsePosition);
 
	//serial0_sendString((debugBuff)); 
 
}
 
 
 
 
 
//#define DEBUG
 
 
// Parse data from circular buffer
 
int serparser_parse(void)
 
{
 
	
 
	char byte;
 
 
	// Process first command (if any) on the circular buffer
 
	while(bufferDataPosition != bufferParsePosition)
 
	{
 
		byte = buffer[bufferParsePosition];
master/master/lib/trackuinoGPS/gpsMKa.c
Show inline comments
 
/*
 
* gpsMKa.c
 
*
 
* Created: 11/15/2012 12:02:38 PM
 
*  Author: mkanning
 
*/
 
 
#include <stdbool.h>
 
#include <avr/io.h>
 
#include "gpsMKa.h"
 
#include "../serial.h"
 

	
 

	
 
// holds the byte ALREADY PARSED. includes starting character
 
int bytesReceived = 0;
 

	
 
//data (and checksum) of most recent transmission
 
char data[16];
 

	
 
//used to skip over bytes during parse
 
int skipBytes = 0;
 

	
 
//used to index data arrays during data collection
 
int numBytes = 0;
 

	
 
@@ -62,29 +63,31 @@ enum decodeState {
 
	//RMC data fields
 
	RMC_TIME,
 
	RMC_VALIDITY,
 
	RMC_LATITUDE,
 
	RMC_LONGITUDE,
 
	RMC_KNOTS,
 
	RMC_COURSE,
 
	RMC_DATE,
 
	RMC_MAG_VARIATION,
 
	
 
}decodeState;
 

	
 

	
 

	
 
//// MKa GPS transmission parser START
 
void parse_gps_transmission(void){
 
	
 
	// Pull byte off of the buffer
 
	char byte = serial1_readChar();
 
	char byte = 'a';// serial1_readChar();
 
	
 
	if(byte == '$') //start of transmission sentence
 
	{
 
		decodeState = GET_TYPE;
 
		numBytes = 0; //prep for next phases
 
		skipBytes = 0;
 
		calculatedChecksum = 0;
 
	}
 
	
 
	//parse transmission type
 
	else if (decodeState == GET_TYPE)
 
	{
master/master/lib/watchdog.c
Show inline comments
 
@@ -15,21 +15,21 @@
 
#include <avr/interrupt.h>
 
#include <avr/wdt.h>
 
 
//initialize watchdog
 
void watchdog_setup(void)
 
{
 
	
 
	cli();
 
	wdt_reset();
 
	// Set change enable bit, enable the WDT
 
	WDTCSR = (1<<WDCE)|(1<<WDE);
 
	// Start watchdog, 4 second timeout
 
	WDTCSR = (1<<WDE)|(1<<WDP3)|(1<<WDP0);
 
	WDTCSR = (1<<WDE)|(1<<WDP3)|(1<<WDP0);
 
	sei();
 
}
 
 
// ISR for watchdog timeout. Not currently used, interrupt is disabled.
 
ISR(WDT_vect)
 
{
 
	
 
}
master/master/master.c
Show inline comments
 
@@ -15,102 +15,156 @@
 

	
 
#include <avr/io.h>
 
#include <util/delay.h>
 
#include <avr/wdt.h>
 
#include <avr/interrupt.h>
 
#include <stdio.h>
 
#include <stdbool.h>
 

	
 
#include "lib/serial.h"
 
#include "lib/aprs.h"
 
#include "lib/afsk.h"
 
#include "lib/led.h"
 
#include "lib/logger.h"
 
//#include "lib/logger.h"
 
#include "lib/watchdog.h"
 
//!
 
#include "lib/sd/sd_raw_config.h"
 
#include "lib/looptime.h"
 
#include "lib/slavesensors.h"
 
#include "lib/serparser.h"
 
#include "lib/sensordata.h"
 

	
 
void micro_setup() 
 
{
 

	
 
}
 

	
 
int main(void)
 
{
 
    
 
    _delay_ms(1500); // warmup
 
	// Initialize libraries
 
	time_setup();
 
	
 
	micro_setup();
 
	watchdog_setup();
 
	
 
	watchdog_setup(); // enables interrupts
 
	
 
	led_setup();
 
	
 
	serial0_setup();
 
	_delay_ms(10);
 
	
 
	serial1_setup();
 
	
 
	sensordata_setup(); // must happen before sensors/logger/afsk
 
	slavesensors_setup();
 
	logger_setup();
 
	
 
	afsk_setup();
 

	
 
	//serial0_sendString("\r\n\r\n---------------------------------\r\n");
 
	//serial0_sendString("HAB Controller 1.0 - Initialized!\r\n");
 
	//serial0_sendString("---------------------------------\r\n\r\n");
 
	//serial0_sendString("\f\r\n\r\Hello.\r\n\r\n");
 
	serial0_sendString("\r\n\r\n---------------------------------\r\n");
 
	serial0_sendString("HAB Controller 1.0 - Initialized!\r\n");
 
	serial0_sendString("---------------------------------\r\n\r\n");
 
	serial0_sendString("\f\r\n\r\Hello.\r\n\r\n");
 
	
 
	led_on(LED_POWER);
 
	led_off(LED_SIDEBOARD);
 

	
 
	
 
	// Buffer for string operations
 
	char logbuf[16];
 
	
 
	// Software timers	
 
	uint32_t lastAprsBroadcast = 0;
 
	uint32_t lastLog = 0;
 
	uint32_t lastLedCycle = 0;
 
	
 
	// Result of last parser run
 
	int parseResult = PARSERESULT_NODATA;
 
	
 
	// Write CSV header to SD card
 
	//logger_log("ProgramTime,LastAprsBroadcast,LastLog\n");
 
	
 
	uint8_t ctr = 0;
 
	void spin() {
 
		if(ctr == 0) {
 
			led_on(LED_ACT0);
 
			led_off(LED_ACT1);
 
			led_off(LED_ACT2);
 
			led_off(LED_ACT3);
 
		}			
 
		else if (ctr == 1) {
 
			led_on(LED_ACT1);
 
			led_off(LED_ACT0);
 
			led_off(LED_ACT2);
 
			led_off(LED_ACT3);
 
		}			
 
		else if (ctr == 2) {
 
			led_on(LED_ACT2);
 
			led_off(LED_ACT1);
 
			led_off(LED_ACT0);
 
			led_off(LED_ACT3);
 
		}			
 
		else if (ctr == 3) {
 
			led_on(LED_ACT3);
 
			led_off(LED_ACT1);
 
			led_off(LED_ACT2);
 
			led_off(LED_ACT0);
 
		}			
 
		ctr = (ctr + 1) % 4;
 
	}
 
	
 
	while(1)
 
    {
 
		
 
		if(time_millis() - lastLedCycle > LEDCYCLE_RATE) {
 
			spin();
 
			
 
			lastLedCycle = time_millis();	
 
		}
 
		
 
		// Periodic: Logging
 
		if(time_millis() - lastLog > LOGGER_RATE) 
 
		{
 
			led_on(LED_STATUS);
 
			snprintf(logbuf, 16, "%lu,%d,\r\n", time_millis(), sensordata_get(HUMIDITY));
 
			logger_log(logbuf);
 
			//serial0_sendString("Logging: ");
 
			//serial0_sendString(logbuf);
 
			led_off(LED_STATUS);
 
			
 
			lastLog = time_millis();
 
		}		
 
		
 
		
 
		// Periodic: APRS transmission
 
		if(time_millis() - lastAprsBroadcast > APRS_TRANSMIT_PERIOD) 
 
		{
 
			serial0_sendString(":: APRS Periodic\r\n");
 
			
 
			while(afsk_busy());
 
			aprs_send(); // non-blocking
 
			
 
			//serial0_sendString("Initiating APRS transmission...\r\n");
 
			
 
			// Start getting values for next transmission
 
			if(slavesensors_isrequesting())
 
			{
 
				// TODO: something is terribly wrong
 
			}
 
			else 
 
			{				
 
				slavesensors_startprocess();
 
			}
 
			
 
			lastAprsBroadcast = time_millis();
 
		}			
 
		
 

	
 
		parseResult = serparser_parse();
 
		
 

	
 
		slavesensors_process(parseResult);
 

	
 
		wdt_reset();
 
    }
 
}
 
\ No newline at end of file
master/master/master.cproj
Show inline comments
 
<?xml version="1.0" encoding="utf-8"?>
 
<Project DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
 
  <PropertyGroup>
 
    <SchemaVersion>2.0</SchemaVersion>
 
    <ProjectVersion>6.0</ProjectVersion>
 
    <ToolchainName>com.Atmel.AVRGCC8</ToolchainName>
 
    <ProjectGuid>{8579ec2d-5815-40db-84e0-1d14239c7aea}</ProjectGuid>
 
    <avrdevice>ATmega324P</avrdevice>
 
    <avrdevice>ATmega644PA</avrdevice>
 
    <avrdeviceseries>none</avrdeviceseries>
 
    <OutputType>Executable</OutputType>
 
    <Language>C</Language>
 
    <OutputFileName>$(MSBuildProjectName)</OutputFileName>
 
    <OutputFileExtension>.elf</OutputFileExtension>
 
    <OutputDirectory>$(MSBuildProjectDirectory)\$(Configuration)</OutputDirectory>
 
    <AssemblyName>master</AssemblyName>
 
    <Name>master</Name>
 
    <RootNamespace>master</RootNamespace>
 
    <ToolchainFlavour>Native</ToolchainFlavour>
 
    <KeepTimersRunning>true</KeepTimersRunning>
 
    <OverrideVtor>false</OverrideVtor>
 
@@ -39,25 +39,25 @@
 
      </Channel>
 
    </com_atmel_avrdbg_tool_simulator>
 
    <com_atmel_avrdbg_tool_ispmk2>
 
      <ToolType>com.atmel.avrdbg.tool.ispmk2</ToolType>
 
      <ToolName>AVRISP mkII</ToolName>
 
      <ToolNumber>000200131077</ToolNumber>
 
      <KeepTimersRunning>true</KeepTimersRunning>
 
      <OverrideVtor>false</OverrideVtor>
 
      <OverrideVtorValue>
 
      </OverrideVtorValue>
 
      <Channel>
 
        <host>127.0.0.1</host>
 
        <port>61309</port>
 
        <port>49512</port>
 
        <ssl>False</ssl>
 
      </Channel>
 
      <ToolOptions>
 
        <InterfaceName>ISP</InterfaceName>
 
        <InterfaceProperties>
 
          <JtagDbgClock>249000</JtagDbgClock>
 
          <JtagProgClock>1000000</JtagProgClock>
 
          <IspClock>2010000</IspClock>
 
          <JtagInChain>false</JtagInChain>
 
          <JtagEnableExtResetOnStartSession>false</JtagEnableExtResetOnStartSession>
 
          <JtagDevicesBefore>0</JtagDevicesBefore>
 
          <JtagDevicesAfter>0</JtagDevicesAfter>
 
@@ -123,76 +123,76 @@
 
    <Compile Include="lib\aprs.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\aprs.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\ax25.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\ax25.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\logger.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\led.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\led.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\logger.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\logger.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\looptime.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\looptime.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\byteordering.c">
 
    <Compile Include="lib\SDa\byteordering.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\byteordering.h">
 
    <Compile Include="lib\SDa\byteordering.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\fat.c">
 
    <Compile Include="lib\SDa\fat.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\fat.h">
 
    <Compile Include="lib\SDa\fat.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\fat_config.h">
 
    <Compile Include="lib\SDa\fat_config.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\partition.c">
 
    <Compile Include="lib\SDa\partition.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\partition.h">
 
    <Compile Include="lib\SDa\partition.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\partition_config.h">
 
    <Compile Include="lib\SDa\partition_config.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\sd-reader_config.h">
 
    <Compile Include="lib\SDa\sd-reader_config.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\sd_raw.c">
 
    <Compile Include="lib\SDa\sd_raw.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\sd_raw.h">
 
    <Compile Include="lib\SDa\sd_raw.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sd\sd_raw_config.h">
 
    <Compile Include="lib\SDa\sd_raw_config.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sensordata.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\sensordata.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\serial.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\serial.h">
 
@@ -201,38 +201,35 @@
 
    <Compile Include="lib\serparser.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\serparser.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\slavesensors.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\slavesensors.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\trackuinoGPS\config.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\trackuinoGPS\gpsMKa.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\trackuinoGPS\gpsMKa.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\watchdog.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="lib\watchdog.h">
 
      <SubType>compile</SubType>
 
    </Compile>
 
    <Compile Include="master.c">
 
      <SubType>compile</SubType>
 
    </Compile>
 
  </ItemGroup>
 
  <ItemGroup>
 
    <Folder Include="lib" />
 
    <Folder Include="lib\SDa" />
 
    <Folder Include="lib\trackuinoGPS" />
 
    <Folder Include="lib\sd" />
 
  </ItemGroup>
 
  <Import Project="$(AVRSTUDIO_EXE_PATH)\\Vs\\Compiler.targets" />
 
</Project>
 
\ No newline at end of file
0 comments (0 inline, 0 general)