PicoBeacon.c File Reference

#include <18f2525.h>
#include <stdlib.h>
#include <string.h>

Include dependency graph for PicoBeacon.c:

Go to the source code of this file.

Data Structures

struct  GPSPOSITION_STRUCT
 GPS Position information. More...

Defines

#define IO_LED   PIN_A2
 Heartbeat LED - Port A2.
#define IO_PS0   PIN_A3
 AD9954 DDS Profile Select 0 - Port A3.
#define IO_PTT   PIN_A4
 UHF amplifier and PA chain - Port A4.
#define IO_UPDATE   PIN_A5
 AD9954 DDS Update - Port A5.
#define IO_CS   PIN_B0
 AD9954 CS (Chip Select) - Port B0.
#define IO_GPS_PWR   PIN_B1
 GPS Engine Power - Port B1.
#define IO_PS1   PIN_C0
 AD9954 DDS Profile Select 1 - Port C0.
#define IO_OSK   PIN_C2
 AD9954 DDS OSK (Output Shift Key) - Port C2.
#define IO_GPS_TXD   PIN_C6
 GPS engine serial transmit pin - Port C6.
#define TIME_DUTYCYCLE_0   0
 0% duty cycle (LED Off) constant for function timeSetDutyCycle
#define TIME_DUTYCYCLE_10   1
 10% duty cycle constant for function timeSetDutyCycle
#define TIME_DUTYCYCLE_70   7
 70% duty cycle constant for function timeSetDutyCycle
#define ADC_REF   0
 PIC ADC Channel number of the reference voltage.
#define ADC_MAINBUS   1
 PIC ADC Channel number of the main bus voltage.
#define MAIN_BUS_VOLT_OFFSET   20
 Input diode drop in units of 0.01 volts.
#define DIAG_BYTES_PER_LINE   32
 Number of bytes per line to display when reading flight data recorder.
#define DDS_AD9954_CFR1   0x00
 AD9954 CFR1 - Control functions including RAM, profiles, OSK, sync, sweep, SPI, and power control settings.
#define DDS_AD9954_CFR2   0x01
 AD9954 CFR2 - Control functions including sync, PLL multiplier, VCO range, and charge pump current.
#define DDS_AD9954_ASF   0x02
 AD9954 ASF - Auto ramp rate speed control and output scale factor (0x0000 to 0x3fff).
#define DDS_AD9954_ARR   0x03
 AD9954 ARR - Amplitude ramp rate for OSK function.
#define DDS_AD9954_FTW0   0x04
 AD9954 FTW0 - Frequency tuning word 0.
#define DDS_AD9954_FTW1   0x06
 AD9954 FTW1 - Frequency tuning word 1.
#define DDS_AD9954_NLSCW   0x07
 AD9954 NLSCW - Negative Linear Sweep Control Word used for spectral shaping in FSK mode.
#define DDS_AD9954_PLSCW   0x08
 AD9954 PLSCW - Positive Linear Sweep Control Word used for spectral shaping in FSK mode.
#define DDS_AD9954_RWCW0   0x07
 AD9954 RSCW0 - RAM Segment Control Word 0.
#define DDS_AD9954_RWCW1   0x08
 AD9954 RSCW0 - RAM Segment Control Word 1.
#define DDS_RAM   0x0b
 AD9954 RAM segment.
#define DDS_FREQ_TO_FTW_DIGITS   9
 Number of digits in DDS frequency to FTW conversion.
#define FLASH_CS   PIN_B3
 Flash Chip Select - Port B3.
#define FLASH_CLK   PIN_B5
 Flash Clock - Port B5.
#define FLASH_D   PIN_B4
 Flash Data Input - Port B4.
#define FLASH_Q   PIN_B2
 Flash Data Output - Port B2.
#define GPS_BUFFER_SIZE   50
 The maximum length of a binary GPS engine message.
#define LOG_WRITE_BUFFER_SIZE   40
 Number of bytes to buffer before writing to flash memory.
#define SERIAL_BUFFER_SIZE   64
 Size of serial port FIFO in bytes. It must be a power of 2, i.e. 2, 4, 8, 16, etc.
#define SERIAL_BUFFER_MASK   0x3f
 Mask to wrap around at end of circular buffer. (SERIAL_BUFFER_SIZE - 1).
#define TIME_RATE   125
 The change in the CCP_1 register for each 104uS (9600bps) interrupt period.
#define TNC_TX_DELAY   45
 The number of start flag bytes to send before the packet message. (360bits * 1200bps = 300mS).
#define TNC_BUFFER_SIZE   80
 The size of the TNC output buffer.

Typedefs

typedef boolean bool_t
 Boolean value { false, true }.
typedef signed int8 int8_t
 Signed 8-bit number in the range -128 through 127.
typedef unsigned int8 uint8_t
 Unsigned 8-bit number in the range 0 through 255.
typedef signed int16 int16_t
 Signed 16-bit number in the range -32768 through 32767.
typedef unsigned int16 uint16_t
 Unsigned 16-bit number in the range 0 through 65535.
typedef signed int32 int32_t
 Signed 32-bit number in the range -2147483648 through 2147483647.
typedef unsigned int32 uint32_t
 Unsigned 32-bit number in the range 0 through 4294967296.

Enumerations

enum  DDS_MODE { DDS_MODE_NOT_INITIALIZED, DDS_MODE_POWERDOWN, DDS_MODE_AFSK, DDS_MODE_FSK }
 Operational modes of the AD9954 DDS for the ddsSetMode function. More...
enum  GPS_FIX_TYPE { GPS_NO_FIX, GPS_2D_FIX, GPS_3D_FIX }
 Type of GPS fix. More...
enum  LOG_TYPE { LOG_BOOTED = 0xb4, LOG_COORD = 0xa5, LOG_TEMPERATURE = 0x96, LOG_VOLTAGE = 0x87 }
 Define the log record types. More...
enum  TNC_DATA_MODE { TNC_MODE_STANDBY, TNC_MODE_1200_AFSK, TNC_MODE_9600_FSK }
 Operational modes of the TNC for the tncSetMode function. More...
enum  GPS_PARSE_STATE_MACHINE {
  GPS_START1, GPS_START2, GPS_COMMAND1, GPS_COMMAND2,
  GPS_READMESSAGE, GPS_CHECKSUMMESSAGE, GPS_EOMCR, GPS_EOMLF
}
 GPS parse engine state machine values. More...
enum  TNC_TX_1200BPS_STATE {
  TNC_TX_READY, TNC_TX_SYNC, TNC_TX_HEADER, TNC_TX_DATA,
  TNC_TX_END
}
 States that define the current mode of the 1200 bps (A-FSK) state machine. More...
enum  TNC_MESSAGE_TYPE { TNC_BOOT_MESSAGE, TNC_STATUS, TNC_GGA, TNC_RMC }
 Enumeration of the messages we can transmit. More...

Functions

void ddsInit ()
 Initialize the DDS regsiters and RAM.
void ddsSetAmplitude (uint8_t amplitude)
 Set the DDS amplitude in units of dBc of full scale where 1 is 0.1 dB.
void ddsSetOutputScale (uint16_t scale)
 Set DDS amplitude value in the range 0 to 16383 where 16383 is full scale.
void ddsSetFSKFreq (uint32_t ftw0, uint32_t ftw1)
 Set DDS frequency tuning word for the FSK 0 and 1 values.
void ddsSetFreq (uint32_t freq)
 Convert frequency in hertz to 32-bit DDS FTW (Frequency Tune Word).
void ddsSetFTW (uint32_t ftw)
 Set DDS frequency tuning word.
void ddsSetMode (DDS_MODE mode)
 Set the DDS to run in A-FSK, FSK, or PSK31 mode.
void flashErase ()
 Erase the entire flash device (all locations set to 0xff).
uint8_t flashGetByte ()
 Read a single byte from the flash device through the serial interface.
void flashReadBlock (uint32_t address, uint8_t *block, uint16_t length)
 Read a block of memory from the flash device.
void flashSendByte (uint8_t value)
 Write a single byte to the flash device through the serial interface.
void flashSendAddress (uint32_t address)
 Write the 24-bit address to the flash device through the serial interface.
void flashWriteBlock (uint32_t address, uint8_t *block, uint8_t length)
 Write a block of memory to the flash device.
void gpsInit ()
 Initialize the GPS subsystem.
bool_t gpsIsReady ()
 Determine if new GPS message is ready to process.
GPS_FIX_TYPE gpsGetFixType ()
 Get the type of fix.
int32_t gpsGetPeakAltitude ()
 Peak altitude detected while GPS is in 3D fix mode since the system was booted.
void gpsPowerOn ()
 Turn on the GPS engine power and serial interface.
bool_t gpsSetup ()
 Verify the GPS engine is sending the @Hb position report message.
void gpsUpdate ()
 Read the serial FIFO and process complete GPS messages.
int16_t lm92GetTemp ()
 Read the LM92 temperature value in 0.1 degrees F.
void logInit ()
 Prepare the flight data recorder for logging.
uint32_t logGetAddress ()
 Last used address in flash memory.
void logType (LOG_TYPE type)
 Start a entry in the data log.
void logUint8 (uint8_t value)
 Save an unsigned, 8-bit value in the log.
void logInt16 (int16_t value)
 Save a signed, 16-bit value in the log.
bool_t serialHasData ()
 Determine if the FIFO contains data.
void serialInit ()
 Initialize the serial processor.
uint8_t serialRead ()
 Get the oldest character from the FIFO.
void serialUpdate ()
 Read and store any characters in the PIC serial port in a FIFO.
uint16_t sysCRC16 (uint8_t *buffer, uint8_t length, uint16_t crc)
 Calculate the CRC-16 CCITT of buffer that is length bytes long.
void sysInit ()
 Initialize the system library and global resources.
void sysLogVoltage ()
 Log the ADC values of the bus and reference voltage values.
uint8_t timeGetTicks ()
 Running 8-bit counter that ticks every 100mS.
void timeInit ()
 Initialize the real-time clock.
void timeSetDutyCycle (uint8_t dutyCycle)
 Set the blink duty cycle of the heartbeat LED.
void timeUpdate ()
 Timer interrupt handler called every 104uS (9600 times/second).
void tncInit ()
 Initialize the TNC internal variables.
bool_t tncIsFree ()
 Determine if the hardware if ready to transmit a 1200 baud packet.
void tncHighRate (bool_t state)
void tncSetMode (TNC_DATA_MODE dataMode)
 Configure the TNC for the desired data mode.
void tnc1200TimerTick ()
 Method that is called every 833uS to transmit the 1200bps A-FSK data stream.
void tnc9600TimerTick ()
 Method that is called every 104uS to transmit the 9600bps FSK data stream.
void tncTxByte (uint8_t character)
 Write character to the TNC buffer.
void tncTxPacket (TNC_DATA_MODE dataMode)
 Prepare an AX.25 data packet.
void adcInit ()
 Intialize the ADC subsystem.
uint16_t adcGetMainBusVolt ()
 Filtered main bus voltage in 10mV resolution.
uint16_t adcRawBusVolt ()
 Get the current ADC value for the main bus voltage.
uint16_t adcRawRefVolt ()
 Get the current ADC value for the reference source voltage.
void adcUpdate (void)
 Read and filter the ADC channels for bus voltages.
void diagEraseFlash ()
 Process the command to erase the data logger flash.
void diagMenu ()
 Display the engineering mode menu.
void diagReadFlash ()
 Process the command to dump the contents of the data logger flash.
void diag1PPS ()
void diagPort ()
 Process diagnostic commands through the debug RS-232 port.
bool_t flashIsWriteInProgress ()
 Determine if a flash write or erase operation is currently in progress.
void flashInit ()
 Initialize the flash memory subsystem.
uint8_t gpsNMEAChecksum (uint8_t *buffer, uint8_t length)
 Calculate NMEA-0183 message checksum of buffer that is length bytes long.
void gpsParsePositionMessage ()
 Parse the Motorola @Hb (Short position/message) report.
void gpsPowerOff ()
 Turn off the GPS engine power and serial interface.
void logFlush ()
 Write the contents of the temporary log buffer to the flash device.
void logUint16 (uint16_t value)
 Save an unsigned, 16-bit value in the log.
void logInt32 (int32_t value)
 Save a signed, 32-bit value in the log.
void sysLogGPSData ()
 Log the current GPS position.
bool_t timeIsUpdate ()
 Function return true once a second based on real-time clock.
void timeSetRunFlag ()
 Set a flag to indicate the flight time should run.
bool_t tncIsTimeSlot (uint8_t timeSeconds)
 Determine if the seconds value timeSeconds is a valid time slot to transmit a message.
void tncNMEATime ()
 Generate the GPS NMEA standard UTC time stamp.
void tncNMEAFix ()
 Generate the GPS NMEA standard latitude/longitude fix.
void tncGPGGAPacket ()
 Generate the GPS NMEA-0183 $GPGGA packet.
void tncGPRMCPacket ()
 Generate the GPS NMEA-0183 $GPRMC packet.
void tncStatusPacket (int16_t temperature)
 Generate the plain text status packet.
void init ()
void test ()
void main ()

Variables

uint16_t adcMainBusVolt
 Filtered voltages using a single pole, low pass filter.
DDS_MODE ddsMode
 Current operational mode.
const uint32_t DDS_MULT [DDS_FREQ_TO_FTW_DIGITS] = { 11, 7, 7, 3, 4, 8, 4, 9, 1 }
 Array of multiplication factors used to convert frequency to the FTW.
const uint32_t DDS_DIVISOR [DDS_FREQ_TO_FTW_DIGITS-1] = { 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000 }
 Array of divisors used to convert frequency to the FTW.
const uint16_t DDS_AMP_TO_SCALE []
 Lookup table to convert dB amplitude scale in 0.5 steps to a linear DDS scale factor.
const uint32_t freqTable [256]
 Frequency Word List - 4.0KHz FM frequency deviation at 81.15MHz (445.950MHz).
uint8_t gpsIndex
 Index into gpsBuffer used to store message data.
GPS_PARSE_STATE_MACHINE gpsParseState
 State machine used to parse the GPS message stream.
uint8_t gpsBuffer [GPS_BUFFER_SIZE]
 Buffer to store data as it is read from the GPS engine.
int32_t gpsPeakAltitude
 Peak altitude detected while GPS is in 3D fix mode.
uint8_t gpsChecksum
 Checksum used to verify binary message from GPS engine.
GPSPOSITION_STRUCT gpsPosition
 Last verified GPS message received.
uint32_t logAddress
 Last used address in flash memory.
uint8_t logBuffer [LOG_WRITE_BUFFER_SIZE]
 Temporary buffer that holds data before it is written to flash device.
uint8_t logIndex
 Current index into log buffer.
uint8_t serialHead
 Index to the next free location in the buffer.
uint8_t serialTail
 Index to the next oldest data in the buffer.
uint8_t serialBuffer [SERIAL_BUFFER_SIZE]
 Circular buffer (FIFO) to hold serial data.
uint8_t timeTicks
 A counter that ticks every 100mS.
uint16_t timeInterruptCount
 Counts the number of 104uS interrupts for a 100mS time period.
uint8_t time100ms
 Counts the number of 100mS time periods in 1 second.
uint8_t timeSeconds
 System time in seconds.
uint8_t timeMinutes
 System time in minutes.
uint8_t timeHours
 System time in hours.
uint8_t timeDutyCycle
 Desired LED duty cycle 0 to 9 where 0 = 0% and 9 = 90%.
uint16_t timeCompare
 Current value of the timer 1 compare register used to generate 104uS interrupt rate (9600bps).
uint16_t timeNCO
 16-bit NCO where the upper 8-bits are used to index into the frequency generation table.
uint16_t timeNCOFreq
 Audio tone NCO update step (phase).
uint8_t timeLowRateCount
 Counter used to deciminate down from the 104uS to 833uS interrupt rate. (9600 to 1200 baud).
TNC_DATA_MODE tncDataMode
 Current TNC mode (standby, 1200bps A-FSK, or 9600bps FSK).
bool_t timeUpdateFlag
 Flag set true once per second.
bool_t timeRunFlag
 Flag that indicate the flight time should run.
uint8_t TNC_AX25_HEADER [30]
 AX.25 compliant packet header that contains destination, station call sign, and path.
uint8_t tncTxBit
 The next bit to transmit.
TNC_TX_1200BPS_STATE tncMode
 Current mode of the 1200 bps state machine.
uint8_t tncBitCount
 Counter for each bit (0 - 7) that we are going to transmit.
uint8_t tncShift
 A shift register that holds the data byte as we bit shift it for transmit.
uint8_t tncIndex
 Index into the APRS header and data array for each byte as we transmit it.
uint8_t tncLength
 The number of bytes in the message portion of the AX.25 message.
uint8_t tncBitStuff
 A copy of the last 5 bits we've transmitted to determine if we need to bit stuff on the next bit.
uint8_ttncBufferPnt
 Pointer to TNC buffer as we save each byte during message preparation.
TNC_MESSAGE_TYPE tncPacketType
 The type of message to tranmit in the next packet.
uint8_t tncBuffer [TNC_BUFFER_SIZE]
 Buffer to hold the message portion of the AX.25 packet as we prepare it.
bool_t tncHighRateFlag
 Flag that indicates we want to transmit every 5 seconds.
uint32_t counter
uint8_t bitIndex
uint8_t streamIndex
uint8_t value
uint8_t bitStream [] = { 0x10, 0x20, 0x30 }


Define Documentation

#define IO_CS   PIN_B0

AD9954 CS (Chip Select) - Port B0.

Definition at line 196 of file PicoBeacon.c.

Referenced by ddsInit(), ddsSetFSKFreq(), ddsSetFTW(), ddsSetMode(), ddsSetOutputScale(), and sysInit().

#define IO_GPS_PWR   PIN_B1

GPS Engine Power - Port B1.

Definition at line 199 of file PicoBeacon.c.

Referenced by gpsPowerOff(), and gpsPowerOn().

#define IO_GPS_TXD   PIN_C6

GPS engine serial transmit pin - Port C6.

Definition at line 208 of file PicoBeacon.c.

Referenced by sysInit().

#define IO_LED   PIN_A2

Heartbeat LED - Port A2.

Definition at line 184 of file PicoBeacon.c.

Referenced by diagPort(), main(), sysInit(), and timeUpdate().

#define IO_OSK   PIN_C2

AD9954 DDS OSK (Output Shift Key) - Port C2.

Definition at line 205 of file PicoBeacon.c.

Referenced by ddsSetAmplitude(), diagPort(), sysInit(), tnc1200TimerTick(), and tncTxPacket().

#define IO_PS0   PIN_A3

AD9954 DDS Profile Select 0 - Port A3.

Definition at line 187 of file PicoBeacon.c.

Referenced by sysInit().

#define IO_PS1   PIN_C0

AD9954 DDS Profile Select 1 - Port C0.

Definition at line 202 of file PicoBeacon.c.

Referenced by sysInit().

#define IO_PTT   PIN_A4

UHF amplifier and PA chain - Port A4.

Definition at line 190 of file PicoBeacon.c.

Referenced by diagPort(), sysInit(), tnc1200TimerTick(), and tncTxPacket().

#define IO_UPDATE   PIN_A5

AD9954 DDS Update - Port A5.

Definition at line 193 of file PicoBeacon.c.

Referenced by ddsInit(), ddsSetFSKFreq(), ddsSetFTW(), ddsSetMode(), ddsSetOutputScale(), and sysInit().

#define TIME_DUTYCYCLE_0   0

0% duty cycle (LED Off) constant for function timeSetDutyCycle

Definition at line 356 of file PicoBeacon.c.

#define TIME_DUTYCYCLE_10   1

10% duty cycle constant for function timeSetDutyCycle

Definition at line 359 of file PicoBeacon.c.

Referenced by gpsSetup().

#define TIME_DUTYCYCLE_70   7

70% duty cycle constant for function timeSetDutyCycle

Definition at line 362 of file PicoBeacon.c.

Referenced by timeInit().


Typedef Documentation

typedef boolean bool_t

Boolean value { false, true }.

Definition at line 158 of file PicoBeacon.c.

typedef signed int16 int16_t

Signed 16-bit number in the range -32768 through 32767.

Definition at line 167 of file PicoBeacon.c.

typedef signed int32 int32_t

Signed 32-bit number in the range -2147483648 through 2147483647.

Definition at line 173 of file PicoBeacon.c.

typedef signed int8 int8_t

Signed 8-bit number in the range -128 through 127.

Definition at line 161 of file PicoBeacon.c.

typedef unsigned int16 uint16_t

Unsigned 16-bit number in the range 0 through 65535.

Definition at line 170 of file PicoBeacon.c.

typedef unsigned int32 uint32_t

Unsigned 32-bit number in the range 0 through 4294967296.

Definition at line 176 of file PicoBeacon.c.

typedef unsigned int8 uint8_t

Unsigned 8-bit number in the range 0 through 255.

Definition at line 164 of file PicoBeacon.c.


Enumeration Type Documentation

enum DDS_MODE

Operational modes of the AD9954 DDS for the ddsSetMode function.

Enumerator:
DDS_MODE_NOT_INITIALIZED  Device has not been initialized.
DDS_MODE_POWERDOWN  Device in lowest power down mode.
DDS_MODE_AFSK  Generate FM modulated audio tones.
DDS_MODE_FSK  Generate true FSK tones.

Definition at line 213 of file PicoBeacon.c.

Type of GPS fix.

Enumerator:
GPS_NO_FIX  No GPS FIX.
GPS_2D_FIX  2D (Latitude/Longitude) fix.
GPS_3D_FIX  3D (Latitude/Longitude/Altitude) fix.

Definition at line 244 of file PicoBeacon.c.

enum LOG_TYPE

Define the log record types.

Enumerator:
LOG_BOOTED  Time stamp the log was started.
LOG_COORD  GPS coordinates.
LOG_TEMPERATURE  Temperature.
LOG_VOLTAGE  Bus voltage.

Definition at line 325 of file PicoBeacon.c.

Operational modes of the TNC for the tncSetMode function.

Enumerator:
TNC_MODE_STANDBY  No operation waiting for setup and configuration.
TNC_MODE_1200_AFSK  1200 bps using A-FSK (Audio FSK) tones.
TNC_MODE_9600_FSK  9600 bps using true FSK tones.

Definition at line 370 of file PicoBeacon.c.


Function Documentation

void init (  ) 

Definition at line 2931 of file PicoBeacon.c.

References bitIndex, bitStream, counter, streamIndex, and value.

void main (  ) 

void test (  ) 

Definition at line 2939 of file PicoBeacon.c.

References bitIndex, bitStream, counter, streamIndex, and value.

Referenced by main().


Variable Documentation

Definition at line 2925 of file PicoBeacon.c.

Referenced by init(), and test().

uint8_t bitStream[] = { 0x10, 0x20, 0x30 }

Definition at line 2929 of file PicoBeacon.c.

Referenced by init(), and test().

Definition at line 2923 of file PicoBeacon.c.

Referenced by init(), and test().

Definition at line 2926 of file PicoBeacon.c.

Referenced by init(), and test().

Definition at line 2927 of file PicoBeacon.c.

Referenced by flashGetByte(), gpsUpdate(), init(), lm92GetTemp(), serialRead(), sysCRC16(), and test().


Generated on Sun Oct 5 11:25:45 2008 for Pico Beacon by  doxygen 1.5.7