Ying-zong Huang

EE281 Project,Stanford University, Fall 2002

Wireless Freeform Input Device

 

Home
Design
Hardware
Software
Tools
Links

The transmitter code is in C and is compiled with AVR-GCC. The AVR-GCC basic libraries will be needed. Not all of the functions in the code are used. Some are for debug purposes. Others are created for future use. The receiver code is in AVR assembly.

Here are packaged versions of the transmitter and receiver software, including binaries:

Transmitter code.

Receiver code.

The code listing of the same is down the page.

Software Design Choices

Here is an outline of the software design choices, with some explanation afterwards.

Tilt vs. Position algorithms

  1. Implement digital filters using IIR
  2. Detect tilt, not position

Other

  1. Emulate a standard serial mouse
  2. Spend minimum time in the ICP interrupt
  3. No sleep between edge transitions
  4. Reduce power consumption when no change is detected

Design Choice Details

Tilt vs. Position algorithms

As mentioned, the accelerometers cannot distinguish one applied force from another. Even assuming that the device is used in an inertial (non-accelerating) reference frame, there is still a problem of distinguishing detected force due to gravity and detected force due to manual application.

This is really a problem of splitting a sum vector into two components, where we know that the gravitational component is constant in some direction. If three dimensions of accelerometer data are available, then based on certain assumptions, it may be possible to find the two force components. If the device is allowed to freely tilt and rotate, then both translational motion of the center of mass and the rigid motion about the center of mass must be accounted for. We make two assumptions: the force due to gravity is, on a time-average, of larger magnitude than other applied forces; and tilt or rotation is slow compared to translational movement.

A method to eliminate gravity that seemed promising was to self-calibrate to the gravitational force while at rest (detected by the lack of change in force, which is nearly impossible to achieve when the object is held), then, any additional force due to movement, which for a moment may be large, can be instantaneously integrated to a translational and a rotational displacement. This is used to calculate the new direction of gravity. If changes fall below a certain level, the remaining force is assumed to be the gravitational force and the device self-calibrates again.

It was originally proposed to use absolute position to move the mouse cursor. Since we did not implement three dimensions of accelerometer input and instead just have an accelerometer in one location, it was quickly decided that we must limit the user to one plane of translational movement only, though that plane need not be orthogonal to the gravitational force. The problem then becomes one of eliminating a constant force due to gravity as well as residual noise forces due to unsteadiness of movement. The constant force can be eliminated by a high-pass filter. The noise though, is hard to eliminate. But let us assume the noise is not significant.

An IIR filter is fairly easy to implement and we can have a sharp cutoff if we use a higher order IIR. In fact, we used a first-order IIR (pole: z=0.977, zero: z=0.988) and eliminated the frequency components below 2Hz or so.

It worked well for magnitude cutoff. Unfortunately, the shape of the force data is distorted, most likely due to the nonlinear phase of the frequency response. When we summed the force (proportional to acceleration) to get a scaled velocity estimate (we reset the velocity to zero after a short period of no acceleration), there was a lot of overshoot around sharp transitions:

A symmetric FIR with a linear phase response was also investigated, but to get a frequency response cutoff as sharp as the IIR above, the length of the filter needed to be so long (due largely to the high sampling rate, 500Hz) that the number of multiplication operations was prohibitive.

The mouse cursor can be moved with this kind of data, but it came far short of true absolute position, and the overshoot made the cursor wiggle, that it was decided this was not an acceptable way to accurately control a mouse cursor.

What is left is to use tilt as the primary indicator of cursor position. In fact, due to the mouse driver packet format, we made tilt the indicator of cursor velocity, which was fine. Now, we have a simpler problem because we need not be so accurate at every moment, but simply need convergence as quickly as possible to the static tilt. So we choose a low pass filter (pole: z=0.984, zero: z= -1):

Now we get this type of filtered force output, which is taken to be proportional mouse cursor velocity:

In this case, the user chooses what constitutes "zero" tilt by holding both buttons down. In the graph above, the user reset the "zero" tilt setting midway across the graph.

Other

On Windows, a serial mouse (or perhaps all serial devices) identifies itself on a hardware scan by sending bytes upon request (request comes in some form of handshake on the serial port). Once identified, drivers are installed for the device and the port is reserved for the device. The device then communicates with the driver in an agreed format. We emulate a standard serial mouse because we found the specs for both the self-identification and reporting formats for it. We didn't have other types of serial mouse around. It would have been interesting to emulate a serial MS IntelliMouse (with a wheel) by letting spurts of translational movement correspond to z-scrolls in addition to the current x and y cursor movement capabilities.

As for the ICP interrupt, we keep it really short (AVR-GCC compiles this to about 50 clock cycles, mostly interrupt overhead) so as to maximize the effective resolution of the PWM detection. In case an edge change is missed, however, it is most likely detected on the next edge change and the function GetFromICPQueue recovers by using information from the last detected edge.

A last word on saving power by going to sleep. We found that it takes a large number of accelerometer samples before the oscillators, hence timers settle after a wakeup from sleep; therefore, it was not feasible to go to sleep between each edge transition and letting the ICP interrupt wake up the device. For the same reason, it is also not overly useful to go to sleep entirely when there is no activity only to wake up and poll every 30ms (longest timer overflow period for the 8-bit timers). Thus, we just shut off the activity indicator LED and stop transmitting over the radio link when it is detected that there is no activity.

Code Listing

transmitter.c

/******************
 * YING-ZONG HUANG
 * December, 2002
 * Wireless Freeform Input Device
 * Transmitter Code
 ******************/
//----- Include Files ---------------------------------------------------------
#include <io.h>			// include I/O definitions (port names, pin names, etc)
#include <sig-avr.h>	// include "signal" names (interrupt names)
#include <interrupt.h>	// include interrupt support
#include <math.h>
#include "global.h"		// include our global settings
//#define __DEBUG_MODE__
//----- Defines ---------------------------------------------------------------
#ifdef __DEBUG_MODE__
	#define BAUD_RATE	115200
	#define BAUD_DIV	((F_CPU/8/BAUD_RATE-1)+1)
#else
	#define BAUD_RATE	1200
	#define BAUD_DIV	(F_CPU/16/BAUD_RATE-1)	// non-double mode
#endif
#define M_DDR	DDRD
#define M_PIN	PIND
#define	M_BL	1<<5
#define	M_BR	1<<4
#define M_IDENT	(M_BL | M_BR)
#define M_MASK	(M_BL | M_BR)
#define	A_DDR	DDRD
#define A_PIN	PIND
#define A_X		1<<2
#define A_Y		1<<3
#define A_ICP	1<<6
#define A_MASK	(A_X | A_Y | A_ICP)
#define L_DDR	DDRD
#define	L_PORT	PORTD
#define	L_MASK	1<<7
#define U_DDR	DDRD	// usart
#define	U_MASK	1<<2
#define	MEM_BASE	0x0060	// base of the RAM
#define BUF_ICP_CHUNKS	40
#define BUF_ICP_SIZE	3
#define BUF_DIFF_CHUNKS	20	// how many elements of struct in buffer
#define FILT_ORD 1
#define sleep() ({ asm volatile ("sleep" "\n\t");})
typedef struct {
	u16 CurTime;
	u08 PinState;
} ICPT;
typedef struct {
	u16 onTime;
	u16 offTime;
} DIFFT;
typedef struct {
	DIFFT* BUF_DIFF;
	u08 bufDiffHead;
	u08 bufDiffTail;
	s16 pBufHistOut[FILT_ORD];
	s16 pBufHistIn[FILT_ORD];	// for filtering
} BDT;
typedef struct {
	u08 b;
	s08 x;
	s08 y;
	u08 btn_old;
	s16 XCenter;
	s16 YCenter;	
} MOUSET;
typedef s16 (*fnFiltT)(s16 In, s16* pLastIn, s16* pLastOut);
//----- Functions -------------------------------------------------------------
void InitAll(void);
inline void MemInit(void);
inline void USARTInit(void);
inline void ICPInit(void);
void WakeInit(void);
void USARTSend(u08 txData);
//u08 CheckButtons(void);
void EnQ(u08 Byte, u08* pQBuf, u08* pQHead, u08 Size);
u08 DeQ(u08* pQBuf, u08* pQTail, u08 Size);
void EnQW(u16 Word, u16* pQBuf, u08* pQHead, u08 Elems);
s16 LPF(s16 In, s16* pLastIn, s16* pLastOut);
s16 HPF(s16 In, s16* pLastIn, s16* pLastOut);
s16 fmul(s16 x, u08 y);
void MousePack(MOUSET* pm);
void GetFromICPQueue(void);
u08 ProcDiffQueue(BDT* bdt, s16* pOut);
s08 ShiftClip(s16 In);
//----- Global Variables ------------------------------------------------------
// shared buffers
ICPT BUF_ICP[BUF_ICP_CHUNKS];
DIFFT BUF_DIFFX[BUF_DIFF_CHUNKS];
DIFFT BUF_DIFFY[BUF_DIFF_CHUNKS];
// and buffer pointers
volatile register u08 bufICPHead asm("r18");
volatile register u08 bufICPTail asm("r19");
BDT bdtX = {BUF_DIFFX, 0, 0, 0, 0};
BDT bdtY = {BUF_DIFFY, 0, 0, 0, 0};
MOUSET coord = {0, 0, 0, 0, 0, 0};
volatile u08 MouseXmitStatus = 0;
enum {WaitInit=0, WaitDown, WaitUp};
u08 XState=WaitInit, YState=WaitInit;
//----- Begin Code ------------------------------------------------------------
SIGNAL(SIG_INPUT_CAPTURE1)
{	// all other interrupts disabled while in here, so we should hurry.
	register u08* ptr = (u08*)BUF_ICP + bufICPHead;
	*(ptr++) = inb(ICR1L);
	*(ptr++) = inb(ICR1H);
	*ptr = inb(A_PIN);
	bufICPHead += BUF_ICP_SIZE;
	if( bufICPHead == BUF_ICP_CHUNKS * BUF_ICP_SIZE )
		bufICPHead = 0;
	// work in clobber mode...
}
INTERRUPT(SIG_UART_TRANS)
{
	if(MouseXmitStatus == 1) {
		MouseXmitStatus++;
		USARTSend(coord.x);
	} else if(MouseXmitStatus == 2) {
		MouseXmitStatus++;
		USARTSend(coord.y);
	} else if(MouseXmitStatus == 4) {
		MouseXmitStatus++;
		USARTSend('2');
	} else	// done
		MouseXmitStatus = 0;
}
int main(void)
{
	s16 VX, VY;
	InitAll();
	u08 btns;
	u08 status;
	s08 x, y, old_x=0, old_y=0;
	u16	cnt=0; //s
	while(1) {
		GetFromICPQueue();
		status = ProcDiffQueue(&bdtX, &VX) && ProcDiffQueue(&bdtY, &VY);
		btns = (~inb(M_PIN) & M_MASK);	// switch state
		if( btns == M_IDENT ) {
#ifndef __DEBUG_MODE__
			if(MouseXmitStatus == 0) {	// if ready to send
				MouseXmitStatus = 4;	// transmit ident string
				USARTSend('M');
			}
#endif
			// calibrate level position
			coord.XCenter = VX;
			coord.YCenter = VY;
		} else if( status ) {	// has x y data
			VX -= coord.XCenter;
			VY -= coord.YCenter;
			x = -ShiftClip(VX);
			y = -ShiftClip(VY);
			if(x == old_x && y == old_y)	//s
				cnt++;	// s: count for sleeping
			else {	//s
				cnt = 0;	//s
				outb(L_PORT, inb(L_PORT) ^ L_MASK);	// toggle LED whenever there is movement
			}
			old_x = x; old_y = y;
			// if we are ready to send, then send, otherwise, throw data away
			if(cnt >= 1000) {	// about two seconds of no movement
				outb(L_PORT, inb(L_PORT) & ~L_MASK);	//turn off LED
				//outb(TIMSK, 1<<TOIE0);	// turn on wake interrupt, turn off icp interrupt
				//sleep();
				//outb(TIMSK, 1<<TICIE1);	// turn on icp interrupt, turn off timer interrupt
				//XState = YState = WaitInit;	// do icp edges from the first state
			}
			else {
#ifdef	__DEBUG_MODE__
				USARTSend(x);	// debug
#else
				if( (btns != coord.btn_old || x != 0 || y != 0)
					&& MouseXmitStatus == 0 ) {
					coord.b = btns;
					coord.x = x;
					coord.y = y;
					coord.btn_old = coord.b;
					MousePack(&coord);
					MouseXmitStatus=1;
					USARTSend(coord.b);	// get started by sending the first byte
				}
#endif
			}
		}
	}
}
s08 ShiftClip(s16 In)
{
	u08 sgn = (In >= 0);
	In = In >= 0 ? In>>5 : (-In)>>5;
	In -= 4;	// clip (dead zone)
	if(In < 0)
		In = 0;
	if(sgn)
		return In;
	else
		return -In;
}
u08 ProcDiffQueue(BDT* bdt, s16* pOut)
{
	s16 In;
	if(bdt->bufDiffHead != bdt->bufDiffTail) {	// have one more input point
		// acquire data
		In = (s16)(bdt->BUF_DIFF[bdt->bufDiffTail].onTime);	// grab on time interval
		if(++(bdt->bufDiffTail) == BUF_DIFF_CHUNKS)
			bdt->bufDiffTail = 0;
		*pOut = LPF(In, bdt->pBufHistIn, bdt->pBufHistOut);
		/* high pass filter here to get rid of tilt-acceleration, then integrate once for v.
			//OutX = -HPF(&LastInX, InX, &LastOutX);
			// now integrate by simply summing
			//VX += OutX >= 0 ? OutX>>7 : -((-OutX)>>7);
			//VX += (OutX >> 3);	// 3 bits of noise as observed.
			if(cnt == 10)
				VX = cnt = 0;	// reset velocity component
			else if((OutX >> 3) == 0)	// within noise, we are actually at rest frame
				cnt++;	// count how many points are like this
			*/
			//outb(PORTC, ~(((OutX>6) * 0xF0) | ((OutX<-6) * 0x0F )));
		return 1;
	}
	return 0;
}
void GetFromICPQueue(void)
{
//	enum {WaitInit=0, WaitDown, WaitUp};
//	static u08 XState=WaitInit, YState=WaitInit;
	static u16 XFirst=0, YFirst=0;
	static u08 bXY_old=0, bChg_old=0;
	u08 bXY, bChg;
	u16 CurTime;
	if(bufICPHead != bufICPTail) {	// there is data in the ICP queue
	// process it
		CurTime = *((u08*)BUF_ICP+(bufICPTail++));
		CurTime += *((u08*)BUF_ICP+(bufICPTail++)) << 8;
		bXY = *((u08*)BUF_ICP+bufICPTail);
		if(++bufICPTail == BUF_ICP_CHUNKS*BUF_ICP_SIZE)
			bufICPTail = 0;
		bChg = (bXY_old ^ bXY) & (A_X | A_Y);
		if(bChg) {	// changed mask
			if(bChg & A_X) {	// x changed
				switch(XState) {
				case WaitInit:
					if(bXY & A_X) {	// if x (changed to) high
						XState=WaitDown;
						XFirst = CurTime;
					}	// if x changed to low, ignore this datapoint
					break;
				case WaitDown:	// x changed to low
					bdtX.BUF_DIFF[bdtX.bufDiffHead].onTime = CurTime-XFirst;
					XFirst = CurTime;
					XState=WaitUp;	// now wait for up edge
					break;
				case WaitUp:	// x changed to up
					bdtX.BUF_DIFF[bdtX.bufDiffHead].offTime = CurTime-XFirst;
					XFirst = CurTime;
					XState=WaitDown;	// now wait for down edge
					if( ++(bdtX.bufDiffHead) == BUF_DIFF_CHUNKS )
						bdtX.bufDiffHead = 0;
					break;
				}
			}
			if(bChg & A_Y) {	// y changed
				switch(YState) {
				case WaitInit:
					if(bXY & A_Y) {	// if y (changed to) high
						YState=WaitDown;
						YFirst = CurTime;
					}	// if y changed to low, ignore this datapoint
					break;
				case WaitDown:	// y changed to low
					bdtY.BUF_DIFF[bdtY.bufDiffHead].onTime = CurTime-YFirst;
					YFirst = CurTime;
					YState=WaitUp;	// now wait for up edge
					break;
				case WaitUp:	// y changed to up
					bdtY.BUF_DIFF[bdtY.bufDiffHead].offTime = CurTime-YFirst;
					YFirst = CurTime;
					YState=WaitDown;	// now wait for down edge
					if( ++(bdtY.bufDiffHead) == BUF_DIFF_CHUNKS )
						bdtY.bufDiffHead = 0;
					break;
				}
			}
			//USARTSend('.');
		} else {	// nothing changed... missed an edge
			// recover that edge by looking at the last event:
			if(XState != WaitInit && YState != WaitInit) {
				if(bChg_old == A_X) {	// x last changed alone.. most recent is y change
					if(YState == WaitDown) {
						bdtY.BUF_DIFF[bdtY.bufDiffHead].onTime = XFirst-YFirst;
						bdtY.BUF_DIFF[bdtY.bufDiffHead].offTime = CurTime-XFirst;
						if( ++(bdtY.bufDiffHead) == BUF_DIFF_CHUNKS )
							bdtY.bufDiffHead = 0;
					} else {
						bdtY.BUF_DIFF[bdtY.bufDiffHead].offTime = XFirst-YFirst;
						if( ++(bdtY.bufDiffHead) == BUF_DIFF_CHUNKS )
							bdtY.bufDiffHead = 0;
						bdtY.BUF_DIFF[bdtY.bufDiffHead].onTime = CurTime-XFirst;
					}
					YFirst = CurTime;
				} else if(bChg_old == A_Y) {	// y last changed alone.. assume most recent is x change
					if(XState == WaitDown) {
						bdtX.BUF_DIFF[bdtX.bufDiffHead].onTime = YFirst-XFirst;
						bdtX.BUF_DIFF[bdtX.bufDiffHead].offTime = CurTime-YFirst;
						if( ++(bdtX.bufDiffHead) == BUF_DIFF_CHUNKS )
							bdtX.bufDiffHead = 0;
					} else {
						bdtX.BUF_DIFF[bdtX.bufDiffHead].offTime = YFirst-XFirst;
						if( ++(bdtX.bufDiffHead) == BUF_DIFF_CHUNKS )
							bdtX.bufDiffHead = 0;
						bdtX.BUF_DIFF[bdtX.bufDiffHead].onTime = CurTime-YFirst;
					}
					XFirst = CurTime;
				}
				//USARTSend('o');
			}
		}
		bXY_old = bXY;	// save current level state
		bChg_old = bChg;	// save changed state also
	}
}
s16 LPF(s16 In, s16* pLastIn, s16* pLastOut)
{	// length two IIR filter (first-order butterworth LPF: wc = 0.008pi ~ 2Hz)
	s16 ret = fmul(*pLastOut, 252) + fmul((In + *pLastIn), 2);
	*pLastIn = In;
	*pLastOut = ret;
	return ret;	// substract out low pass value.
}
s16 HPF(s16 In, s16* pLastIn, s16* pLastOut)
{	// high pass first-order Butterworth filter with cutoff around 2Hz.
	//return In;
	//s16 ret = fmul(*pLastOut, 250) + fmul((In - *pLastIn), 253);
	s16 ret = fmul(*pLastOut, 254) + In - *pLastIn;
	*pLastIn = In;
	*pLastOut = ret;
	return ret;
}
s16 fmul(s16 x, u08 y)
{	// gives the 16 bit signed integer equal to x * (y/256)
	u16 lsb, msb;
	s16 ret;
	if(x & 0x8000) {
		lsb = -x & 0x00FF;
		msb = (-x & 0xFF00) >> 8;
		ret = -(s16)((((lsb * y) >> 8) & 0x00FF) + (msb * y));
	} else {
		lsb = x & 0x00FF;
		msb = (x & 0xFF00) >> 8;
		ret = (((lsb * y) >> 8) & 0x00FF) + (msb * y);
	}
	return ret;
}
void MousePack(MOUSET* pm)
{
	u08 b = ((( pm->y & 0xC0 ) >> 4) & 0x0C);
	b |= ((( pm->x & 0xC0 ) >> 6) & 0x03);
	pm->b |= (b | (1 << 6));
	pm->x &= 0x3F;
	pm->y &= 0x3F;
}
void InitAll(void)
{
	MemInit();
	USARTInit(); 			// initialize the UART (serial port)
	ICPInit();
	WakeInit();
	outb(U_DDR, inb(U_DDR) | U_MASK);	// usart is output
	outb(L_DDR, inb(L_DDR) | L_MASK);	// led is output
	// mouse and accelerometers are inputs
	outb(M_DDR, ~(~inb(M_DDR) | M_MASK));
	outb(A_DDR, ~(~inb(A_DDR) | A_MASK));
	outb(L_PORT, inb(L_PORT) | L_MASK);	// turn on LED for debug
	outb(MCUCR, (1<<SE) | (1<<SM0) );	//idle mode (timers enabled)
	sei();	// enable all interrupts
	// oiii iioi
}
void MemInit(void)
{
	bufICPHead=0;
	bufICPTail=0;
}
void ICPInit(void)
{
	outb(TCCR1A, 0);
	outb(TCCR1B, (1<<ICES1 | 1<<CS10));	// rising edge for ICP, full speed
	outb(TIMSK, 1<<TICIE1);	// ICP interrupt enable
}
void WakeInit(void)
{
	outb(TCCR0, 5<<CS00);	// overflows at ~30.5 Hz.
}
void USARTInit(void)
{
	// set baud rate
	outb(UBRRL, (u08)BAUD_DIV);	// lower bits
	outb(UBRRH, (u08)(BAUD_DIV >> 8));	// upper bits
#ifdef __DEBUG_MODE__
	outb(UCSRA, 1 << U2X);	// double speed
	outb(UCSRB, (1<<RXEN)|(1<<TXEN));	// no transfer interrupt
	outb(UCSRC, (1<<URSEL)|(0<<USBS)|(3<<UCSZ0));	// 8N1
#else
	// disable double baud rate (less switching)
	outb(UCSRA, 0 << U2X);
	// set up transmit and receive
	outb(UCSRB, (1<<RXEN)|(1<<TXEN)|(1<<TXCIE));
	// frame format: 7N1
	outb(UCSRC, (1<<URSEL)|(0<<USBS)|(2<<UCSZ0));
#endif
}
void USARTSend(u08 txData)
{
	// wait for the transmitter to be ready
	//while(!bit_is_set(UCSRA, UDRE));		// loop until USR:UDRE is 1
	outb( UDR, txData );
}
/* efficient circular queue */
void EnQ(u08 Byte, u08* pQBuf, u08* pQHead, u08 Size)
{
	*(pQBuf+*pQHead) = Byte;
	*pQHead = (*pQHead+1>=Size) ? 0 : (*pQHead+1);
}
u08 DeQ(u08* pQBuf, u08* pQTail, u08 Size)
{
	u08 temp = *(pQBuf+*pQTail);
	*pQTail = (*pQTail+1>=Size) ? 0 : (*pQTail+1);
	return temp;
}
void EnQW(u16 Word, u16* pQBuf, u08* pQHead, u08 Elems)
{	// Elems is the number of 2-byte elements
	*(pQBuf+*pQHead) = Word;
	*pQHead = (*pQHead+1>=Elems) ? 0 : (*pQHead+1);
	/*if(pQBuf == (u16*)BUF_DIFFX)
		USARTSend('X');
	else
		USARTSend('Y');*/
	//USARTSend((u08)(Word>>8));
}


 

global.h

//*****************************************************************************

//

// File Name : 'global.h'

// Title : AVR project global include

// Author : Pascal Stang

// Created : 7/12/2001

// Revised : 9/30/2002

// Version : 1.1

// Target MCU : Atmel AVR series

// Editor Tabs : 4

//

// Description : This include file is designed to contain items useful to all

// code files and projects.

//

// This code is distributed under the GNU Public License

// which can be found at http://www.gnu.org/licenses/gpl.txt

//

//*****************************************************************************

#ifndef GLOBAL_H

#define GLOBAL_H

// global AVRLIB defines

#include "avrlibdefs.h"

// global AVRLIB types definitions

#include "avrlibtypes.h"

// project/system dependent defines

// temporary work-around for the Mega323

#define CTC1 CTC10

// CPU clock speed

//#define F_CPU 16000000 // 16MHz processor

//#define F_CPU 14745000 // 14.745MHz processor

//#define F_CPU 8000000 // 8MHz processor

//#define F_CPU 7372800 // 7.37MHz processor

//#define F_CPU 4000000 // 4MHz processor

//#define F_CPU 3686400 // 3.69MHz processor

#define F_CPU 8000000

// CYCLES_PER_US is used by some short delay loops

#define CYCLES_PER_US ((F_CPU+500000)/1000000) // cpu cycles per microsecond

#endif

 

And the makefile I used:

# Makefile for AVR function library development and examples

# Author: Pascal Stang

#

# For those who have never heard of makefiles: a makefile is essentially a

# script for compiling your code. Most C/C++ compilers in the world are

# command line programs and this is even true of programming environments

# which appear to be windows-based (like Microsoft Visual C++). Although

# you could use AVR-GCC directly from the command line and try to remember

# the compiler options each time, using a makefile keeps you free of this

# tedious task and automates the compile and link process.

#

# For those just starting with AVR-GCC and not used to using makefiles,

# I've added some extra comments above several of the makefile fields which

# you will have to deal with.

########### change this lines according to your project ##################

#put the name of the target mcu here (at90s8515, at90s8535, attiny22, atmega603 etc.)

# MCU = at90s8515

# MCU = atmega161

# MCU = atmega163

MCU = atmega323

# MCU = atmega128

#put the name of the target file here (without .c extension)

# Your "target" file is your C source file that is at the top level of your code.

# In other words, this is the file which contains your main() function.

TRG = transmitter

#put your C sourcefiles here

# Here you must list any C source files which are used by your target file.

# They will be compiled in the order you list them, so it's probably best

# to list $(TRG).c, your top-level target file, last.

# Enter the location of the AVRlib code here

AVR = c:/avrgcc

AVRLIB = z:/avrlib

SRC = $(TRG).c

#put additional assembler source file here

# The ASRC line allows you to list files which contain assembly code/routines that

# you would like to use from within your C programs. The assembly code must be

# written in a special way to be usable as a function from your C code.

ASRC =

#additional libraries and object files to link

# Libraries and object files are collections of functions which have already been

# compiled. If you have such files, list them here, and you will be able to use

# use the functions they contain in your target program.

LIB =

#additional includes to compile

INC =

#assembler flags

ASFLAGS = -Wa, -gstabs

#compiler flags

CPFLAGS = -g -O2 -Wall -Wstrict-prototypes -I$(AVRLIB) -Wa,-ahlms=$(<:.c=.lst)

#linker flags

LDFLAGS = -Wl,-Map=$(TRG).map,--cref

# Use the -lm flag if you need the floating-point math library

# LDFLAGS = -Wl,-Map=$(TRG).map,--cref -lm

########### you should not need to change the following line #############

include $(AVR)/avrfreaks/avr_make

#include $(AVR)/avrfreaks/avr_make_no_elfcoff

###### dependecies, add any dependencies you need here ###################

# Dependencies tell the compiler which files in your code depend on which

# other files. When you change a piece of code, the dependencies allow

# the compiler to intelligently figure out which files are affected and

# need to be recompiled. You should only list the dependencies of *.o

# files. For example: uart.o is the compiled output of uart.c and uart.h

# and therefore, uart.o "depends" on uart.c and uart.h. But the code in

# uart.c also uses information from global.h, so that file should be listed

# in the dependecies too. That way, if you alter global.h, uart.o will be

# recompiled to take into account the changes.

buffer.o : buffer.c buffer.h

uart.o : uart.c uart.h global.h

uart2.o : uart2.c uart2.h global.h

rprintf.o : rprintf.c rprintf.h

a2d.o : a2d.c a2d.h

timer.o : timer.c timer.h global.h

pulse.o : pulse.c pulse.h timer.h global.h

lcd.o : lcd.c lcd.h global.h

i2c.o : i2c.c i2c.h global.h

spi.o : spi.c spi.h global.h

swpwm.o : swpwm.c swpwm.h global.h

servo.o : servo.c servo.h global.h

uartsw.o : uartsw.c uartsw.h global.h

tsip.o : tsip.c tsip.h global.h

nmea.o : nmea.c nmea.h global.h

vt100.o : vt100.c vt100.h global.h

gps.o : gps.c gps.h global.h

$(TRG).o : $(TRG).c global.h

 


The receiver code is in AVR assembly.

echo.asm

;*****************************************************************

;

;YING-ZONG HUANG

;December, 2002

;Wireless Freeform Input Device

;Receiver Code

;

;*****************************************************************

.nolist

.include "m323def.inc"

.list

; define constants

.equ BEL =0x07

.equ BS =0x08

.equ CR =0x0D

.equ LF =0x0A

.equ SPACE =0x20

.equ ASC_M =0x4D

.equ ASC_2 =0x32

.equ BAUD_RATE =1200

.equ CPU_CLOCK =8000000

.equ UART_BAUD_DIV =(CPU_CLOCK/16/BAUD_RATE)-1

.equ TMR0_PRESCL =0x04 ; this is the prescaler setting for CK/256 = ~56 OVFL interrupts per second

.equ TMR0_INT_EN =1<<TOIE0 ; set the timer 0 ovfl intr enable bit

.equ TMR0_INT_DS =~TMR0_INT_EN

.equ TMR1_PRESCL =0x01 ; no scale

.equ TMR1_PWM_EN =0x83 ; 10 bits, non-inverted up down PWM EN

.equ TMR1_PWM_DS =0x80 ; PWM disable...

.equ TMR1_HALFH =0x01 ; 0x01FF

.equ TMR1_HALFL =0xFF

.equ BUFSIZE =100

.equ QSIZE =BUFSIZE+1

; define register aliases

.def pr =r0

.def zero =r1

.def all =r2

.def a1 =r3 ; function argument 1

.def v0 =r4 ; function return 0

.def v1 =r5 ; function return 1

.def t0 =r16 ; temporary register 0h

.def t1 =r17 ; temporary register 1

.def t2 =r18

.def t3 =r19

.def s0 =r20

.def s1 =r21

.def s2 =r22

.def s3 =r23

.def a0 =r26 ; function argument 0

.def qHead =r24 ; index of beginning of queue buffer

.def qTail =r25 ; index of end of queue buffer

.def z =r30

; data segment

.dseg

qbuf: .byte QSIZE ; define an array of bytes qbuf[QSIZE]

 

; code segment interrupt table must use the 2-byte 'jmp'

.cseg

.org $000

jmp reset ; $000 HW reset or watchdog

jmp reset ; External Interrupt0 Vector Address

jmp reset ; External Interrupt1 Vector Address

jmp reset ; External Interrupt2 Vector Address

jmp reset ; Output Compare2 Interrupt Vector Address

jmp reset ; Overflow2 Interrupt Vector Address

jmp reset ; Input Capture1 Interrupt Vector Address

jmp reset ; Output Compare1A Interrupt Vector Address

jmp reset ; Output Compare1B Interrupt Vector Address

jmp reset ; Overflow1 Interrupt Vector Address

jmp reset ; Output Compare0 Interrupt Vector Address

jmp reset ; Overflow0 Interrupt Vector Address

jmp reset ; SPI Interrupt Vector Address

jmp RxC_Isr ; USART Receive Complete Interrupt Vector Address

jmp reset ; USART Data Register Empty Interrupt Vector Address

jmp reset ; USART Transmit Complete Interrupt Vector Address

jmp reset ; ADC Interrupt Vector Address

jmp reset ; EEPROM Interrupt Vector Address

jmp reset ; Analog Comparator Interrupt Vector Address

jmp reset ; Irq. vector address for Two-Wire Interface

jmp reset ; Store Program Memory Ready Interrupt Vector Address

; begin main code

reset:

ldi t0, low(RAMEND) ; initialize stack pointer to highest (valid) mem location

out SPL, t0

ldi t0, high(RAMEND)

out SPH, t0

clr zero ; set zero register to actually zero

clr all

com all

rcall clrqueue ; initialize queue

ldi t0, $7F ; port D all outputs, except D0 is input (RXD)

out DDRD, t0

; Set baud rate

ldi t0, low(UART_BAUD_DIV)

out UBRRL, t0

ldi t0, high(UART_BAUD_DIV) ;send at 1200 baud

out UBRRH, t0

ldi t0, (0<<U2X) ; non double speed mode

out UCSRA, t0

; Enable Receiver and Transmitter, receive interrupt

ldi t0, (1<<RXEN)|(1<<TXEN)|(1<<RXCIE)

out UCSRB,t0

; Set frame format: 7data, 1stop bit

ldi t0, (1<<URSEL)|(0<<USBS)|(2<<UCSZ0)

out UCSRC,t0

sei ; enable interrupts

loopchar:

rcall getchar ; get next character from queue

mov a0, v0

rcall putchar

rjmp loopchar

 

; begin subroutines and functions

; function getchar

; get character from receive serial queue

; if none available, wait until one arrives

getchar:

rcall dequeue

brcc getchar ; try again if queue empty

ret

; function putchar

; output character in a0 to serial port, non-interrupt driven

putchar:

sbis UCSRA, UDRE ; loop until USR:UDRE is 1

rjmp putchar

out UDR, a0 ; write a0 to transmitter buffer

ret

; Interrupt Handler RxC_Isr

; UART receive character interrupt service routine

RxC_Isr:

push t0 ; save registers

in t0, SREG

push t0

push a0

in a0, UDR ; read UART receive data

rcall enqueue ; place data in the queue

pop a0 ; restore registers

pop t0

out SREG, t0

pop t0

reti ; return from interrupt

 

; function clrqueue

; initialize the queue buffer to empty (beginning=end=0)

clrqueue:

clr qHead ; make pointers equal

clr qTail

ret

; function enqueue

; add byte in a0 to end of queue buffer

enqueue:

push yh ; save registers

push yl

push t0 ; save this if it is possible to get interrupt in an ISR???

ldi yl, low(qbuf) ; y = base of queue

ldi yh, high(qbuf)

add yl, qHead ; add offset of head

adc yh, zero ; to get to end of queue

st y, a0 ; store data in queue

mov t0, qHead

inc t0

cpi t0, QSIZE

brlo enq1

clr t0

enq1:

cp t0, qTail ; compare head to tail

breq enq2 ; if head equals tail, we ain't incrementing the head pointer

mov qHead, t0 ; queue has room, back-copy incremented pointer

enq2:

pop t0

pop yl

pop yh

ret ; return

; function enqueue

; remove byte from beginning of queue and return in v0

; if data was available, carry is set

; if no data was available, carry is clear

dequeue:

cp qHead, qTail ; check for empty queue

brne deq1 ; queue not empty, actually dequeue at deq1...

clc ; clear carry flag when empty

ret

deq1:

push yh ; save queue base pointers

push yl

ldi yl, low(qbuf) ; y = base of queue

ldi yh, high(qbuf)

add yl, qTail ; add offset to get to tail

adc yh, zero ; the tail of the queue

ld v0, y ; fetch current tail element in queue

inc qTail ; update tail pointer

cpi qTail, QSIZE

brlo deq2

clr qTail ; wraparound to 0 when needed

deq2:

pop yl ; restore registers

pop yh

sec ; set carry to indicate data

ret