aboutsummaryrefslogtreecommitdiff
path: root/ATmega48
diff options
context:
space:
mode:
Diffstat (limited to 'ATmega48')
-rw-r--r--ATmega48/MEGA48/Include/atmega48.c31
-rw-r--r--ATmega48/MEGA48/Include/atmega48.h66
-rw-r--r--ATmega48/MEGA48/Include/inavr.h213
-rw-r--r--ATmega48/MEGA48/Include/iom48.h741
-rw-r--r--ATmega48/MEGA48/Include/iomacro.h380
-rw-r--r--ATmega48/MEGA48/Lib/cl1s-ec.r90bin0 -> 896097 bytes
-rw-r--r--ATmega48/Source/c_armcomm.c601
-rw-r--r--ATmega48/Source/c_armcomm.h44
-rw-r--r--ATmega48/Source/d_armcomm.c48
-rw-r--r--ATmega48/Source/d_armcomm.h28
-rw-r--r--ATmega48/Source/d_armcomm.r253
-rw-r--r--ATmega48/Source/d_button.c40
-rw-r--r--ATmega48/Source/d_button.h27
-rw-r--r--ATmega48/Source/d_button.r68
-rw-r--r--ATmega48/Source/d_input.c52
-rw-r--r--ATmega48/Source/d_input.h29
-rw-r--r--ATmega48/Source/d_input.r209
-rw-r--r--ATmega48/Source/d_output.c86
-rw-r--r--ATmega48/Source/d_output.h27
-rw-r--r--ATmega48/Source/d_output.r425
-rw-r--r--ATmega48/Source/d_pccomm.c33
-rw-r--r--ATmega48/Source/d_pccomm.h26
-rw-r--r--ATmega48/Source/d_pccomm.r93
-rw-r--r--ATmega48/Source/d_power.c122
-rw-r--r--ATmega48/Source/d_power.h35
-rw-r--r--ATmega48/Source/d_power.r79
-rw-r--r--ATmega48/Source/d_timer.c48
-rw-r--r--ATmega48/Source/d_timer.h30
-rw-r--r--ATmega48/Source/d_timer.r34
-rw-r--r--ATmega48/Source/m_sched.c54
-rw-r--r--ATmega48/Source/m_sched.h87
-rw-r--r--ATmega48/Source/stdconst.h44
32 files changed, 4053 insertions, 0 deletions
diff --git a/ATmega48/MEGA48/Include/atmega48.c b/ATmega48/MEGA48/Include/atmega48.c
new file mode 100644
index 0000000..9583438
--- /dev/null
+++ b/ATmega48/MEGA48/Include/atmega48.c
@@ -0,0 +1,31 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 17-02-05 11:26 $
+//
+// Filename $Workfile:: atmega48.c $
+//
+// Version $Revision:: 2 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Mega48/Include/ $
+//
+// Platform C
+//
+
+
+void main(void)
+{
+ HARDWAREInit;
+ mSchedInit();
+ while(TRUE == mSchedCtrl())
+ {
+ OSWatchdogWrite;
+ }
+ mSchedExit();
+ HARDWAREExit;
+}
+
diff --git a/ATmega48/MEGA48/Include/atmega48.h b/ATmega48/MEGA48/Include/atmega48.h
new file mode 100644
index 0000000..d6b75b4
--- /dev/null
+++ b/ATmega48/MEGA48/Include/atmega48.h
@@ -0,0 +1,66 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: atmega48.h $
+//
+// Version $Revision:: 7 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Mega48/Include/ $
+//
+// Platform C
+//
+
+
+#ifndef ATMEGA88_H
+#define ATMEGA88_H
+
+#include "iom48.h"
+#include "inavr.h"
+
+
+#define ATMEGAX8
+
+
+#define HARDWAREReset {\
+ void (*Reset)(void);\
+ Reset = (void*)0x0000;\
+ Reset();\
+ }
+
+#define HARDWAREInit {\
+ SMCR = 0x00;\
+ CLKPR = 0x80;\
+ CLKPR = 0x00;\
+ __enable_interrupt();\
+ }
+
+
+#define HARDWAREExit {\
+ ADCSRA = 0x00;\
+ SMCR = 0x05;\
+ __sleep();\
+ HARDWAREReset;\
+ }
+
+#define OSIntEnable() {\
+ __enable_interrupt();\
+ }
+
+#define OSIntDisable() {\
+ __disable_interrupt();\
+ }
+
+#define OSWatchdogWrite
+
+void mSchedInit(void);
+UBYTE mSchedCtrl(void);
+void mSchedExit(void);
+
+
+#endif
diff --git a/ATmega48/MEGA48/Include/inavr.h b/ATmega48/MEGA48/Include/inavr.h
new file mode 100644
index 0000000..bf1ecfc
--- /dev/null
+++ b/ATmega48/MEGA48/Include/inavr.h
@@ -0,0 +1,213 @@
+/**************************************************************
+ ** - INAVR.H -
+ **
+ ** Intrinsics for iccAVR
+ **
+ ** Used with iccAVR.
+ **
+ ** Copyright IAR Systems 1999. All rights reserved.
+ **
+ ** File version: $Revision: 1 $
+ **
+ **************************************************************/
+
+#ifndef __INAVR_H
+#define __INAVR_H
+
+#ifndef __ICCAVR__
+#error This file should only be compiled with iccAVR
+#endif /* __ICCAVR__ */
+
+__intrinsic void __no_operation(void);
+__intrinsic void __enable_interrupt(void);
+__intrinsic void __disable_interrupt(void);
+__intrinsic void __sleep(void);
+__intrinsic void __watchdog_reset(void);
+#define __clear_watchdog_timer() __watchdog_reset()
+#pragma language=extended
+__intrinsic unsigned char __load_program_memory(const unsigned char __flash *);
+#ifdef __HAS_ELPM__
+__intrinsic unsigned char __extended_load_program_memory(
+ const unsigned char __farflash *);
+#endif
+#pragma language=default
+
+__intrinsic void __insert_opcode(unsigned short op);
+
+#if __MEMORY_MODEL__ == 4
+#if __CPU__ < 2
+#define __STR_MATTR__ __flash
+#else
+#define __STR_MATTR__ __hugeflash
+#endif
+#else
+#define __STR_MATTR__
+#endif
+
+
+__intrinsic void __require(void *);
+
+__intrinsic void __delay_cycles(unsigned long);
+
+__intrinsic unsigned char __save_interrupt(void);
+#define __get_interrupt_state() __save_interrupt()
+
+__intrinsic void __restore_interrupt(unsigned char);
+#define __set_interrupt_state(STATE) __restore_interrupt(STATE)
+
+__intrinsic unsigned char __swap_nibbles(unsigned char);
+
+__intrinsic void __indirect_jump_to(unsigned long);
+
+#ifdef __HAS_ENHANCED_CORE__
+
+#ifdef __HAS_MUL__
+__intrinsic unsigned int __multiply_unsigned(unsigned char, unsigned char);
+__intrinsic signed int __multiply_signed(signed char, signed char);
+__intrinsic signed int __multiply_signed_with_unsigned(signed char, unsigned char);
+
+__intrinsic unsigned int __fractional_multiply_unsigned(unsigned char, unsigned char);
+__intrinsic signed int __fractional_multiply_signed(signed char, signed char);
+__intrinsic signed int __fractional_multiply_signed_with_unsigned(signed char, signed char);
+#endif
+
+#pragma language=extended
+
+/* SPM */
+__intrinsic void __DataToR0ByteToSPMCR_SPM(unsigned char data,
+ unsigned char byte);
+__intrinsic void __AddrToZByteToSPMCR_SPM(void __flash* addr,
+ unsigned char byte);
+__intrinsic void __AddrToZWordToR1R0ByteToSPMCR_SPM(void __flash* addr,
+ unsigned short word,
+ unsigned char byte);
+
+#define _SPM_LOCKBITS(Data) \
+ __DataToR0ByteToSPMCR_SPM((Data), 0x09)
+
+#define _SPM_ERASE(Addr) \
+ __AddrToZByteToSPMCR_SPM((void __flash*)(Addr), 0x03)
+
+#define _SPM_FILLTEMP(Addr,Data) \
+ __AddrToZWordToR1R0ByteToSPMCR_SPM((void __flash*)(Addr), (Data), 0x01)
+
+#define _SPM_PAGEWRITE(Addr) \
+ __AddrToZByteToSPMCR_SPM((void __flash*)(Addr), (0x05))
+
+
+__intrinsic unsigned char __AddrToZByteToSPMCR_LPM(void __flash* addr,
+ unsigned char byte);
+
+#define _SPM_GET_LOCKBITS() \
+ __AddrToZByteToSPMCR_LPM((void __flash*)0x0001, 0x09)
+
+#define _SPM_GET_FUSEBITS() \
+ __AddrToZByteToSPMCR_LPM((void __flash*)0x0000, 0x09)
+
+
+#ifdef __HAS_ELPM__
+__intrinsic void __AddrToZ24ByteToSPMCR_SPM(void __farflash* addr,
+ unsigned char byte);
+__intrinsic void __AddrToZ24WordToR1R0ByteToSPMCR_SPM(void __farflash* addr,
+ unsigned short word,
+ unsigned char byte);
+#define _SPM_24_ERASE(Addr) \
+ __AddrToZ24ByteToSPMCR_SPM((void __farflash*)(Addr), 0x03)
+
+#define _SPM_24_FILLTEMP(Addr,Data) \
+ __AddrToZ24WordToR1R0ByteToSPMCR_SPM((void __farflash*)(Addr), (Data), 0x01)
+
+#define _SPM_24_PAGEWRITE(Addr) \
+ __AddrToZ24ByteToSPMCR_SPM((void __farflash*)(Addr), (0x05))
+
+__intrinsic unsigned char __AddrToZ24ByteToSPMCR_ELPM(void __farflash* addr,
+ unsigned char byte);
+#endif
+#pragma language=default
+
+#endif //__HAS_ENHANCED_CORE__
+
+/* Include a file appropriate for the processor used,
+ * that defines EECR, EEAR and EEDR (e.g. io2312.h). */
+#ifdef __HAS_EEPROM__
+#define __EEPUT(ADR,VAL) (*((unsigned char __eeprom *)ADR) = VAL)
+#define __EEGET(VAR, ADR) (VAR = *((unsigned char __eeprom *)ADR))
+#else /* !__HAS_EEPROM__ */
+#define __EEPUT(ADR,VAL) {while (EECR & 0x02); \
+ EEAR = (ADR); EEDR = (VAL); EECR = 0x04; EECR = 0x02;}
+
+#define __EEGET(VAR, ADR) {while (EECR & 0x02); \
+ EEAR = (ADR); EECR = 0x01; (VAR) = EEDR;}
+#endif /* __HAS_EEPROM__ */
+
+/* PORT is a sfrb defined variable */
+#define input(PORT) (PORT)
+#define output(PORT,VAL) ((PORT)=(VAL))
+
+#define input_block_dec(PORT,ADDRESS,COUNT)\
+{ \
+ unsigned char i;\
+ unsigned char *addr=(ADDRESS);\
+ for(i=0;i<(COUNT);i++)\
+ *addr--=(PORT);\
+}
+
+#define input_block_inc(PORT,ADDRESS,COUNT)\
+{ \
+ unsigned char i;\
+ unsigned char *addr=(ADDRESS);\
+ for(i=0;i<(COUNT);i++)\
+ *addr++=(PORT);\
+}
+
+#define output_block_dec(PORT,ADDRESS,COUNT)\
+{ \
+ unsigned char i;\
+ unsigned char *addr=(ADDRESS);\
+ for(i=0;i<(COUNT);i++)\
+ (PORT)=*addr--;\
+}
+
+#define output_block_inc(PORT,ADDRESS,COUNT)\
+{ \
+ unsigned char i;\
+ unsigned char *addr=(ADDRESS);\
+ for(i=0;i<(COUNT);i++)\
+ (PORT)=*addr++;\
+}
+
+
+//Nice to have macros
+
+#define __out_word(BaseName, value)\
+{\
+ unsigned char _tH=(value) >> 8;\
+ unsigned char _tL=(value) & 0xFF;\
+ BaseName ## H = _tH;\
+ BaseName ## L = _tL;\
+}
+
+
+#define __out_word_atomic(BaseName, value)\
+{\
+ unsigned char _t=__save_interrupt();\
+ __disable_interrupt();\
+ __out_word(BaseName,value);\
+ __restore_interrupt(_t);\
+}
+
+#define __in_word(BaseName, value)\
+{\
+ (value) = (BaseName ## L);\
+ (value) |= (unsigned short)BaseName ## H << 8;\
+}
+
+
+#define __in_word_atomic(BaseName, value)\
+{\
+ unsigned char _t=__save_interrupt();\
+ __disable_interrupt();\
+ __in_word(BaseName, value);\
+ __restore_interrupt(_t);\
+}
+#endif /* __INAVR_H */
diff --git a/ATmega48/MEGA48/Include/iom48.h b/ATmega48/MEGA48/Include/iom48.h
new file mode 100644
index 0000000..ab268c1
--- /dev/null
+++ b/ATmega48/MEGA48/Include/iom48.h
@@ -0,0 +1,741 @@
+/****************************************************************************
+ ** - iom48.h -
+ **
+ ** This file declares the internal register addresses for ATmega48.
+ **
+ ** Used with iccAVR and aAVR.
+ **
+ ** Copyright IAR Systems 2003. All rights reserved.
+ **
+ ** File version: $Revision: 1 $
+ **
+ ***************************************************************************/
+
+#include "iomacro.h"
+
+#if TID_GUARD(1)
+#error This file should only be compiled with iccavr or aavr whith processor option -v1
+#endif /* TID_GUARD(1) */
+
+/* Include the SFR part if this file has not been included before,
+ * OR this file is included by the assembler (SFRs must be defined in
+ * each assembler module). */
+#if !defined(__IOM48_H) || defined(__IAR_SYSTEMS_ASM__)
+
+#pragma language=extended
+
+/*==========================*/
+/* Predefined SFR Addresses */
+/*==========================*/
+
+/****************************************************************************
+ * An example showing the SFR_B() macro call,
+ * the expanded result and usage of this result:
+ *
+ * SFR_B(AVR, 0x1F) Expands to:
+ * __io union {
+ * unsigned char AVR; // The sfrb as 1 byte
+ * struct { // The sfrb as 8 bits
+ * unsigned char AVR_Bit0:1,
+ * AVR_Bit1:1,
+ * AVR_Bit2:1,
+ * AVR_Bit3:1,
+ * AVR_Bit4:1,
+ * AVR_Bit5:1,
+ * AVR_Bit6:1,
+ * AVR_Bit7:1;
+ * };
+ * } @ 0x1F;
+ * Examples of how to use the expanded result:
+ * AVR |= (1<<5);
+ * or like this:
+ * AVR_Bit5 = 1;
+ ***************************************************************************/
+
+
+/* Extended I/O space */
+SFR_B(UDR0, 0xC6) /* USART0 I/O Data Register */
+SFR_W(UBRR0, 0xC4) /* USART0 Baud Rate Register */
+
+SFR_B(UCSR0C, 0xC2) /* USART0 Control and Status Register C */
+SFR_B(UCSR0B, 0xC1) /* USART0 Control and Status Register B */
+SFR_B(UCSR0A, 0xC0) /* USART0 Control and Status Register A */
+
+SFR_B(TWAMR, 0xBD) /* 2-wire Serial Interface */
+SFR_B(TWCR, 0xBC) /* 2-wire Serial Interface Control Register */
+SFR_B(TWDR, 0xBB) /* 2-wire Serial Interface Data Register */
+SFR_B(TWAR, 0xBA) /* 2-wire Serial Interface Address Register */
+SFR_B(TWSR, 0xB9) /* 2-wire Serial Interface Status Register */
+SFR_B(TWBR, 0xB8) /* 2-wire Serial Interface Bit Rate Register */
+
+SFR_B(ASSR, 0xB6) /* Asynchronous mode Status Register */
+
+SFR_B(OCR2B, 0xB4) /* Timer/Counter 2 Output Compare Register B */
+SFR_B(OCR2A, 0xB3) /* Timer/Counter 2 Output Compare Register A */
+SFR_B(TCNT2, 0xB2) /* Timer/Counter 2 */
+SFR_B(TCCR2B, 0xB1) /* Timer/Counter 2 Control Register B */
+SFR_B(TCCR2A, 0xB0) /* Timer/Counter 2 Control Register A */
+
+SFR_W(OCR1B, 0x8A) /* Timer/Counter 1 - Output Compare Register B */
+SFR_W(OCR1A, 0x88) /* Timer/Counter 1 - Output Compare Register A */
+SFR_W(ICR1, 0x86) /* Timer/Counter 1 - Input Capture Register */
+SFR_W(TCNT1, 0x84) /* Timer/Counter 1 - Counter Register */
+
+SFR_B(TCCR1C, 0x82) /* Timer/Counter 1 Control Register C */
+SFR_B(TCCR1B, 0x81) /* Timer/Counter 1 Control Register B */
+SFR_B(TCCR1A, 0x80) /* Timer/Counter 1 Control Register A */
+SFR_B(DIDR1, 0x7F) /* Digital Input Disable Register 1 */
+SFR_B(DIDR0, 0x7E) /* Digital Input Disable Register 0 */
+
+SFR_B(ADMUX, 0x7C) /* ADC Multiplexer Selection Register */
+SFR_B(ADCSRB, 0x7B) /* ADC Control and Status Register B */
+SFR_B(ADCSRA, 0x7A) /* ADC Control and Status Register A */
+SFR_W(ADC, 0x78) /* ADC Data Register */
+
+SFR_B(TIMSK2, 0x70) /* Timer/Counter 2 Interrupt Mask Register */
+SFR_B(TIMSK1, 0x6F) /* Timer/Counter 1 Interrupt Mask Register */
+SFR_B(TIMSK0, 0x6E) /* Timer/Counter 0 Interrupt Mask Register */
+SFR_B(PCMSK2, 0x6D) /* Pin Change Mask Register 2 */
+SFR_B(PCMSK1, 0x6C) /* Pin Change Mask Register 1 */
+SFR_B(PCMSK0, 0x6B) /* Pin Change Mask Register 0 */
+
+SFR_B(EICRA, 0x69) /* External Interrupt Control Register A */
+SFR_B(PCICR, 0x68) /* Pin Change Interrupt Control Register */
+
+SFR_B(OSCCAL, 0x66) /* Oscillator Calibration Register */
+
+SFR_B(PRR, 0x64) /* */
+
+SFR_B(CLKPR, 0x61) /* System Clock Prescaler */
+SFR_B(WDTCSR, 0x60) /* Watchdog Timer Control and Status Register */
+
+/* Ordinary I/O space */
+SFR_B(SREG, 0x3F) /* Status Register */
+SFR_W(SP, 0x3D) /* Stack Pointer */
+
+SFR_B(SPMCSR, 0x37) /* Store Program Memory Control Register */
+
+SFR_B(MCUCR, 0x35) /* MCU Control Register */
+SFR_B(MCUSR, 0x34) /* MCU Status Register */
+SFR_B(SMCR, 0x33) /* Sleep Mode Control Register */
+
+SFR_B(MONDR, 0x31) /* Monitor Data Register */
+SFR_B(ACSR, 0x30) /* Analog Comparator Control and Status Register */
+
+SFR_B(SPDR, 0x2E) /* SPI Data Register */
+SFR_B(SPSR, 0x2D) /* SPI Status Register */
+SFR_B(SPCR, 0x2C) /* SPI Control Register */
+SFR_B(GPIOR2, 0x2B) /* General Purpose I/O Register 2 */
+SFR_B(GPIOR1, 0x2A) /* General Purpose I/O Register 1 */
+
+SFR_B(OCR0B, 0x28) /* Timer/Counter 0 Output Compare Register B */
+SFR_B(OCR0A, 0x27) /* Timer/Counter 0 Output Compare Register A */
+SFR_B(TCNT0, 0x26) /* Timer/Counter 0 (8-bit) */
+SFR_B(TCCR0B, 0x25) /* Timer/Counter 0 Control Register B */
+SFR_B(TCCR0A, 0x24) /* Timer/Counter 0 Control Register A */
+SFR_B(GTCCR, 0x23) /* General Timer/Counter Control Register */
+SFR_B(EEAR, 0x21) /* EEPROM Address Register */
+SFR_B(EEDR, 0x20) /* EEPROM Data Register */
+SFR_B(EECR, 0x1F) /* EEPROM Control Register */
+SFR_B(GPIOR0, 0x1E) /* General Purpose I/O Register 0 */
+SFR_B(EIMSK, 0x1D) /* External Interrupt Mask Register */
+SFR_B(EIFR, 0x1C) /* External Interrupt Flag Register */
+SFR_B(PCIFR, 0x1B) /* Pin Change Interrupt Flag Register */
+
+SFR_B(TIFR2, 0x17) /* Timer/Counter 2 Interrupt Flag Register */
+SFR_B(TIFR1, 0x16) /* Timer/Counter 1 Interrupt Flag Register */
+SFR_B(TIFR0, 0x15) /* Timer/Counter 0 Interrupt Flag Register */
+
+SFR_B(PORTD, 0x0B) /* Data Register, Port D */
+SFR_B(DDRD, 0x0A) /* Data Direction Register, Port D */
+SFR_B(PIND, 0x09) /* Input Pins, Port D */
+SFR_B(PORTC, 0x08) /* Data Register, Port C */
+SFR_B(DDRC, 0x07) /* Data Direction Register, Port C */
+SFR_B(PINC, 0x06) /* Input Pins, Port C */
+SFR_B(PORTB, 0x05) /* Data Register, Port B */
+SFR_B(DDRB, 0x04) /* Data Direction Register, Port B */
+SFR_B(PINB, 0x03) /* Input Pins, Port B */
+
+
+#ifndef __IOM48_H
+#define __IOM48_H
+
+
+/* SFRs are local in assembler modules (so this file may need to be */
+/* included in more than one module in the same source file), */
+/* but #defines must only be made once per source file. */
+
+/*==============================*/
+/* Interrupt Vector Definitions */
+/*==============================*/
+
+/* NB! vectors are specified as byte addresses */
+
+#define RESET_vect (0x00) /* External Pin, Power-on Reset, Brownout
+ Reset and Watchdog Reset */
+#define INT0_vect (0x02) /* External Interrupt Request 0 */
+#define INT1_vect (0x04) /* External Interrupt Request 1 */
+#define PCINT0_vect (0x06) /* Pin Change Interrupt Request 0 */
+#define PCINT1_vect (0x08) /* Pin Change Interrupt Request 1 */
+#define PCINT2_vect (0x0A) /* Pin Change Interrupt Request 2 */
+#define WDT_vect (0x0C) /* Watchdog Time-out Interrupt */
+#define TIMER2_COMPA_vect (0x0E) /* Timer/Counter2 Compare Match A */
+#define TIMER2_COMPB_vect (0x10) /* Timer/Counter2 Compare Match B */
+#define TIMER2_OVF_vect (0x12) /* Timer/Counter2 Overflow */
+#define TIMER1_CAPT_vect (0x14) /* Timer/Counter1 Capture Event */
+#define TIMER1_COMPA_vect (0x16) /* Timer/Counter1 Compare Match A */
+#define TIMER1_COMPB_vect (0x18) /* Timer/Coutner1 Compare Match B */
+#define TIMER1_OVF_vect (0x1A) /* Timer/Counter1 Overflow */
+#define TIMER0_COMPA_vect (0x1C) /* Timer/Counter0 Compare Match A */
+#define TIMER0_COMPB_vect (0x1E) /* Timer/Counter0 Compare Match B */
+#define TIMER0_OVF_vect (0x20) /* Timer/Counter0 Overflow */
+#define SPI_STC_vect (0x22) /* SPI Serial Transfer Complete */
+#define USART_RX_vect (0x24) /* USART Rx Complete */
+#define USART_UDRE_vect (0x26) /* USART, Data Register Empty */
+#define USART_TX_vect (0x28) /* USART, Tx Complete */
+#define ADC_vect (0x2A) /* ADC Conversion Complete */
+#define EE_RDY_vect (0x2C) /* EEPROM Ready */
+#define ANA_COMP_vect (0x2E) /* Analog Comparator */
+#define TWI_vect (0x30) /* 2-wire Serial Interface */
+#define SPM_READY_vect (0x32) /* Store Program Memory Ready */
+
+#ifdef __IAR_SYSTEMS_ASM__
+#ifndef ENABLE_BIT_DEFINITIONS
+#define ENABLE_BIT_DEFINITIONS
+#endif /* ENABLE_BIT_DEFINITIONS */
+#endif /* __IAR_SYSTEMS_ASM__ */
+
+#ifdef ENABLE_BIT_DEFINITIONS
+
+
+/* Bit definitions for use with the IAR Assembler
+ The Register Bit names are represented by their bit number (0-7).
+*/
+
+/*UCSR0C*/
+#define UMSEL01 7
+#define UMSEL00 6
+#define UPM01 5
+#define UPM00 4
+#define USBS0 3
+#define UDORD0 2
+#define UCPHA0 1
+#define UCPOL0 0
+
+#define UCSZ01 UDORD0
+#define UCSZ00 UCPHA0
+
+/*UCSR0B*/
+#define RXCIE0 7
+#define TXCIE0 6
+#define UDRIE0 5
+#define RXEN0 4
+#define TXEN0 3
+#define UCSZ02 2
+#define RXB80 1
+#define TXB80 0
+
+/*UCSR0A*/
+#define RXC0 7
+#define TXC0 6
+#define UDRE0 5
+#define FE0 4
+#define DOR0 3
+#define UPE0 2
+#define U2X0 1
+#define MPCM0 0
+
+
+/*TWAMR*/
+#define TWAM6 7
+#define TWAM5 6
+#define TWAM4 5
+#define TWAM3 4
+#define TWAM2 3
+#define TWAM1 2
+#define TWAM0 1
+
+/*TWCR*/
+#define TWINT 7
+#define TWEA 6
+#define TWSTA 5
+#define TWSTO 4
+#define TWWC 3
+#define TWEN 2
+#define TWIE 0
+
+/*TWAR*/
+#define TWA6 7
+#define TWA5 6
+#define TWA4 5
+#define TWA3 4
+#define TWA2 3
+#define TWA1 2
+#define TWA0 1
+#define TWGCE 0
+
+/*TWSR*/
+#define TWS7 7
+#define TWS6 6
+#define TWS5 5
+#define TWS4 4
+#define TWS3 3
+#define TWPS1 1
+#define TWPS0 0
+
+
+/*ASSR*/
+#define EXCLK 6
+#define AS2 5
+#define TCN2UB 4
+#define OCR2AUB 3
+#define OCR2BUB 2
+#define TCR2AUB 1
+#define TCR2BUB 0
+
+
+/*TCCR2B*/
+#define FOC2A 7
+#define FOC2B 6
+#define WGM22 3
+#define CS22 2
+#define CS21 1
+#define CS20 0
+
+/*TCCR2A*/
+#define COM2A1 7
+#define COM2A0 6
+#define COM2B1 5
+#define COM2B0 4
+#define WGM21 1
+#define WGM20 0
+
+
+/*TCCR1C*/
+#define FOC1A 7
+#define FOC1B 6
+
+/*TCCR1B*/
+#define ICNC1 7
+#define ICES1 6
+#define WGM13 4
+#define WGM12 3
+#define CS12 2
+#define CS11 1
+#define CS10 0
+
+/*TCCR1A*/
+#define COM1A1 7
+#define COM1A0 6
+#define COM1B1 5
+#define COM1B0 4
+#define WGM11 1
+#define WGM10 0
+
+/*DIDR1*/
+#define AIN1D 1
+#define AIN0D 0
+
+/*DIDR0*/
+#define ADC5D 5
+#define ADC4D 4
+#define ADC3D 3
+#define ADC2D 2
+#define ADC1D 1
+#define ADC0D 0
+
+
+/*ADMUX*/
+#define REFS1 7
+#define REFS0 6
+#define ADLAR 5
+#define MUX3 3
+#define MUX2 2
+#define MUX1 1
+#define MUX0 0
+
+/*ADCSRB*/
+#define ACME 6
+#define ADTS2 2
+#define ADTS1 1
+#define ADTS0 0
+
+/*ADCSRA*/
+#define ADEN 7
+#define ADSC 6
+#define ADATE 5
+#define ADIF 4
+#define ADIE 3
+#define ADPS2 2
+#define ADPS1 1
+#define ADPS0 0
+
+
+/*TIMSK2*/
+#define OCIE2B 2
+#define OCIE2A 1
+#define TOIE2 0
+
+/*TIMSK1*/
+#define ICIE1 5
+#define OCIE1B 2
+#define OCIE1A 1
+#define TOIE1 0
+
+/*TIMSK0*/
+#define OCIE0B 2
+#define OCIE0A 1
+#define TOIE0 0
+
+/*PCMSK2*/
+#define PCINT23 7
+#define PCINT22 6
+#define PCINT21 5
+#define PCINT20 4
+#define PCINT19 3
+#define PCINT18 2
+#define PCINT17 1
+#define PCINT16 0
+
+/*PCMSK1*/
+#define PCINT14 6
+#define PCINT13 5
+#define PCINT12 4
+#define PCINT11 3
+#define PCINT10 2
+#define PCINT9 1
+#define PCINT8 0
+
+/*PCMSK0*/
+#define PCINT7 7
+#define PCINT6 6
+#define PCINT5 5
+#define PCINT4 4
+#define PCINT3 3
+#define PCINT2 2
+#define PCINT1 1
+#define PCINT0 0
+
+
+/*EICRA*/
+#define ISC11 3
+#define ISC10 2
+#define ISC01 1
+#define ISC00 0
+
+/*PCICR*/
+#define PCIE2 2
+#define PCIE1 1
+#define PCIE0 0
+
+
+/*PRR*/
+#define PRTW1 7
+#define PRTIM2 6
+#define PRTIM0 5
+#define PRTIM1 3
+#define PRSPI 2
+#define PRUSART0 1
+#define PRADC 0
+
+
+/*CLKPR*/
+#define CLKPCE 7
+#define CLKPS3 3
+#define CLKPS2 2
+#define CLKPS1 1
+#define CLKPS0 0
+
+/*WDTCSR*/
+#define WDIF 7
+#define WDIE 6
+#define WDP3 5
+#define WDCE 4
+#define WDE 3
+#define WDP2 2
+#define WDP1 1
+#define WDP0 0
+
+/* Ordinary I/O space */
+
+/*SPH*/
+#define SP9 1
+#define SP8 0
+
+/*SPL*/
+#define SP7 7
+#define SP6 6
+#define SP5 5
+#define SP4 4
+#define SP3 3
+#define SP2 2
+#define SP1 1
+#define SP0 0
+
+
+/*SPMCSR*/
+#define SPMIE 7
+#define BLBSET 3
+#define PGWRT 2
+#define PGERS 1
+#define SPMEN 0
+
+
+/*MCUCR*/
+#define PUD 4
+#define IVSEL 1
+#define IVCE 0
+
+/*MCUSR*/
+#define WDRF 3
+#define BORF 2
+#define EXTRF 1
+#define PORF 0
+
+/*SMCR*/
+#define SM2 3
+#define SM1 2
+#define SM0 1
+#define SE 0
+
+
+/*ACSR*/
+#define ACD 7
+#define ACBG 6
+#define ACO 5
+#define ACI 4
+#define ACIE 3
+#define ACIC 2
+#define ACIS1 1
+#define ACIS0 0
+
+
+/*SPSR*/
+#define SPIF 7
+#define WCOL 6
+#define SPI2X 0
+
+/*SPCR*/
+#define SPIE 7
+#define SPE 6
+#define DORD 5
+#define MSTR 4
+#define CPOL 3
+#define CPHA 2
+#define SPR1 1
+#define SPR0 0
+
+
+/*TCCR0B*/
+#define FOC0A 7
+#define FOC0B 6
+#define WGM02 3
+#define CS02 2
+#define CS01 1
+#define CS00 0
+
+/*TCCR0A*/
+#define COM0A1 7
+#define COM0A0 6
+#define COM0B1 5
+#define COM0B0 4
+#define WGM01 1
+#define WGM00 0
+
+/*GTCCR*/
+#define TSM 7
+#define PSR2 1
+#define PSR10 0
+
+
+/*EECR*/
+#define EERIE 3
+#define EEMPE 2
+#define EEPE 1
+#define EERE 0
+
+/*EIMSK*/
+#define INT1 1
+#define INT0 0
+
+/*EIFR*/
+#define INTF1 1
+#define INTF0 0
+
+/*PCIFR*/
+#define PCIF2 2
+#define PCIF1 1
+#define PCIF0 0
+
+
+/*TIFR2*/
+#define OCF2B 2
+#define OCF2A 1
+#define TOV2 0
+
+/*TIFR1*/
+#define ICF1 5
+#define OCF1B 2
+#define OCF1A 1
+#define TOV1 0
+
+/*TIFR0*/
+#define OCF0B 2
+#define OCF0A 1
+#define TOV0 0
+
+
+/*PORTD*/
+#define PORTD7 7
+#define PORTD6 6
+#define PORTD5 5
+#define PORTD4 4
+#define PORTD3 3
+#define PORTD2 2
+#define PORTD1 1
+#define PORTD0 0
+
+#define PD7 7
+#define PD6 6
+#define PD5 5
+#define PD4 4
+#define PD3 3
+#define PD2 2
+#define PD1 1
+#define PD0 0
+
+/*DDRD*/
+#define DDD7 7
+#define DDD6 6
+#define DDD5 5
+#define DDD4 4
+#define DDD3 3
+#define DDD2 2
+#define DDD1 1
+#define DDD0 0
+
+/*PIND*/
+#define PIND7 7
+#define PIND6 6
+#define PIND5 5
+#define PIND4 4
+#define PIND3 3
+#define PIND2 2
+#define PIND1 1
+#define PIND0 0
+
+/*PORTC*/
+#define PORTC6 6
+#define PORTC5 5
+#define PORTC4 4
+#define PORTC3 3
+#define PORTC2 2
+#define PORTC1 1
+#define PORTC0 0
+
+#define PC6 6
+#define PC5 5
+#define PC4 4
+#define PC3 3
+#define PC2 2
+#define PC1 1
+#define PC0 0
+
+/*DDRC*/
+#define DDC6 6
+#define DDC5 5
+#define DDC4 4
+#define DDC3 3
+#define DDC2 2
+#define DDC1 1
+#define DDC0 0
+
+/*PINC*/
+#define PINC6 6
+#define PINC5 5
+#define PINC4 4
+#define PINC3 3
+#define PINC2 2
+#define PINC1 1
+#define PINC0 0
+
+/*PORTB*/
+#define PORTB7 7
+#define PORTB6 6
+#define PORTB5 5
+#define PORTB4 4
+#define PORTB3 3
+#define PORTB2 2
+#define PORTB1 1
+#define PORTB0 0
+
+#define PB7 7
+#define PB6 6
+#define PB5 5
+#define PB4 4
+#define PB3 3
+#define PB2 2
+#define PB1 1
+#define PB0 0
+
+/*DDRB*/
+#define DDB7 7
+#define DDB6 6
+#define DDB5 5
+#define DDB4 4
+#define DDB3 3
+#define DDB2 2
+#define DDB1 1
+#define DDB0 0
+
+/*PINB*/
+#define PINB7 7
+#define PINB6 6
+#define PINB5 5
+#define PINB4 4
+#define PINB3 3
+#define PINB2 2
+#define PINB1 1
+#define PINB0 0
+
+
+/* Extended Fuse Byte */
+#define SELFPRGEN 0
+
+/* High Fuse Byte */
+#define RSTDISBL 7
+#define DWEN 6
+#define SPIEN 5
+#define WDTON 4
+#define EESAVE 3
+#define BODLEVEL2 2
+#define BODLEVEL1 1
+#define BODLEVEL0 0
+
+/* Low Fuse Byte */
+#define CKDIV8 7
+#define CKOUT 6
+#define SUT1 5
+#define SUT0 4
+#define CKSEL3 3
+#define CKSEL2 2
+#define CKSEL1 1
+#define CKSEL0 0
+
+/* Pointer definition */
+#define XL r26
+#define XH r27
+#define YL r28
+#define YH r29
+#define ZL r30
+#define ZH r31
+
+/* Contants */
+#define RAMEND 0x02FF /*Last On-Chip SRAM location*/
+#define XRAMEND 0x02FF
+#define E2END 0x00FF
+#define FLASHEND 0x0FFF
+
+#endif /* ENABLE_BIT_DEFINITIONS */
+#endif /* __IOM48_H (define part) */
+#endif /* __IOM48_H (SFR part) */
diff --git a/ATmega48/MEGA48/Include/iomacro.h b/ATmega48/MEGA48/Include/iomacro.h
new file mode 100644
index 0000000..ff3a71f
--- /dev/null
+++ b/ATmega48/MEGA48/Include/iomacro.h
@@ -0,0 +1,380 @@
+/**************************************************************
+ ** - iomacro.h -
+ **
+ ** This file defines the Special Function Register Macros
+ ** for Atmel AT90S.
+ **
+ ** Used with iccAVR and aAVR.
+ **
+ ** Copyright IAR Systems 1999. All rights reserved.
+ **
+ ** File version: $Revision: 1 $
+ **
+ **************************************************************/
+
+#ifndef __IOMACRO_H
+#define __IOMACRO_H
+
+#define TID_GUARD(proc) ((__TID__ & 0x7FF0) != ((90 << 8) | ((proc) << 4)))
+
+#if !(__IAR_SYSTEMS_ICC__) && !defined(__IAR_SYSTEMS_ASM__)
+#error This file should only be compiled with iccavr,icca90 or aavr.
+#endif /* !(__IAR_SYSTEMS_ICC__ > 2) && !defined __IAR_SYSTEMS_ASM__ */
+
+/* The assembler uses a special set of macros... */
+#ifdef __IAR_SYSTEMS_ASM__
+
+/* Byte sized SFRs */
+#define SFR_B_BITS(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME = _ADDR
+#define SFR_B_BITS_EXT(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME = _ADDR
+#define SFR_B_BITS_EXT_IO(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME = _ADDR
+#define SFR_B2_BITS(_NAME1,_NAME2,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ ASMSFRB2 _NAME1, _NAME2, _ADDR
+
+#define SFR_B_BITS_N(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME = _ADDR
+#define SFR_B_BITS_EXT_N(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME = _ADDR
+#define SFR_B_BITS_EXT_IO_N(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME = _ADDR
+#define SFR_B2_BITS_N(_NAME1,_NAME2,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ ASMSFRB2 _NAME1, _NAME2, _ADDR
+
+ASMSFRB2 MACRO
+ sfrb \1 = \3
+ sfrb \2 = \3
+ ENDM
+
+
+/* Word sized SFRs, needs to be expanded into an assembler macro first. */
+#define SFR_W_BITS(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P)\
+ ASMSFRW _NAME, _ADDR
+#define SFR_W_BITS_EXT_IO(_ADDR, _NAME, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P)\
+ ASMSFRW _NAME, _ADDR
+#define SFR_W_BITS_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2, \
+ _I2,_J2,_K2,_L2,_M2,_N2,_O2,_P2)\
+ ASMSFRW _NAME, _ADDR
+
+ASMSFRW MACRO
+ sfrw \1 = \2
+ sfrb \1L = (\2+0)
+ sfrb \1H = (\2+1)
+ ENDM
+
+#endif /* __IAR_SYSTEMS_ASM__ */
+
+#ifdef __ICCAVR__
+
+#define __BYTEBITS(_NAME,_A,_B,_C,_D,_E,_F,_G,_H) \
+unsigned char _NAME ## _ ## _A:1, \
+ _NAME ## _ ## _B:1, \
+ _NAME ## _ ## _C:1, \
+ _NAME ## _ ## _D:1, \
+ _NAME ## _ ## _E:1, \
+ _NAME ## _ ## _F:1, \
+ _NAME ## _ ## _G:1, \
+ _NAME ## _ ## _H:1;
+
+#define SFR_B_BITS(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H) \
+ __io union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B_BITS_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ __io union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B2_BITS(_NAME1, _NAME2, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H) \
+ __io union { \
+ unsigned char _NAME1; /* The sfrb as 1 byte */ \
+ unsigned char _NAME2; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME1, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME2, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B2_BITS_N(_NAME1, _NAME2, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ __io union { \
+ unsigned char _NAME1; /* The sfrb as 1 byte */ \
+ unsigned char _NAME2; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME1, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME2, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME1, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME2, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B_BITS_EXT(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H) \
+ __near __no_init volatile union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B_BITS_EXT_IO(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H) \
+ __ext_io union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ } @ _ADDR;
+
+
+#define SFR_B_BITS_EXT_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ __near __no_init volatile union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_B_BITS_EXT_IO_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ __ext_io union { \
+ unsigned char _NAME; /* The sfrb as 1 byte */ \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) \
+ }; \
+ struct { /* The sfrb as 8 bits */ \
+ __BYTEBITS(_NAME, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) \
+ }; \
+ } @ _ADDR;
+
+#define SFR_W_BITS(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P) \
+ __io union { \
+ unsigned short _NAME; /* The sfrw as 1 short */ \
+ struct { /* The sfrw as 16 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) /* Bit names defined by user */ \
+ __BYTEBITS(_NAME, _I,_J,_K,_L,_M,_N,_O,_P) /* Bit names defined by user */ \
+ }; \
+ struct { /* The sfrw as 2 bytes */ \
+ unsigned char _NAME ## L; \
+ unsigned char _NAME ## H; \
+ }; \
+ struct { /* The sfrw as 2 x 8 bits */ \
+ __BYTEBITS(_NAME ## L, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ __BYTEBITS(_NAME ## H, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ }; \
+ } @ _ADDR;
+
+#define SFR_W_BITS_EXT_IO(_ADDR, _NAME, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P) \
+ __ext_io union { \
+ unsigned short _NAME; /* The sfrw as 1 short */ \
+ struct { /* The sfrw as 16 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) /* Bit names defined by user */ \
+ __BYTEBITS(_NAME, _I,_J,_K,_L,_M,_N,_O,_P) /* Bit names defined by user */ \
+ }; \
+ struct { /* The sfrw as 2 bytes */ \
+ unsigned char _NAME ## L; \
+ unsigned char _NAME ## H; \
+ }; \
+ struct { /* The sfrw as 2 x 8 bits */ \
+ __BYTEBITS(_NAME ## L, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ __BYTEBITS(_NAME ## H, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ }; \
+ } @ _ADDR;
+
+#define SFR_W_BITS_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2, \
+ _I2,_J2,_K2,_L2,_M2,_N2,_O2,_P2) \
+ __io union { \
+ unsigned short _NAME; /* The sfrw as 1 short */ \
+ struct { /* The sfrw as 16 bits */ \
+ __BYTEBITS(_NAME, _A,_B,_C,_D,_E,_F,_G,_H) /* Bit names defined by user */ \
+ __BYTEBITS(_NAME, _I,_J,_K,_L,_M,_N,_O,_P) /* Bit names defined by user */ \
+ }; \
+ struct { /* The sfrw as 16 bits */ \
+ __BYTEBITS(_NAME, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) /* Bit names defined by user */ \
+ __BYTEBITS(_NAME, _I2,_J2,_K2,_L2,_M2,_N2,_O2,_P2) /* Bit names defined by user */ \
+ }; \
+ struct { /* The sfrw as 2 bytes */ \
+ unsigned char _NAME ## L; \
+ unsigned char _NAME ## H; \
+ }; \
+ struct { /* The sfrw as 2 x 8 bits */ \
+ __BYTEBITS(_NAME ## L, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ __BYTEBITS(_NAME ## H, Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7) /* Bit names hard coded to 0-7 */ \
+ }; \
+ struct { /* The sfrw as 2 x 8 bits */ \
+ __BYTEBITS(_NAME ## L, _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2) /* Bit names defined by user */ \
+ __BYTEBITS(_NAME ## H, _I2,_J2,_K2,_L2,_M2,_N2,_O2,_P2) /* Bit names defined by user */ \
+ }; \
+ } @ _ADDR;
+#else
+#ifndef __IAR_SYSTEMS_ASM__
+ /* Special for the icca90 */
+
+/* Byte sized SFRs */
+#define SFR_B_BITS(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME = _ADDR;
+#define SFR_B_BITS_EXT(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME = _ADDR;
+#define SFR_B2_BITS(_NAME1,_NAME2,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H)\
+ sfrb _NAME1 = _ADDR; sfrb _NAME2 = _ADDR;
+
+#define SFR_B_BITS_N(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME = _ADDR;
+#define SFR_B_BITS_EXT_N(_NAME,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME = _ADDR;
+#define SFR_B2_BITS_N(_NAME1,_NAME2,_ADDR,_A,_B,_C,_D,_E,_F,_G,_H, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2)\
+ sfrb _NAME1 = _ADDR; sfrb _NAME2 = _ADDR;
+
+/* Word sized SFRs */
+#define SFR_W_BITS(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P)\
+ sfrw _NAME = _ADDR; sfrb _NAME##L = _ADDR; sfrb _NAME##H = (_ADDR+1);
+#define SFR_W_BITS_N(_NAME, _ADDR, _A,_B,_C,_D,_E,_F,_G,_H, _I,_J,_K,_L,_M,_N,_O,_P, \
+ _A2,_B2,_C2,_D2,_E2,_F2,_G2,_H2, \
+ _I2,_J2,_K2,_L2,_M2,_N2,_O2,_P2)\
+ sfrw _NAME = _ADDR; sfrb _NAME##L = _ADDR; sfrb _NAME##H = (_ADDR+1);
+
+#endif
+#endif /* !__ICCAVR__ */
+
+#define SFR_B(_NAME, _ADDR) SFR_B_BITS(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+/*
+ SFR_B(SREG, 0x3F) Expands to:
+ __io union {
+ unsigned char SREG; // The sfrb as 1 byte
+ struct { // The sfrb as 8 bits
+ unsigned char SREG_Bit0:1,
+ SREG_Bit1:1,
+ SREG_Bit2:1,
+ SREG_Bit3:1,
+ SREG_Bit4:1,
+ SREG_Bit5:1,
+ SREG_Bit6:1,
+ SREG_Bit7:1;
+ };
+ } @ 0x3F;
+*/
+#define SFR_B2(_NAME1, _NAME2, _ADDR) SFR_B2_BITS(_NAME1, _NAME2, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+#define SFR_B_EXT(_NAME, _ADDR) SFR_B_BITS_EXT(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+
+#define SFR_W(_NAME, _ADDR) SFR_W_BITS(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ Bit8,Bit9,Bit10,Bit11,Bit12,Bit13,Bit14,Bit15)
+
+#define SFR_B_R(_ADDR, _NAME) SFR_B_BITS(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+#define SFR_B_EXT_IO_R(_ADDR, _NAME) SFR_B_BITS_EXT_IO(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+#define SFR_W_EXT_IO_R(_NAME, _ADDR) SFR_W_BITS_EXT_IO(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ Bit8,Bit9,Bit10,Bit11,Bit12,Bit13,Bit14,Bit15)
+/*
+ SFR_B(0x3F, SREG) Expands to:
+ __io union {
+ unsigned char SREG; // The sfrb as 1 byte
+ struct { // The sfrb as 8 bits
+ unsigned char SREG_Bit0:1,
+ SREG_Bit1:1,
+ SREG_Bit2:1,
+ SREG_Bit3:1,
+ SREG_Bit4:1,
+ SREG_Bit5:1,
+ SREG_Bit6:1,
+ SREG_Bit7:1;
+ };
+ } @ 0x3F;
+*/
+#define SFR_B2_R(_ADDR, _NAME1, _NAME2) SFR_B2_BITS(_NAME1, _NAME2, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7)
+#define SFR_W_R(_ADDR, _NAME) SFR_W_BITS(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ Bit8,Bit9,Bit10,Bit11,Bit12,Bit13,Bit14,Bit15)
+
+#define SFR_B_N(_ADDR, _NAME, _B7, _B6, _B5, _B4, _B3, _B2, _B1, _B0) \
+ SFR_B_BITS_N(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ _B0,_B1,_B2,_B3,_B4,_B5,_B6,_B7)
+/*
+ SFR_B_N(0x3F,SREG,I,T,H,S,V,N,Z,C) Expands to:
+ __io union {
+ unsigned char SREG; // The sfrb as 1 byte
+ struct { // The sfrb as 8 bits
+ unsigned char SREG_Bit0:1,
+ SREG_Bit1:1,
+ SREG_Bit2:1,
+ SREG_Bit3:1,
+ SREG_Bit4:1,
+ SREG_Bit5:1,
+ SREG_Bit6:1,
+ SREG_Bit7:1;
+ };
+ struct { // The sfrb as 8 bits
+ unsigned char SREG_C:1,
+ SREG_Z:1,
+ SREG_N:1,
+ SREG_V:1,
+ SREG_S:1,
+ SREG_H:1,
+ SREG_T:1,
+ SREG_I:1;
+ };
+ } @ 0x3F;
+*/
+#define SFR_B2_N(_ADDR, _NAME1, _NAME2, _B7, _B6, _B5, _B4, _B3, _B2, _B1, _B0) \
+ SFR_B2_BITS_N(_NAME1, _NAME2, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ _B0,_B1,_B2,_B3,_B4,_B5,_B6,_B7)
+
+#define SFR_B_EXT_N(_ADDR, _NAME, _B7, _B6, _B5, _B4, _B3, _B2, _B1, _B0) \
+ SFR_B_BITS_EXT_N(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ _B0,_B1,_B2,_B3,_B4,_B5,_B6,_B7)
+
+#define SFR_B_EXT_IO_N(_ADDR, _NAME, _B7, _B6, _B5, _B4, _B3, _B2, _B1, _B0) \
+ SFR_B_BITS_EXT_IO_N(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ _B0,_B1,_B2,_B3,_B4,_B5,_B6,_B7)
+
+#define SFR_W_N(_ADDR, _NAME, _B15, _B14, _B13, _B12, _B11, _B10, _B9, _B8, \
+ _B7, _B6, _B5, _B4, _B3, _B2, _B1, _B0) \
+ SFR_W_BITS_N(_NAME, _ADDR, \
+ Bit0,Bit1,Bit2,Bit3,Bit4,Bit5,Bit6,Bit7, \
+ Bit8,Bit9,Bit10,Bit11,Bit12,Bit13,Bit14,Bit15, \
+ _B0,_B1,_B2,_B3,_B4,_B5,_B6,_B7, \
+ _B8,_B9,_B10,_B11,_B12,_B13,_B14,_B15)
+
+#endif /* __IOMACRO_H */
diff --git a/ATmega48/MEGA48/Lib/cl1s-ec.r90 b/ATmega48/MEGA48/Lib/cl1s-ec.r90
new file mode 100644
index 0000000..cb214e0
--- /dev/null
+++ b/ATmega48/MEGA48/Lib/cl1s-ec.r90
Binary files differ
diff --git a/ATmega48/Source/c_armcomm.c b/ATmega48/Source/c_armcomm.c
new file mode 100644
index 0000000..6d5853d
--- /dev/null
+++ b/ATmega48/Source/c_armcomm.c
@@ -0,0 +1,601 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 10-11-05 15:35 $
+//
+// Filename $Workfile:: c_armcomm.c $
+//
+// Version $Revision:: 17 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/c_armcom $
+//
+// Platform C
+//
+
+/* Event Function State
+--------------------------------------- ------------------------------------- -----------------------------------
+
+Voltage > 4,3V, wakeup or reset button Brake motor drivers RESET
+ POWERUP
+ Batt measument off POWERUP_CHECK_FOR_RECHARGEABLE
+ Wait 10 mS
+ Rechargeable if switch > 0,5V
+ Batt measurement on POWERUP_CHECK_VOLTAGE_FOR_ARM_ON
+ Wait 10 mS
+ Check voltage for ARM on <= 11,8V
+ Batt measument off POWERUP_DISABLE_AMP
+ Wait 10 mS
+ Turn ARM on POWERUP_TURN_ARM_ON
+ Brake off
+ Wait 500 mS POWERUP_ENABLE_AMP
+ Batt measurement on
+ Check voltage for ARM on >= 6,5V (rechg) POWERUP_CHECK_RECHARGEABLE_VOLTAGE
+Samba active Reset copyright timer ON
+ Read all inputs and update buttons ON_RUNNING
+ Check ARM communicating
+ Check for high voltage/samba button
+ Control led (Batt measurement on/off)
+ Check for ARM samba request
+ Check for ARM powerdown request
+ Check for ARM copyright invalid
+
+
+High voltage (batt > 12,2V or samba button) Turn of input current drive ON_HIGH_VOLTAGE
+ Turn off ARM
+ Brake output drivers
+ Batt measurement off ON_CHECK_BUTTON
+ Check samba button
+
+
+Power down request or copyright invalid POWERDOWN
+ Batt measurement off POWERDOWN_DISABLE_AMP
+ Wait 10 mS
+ Turn ARM off POWERDOWN_TURN_ARM_OFF
+ Wait 1 sec
+Rechargeable < 6,5V OFF
+ SLEEP
+
+
+Samba button (long press) or samba request SAMBA
+ Wait 100 mS SAMBA_ACTIVATE
+ Batt measurement forced high SAMBA_TURN_ARM_OFF_AND_WAIT
+ Batt measurement off
+ Turn ARM off
+ Wait 1 sec
+ Turn ARM on SAMBA_TURN_ARM_ON_AND_WAIT
+ Wait 10 sec
+ Turn ARM off SAMBA_TURN_ARM_OFF_FOR_RESET
+ Remove batt measurement force
+ Wait 1 sec
+ Turn ARM on SAMBA_TURN_ARM_ON
+ ON
+
+
+*/
+
+#include "stdconst.h"
+#include "c_armcomm.h"
+#include "d_power.h"
+#include "d_output.h"
+#include "d_input.h"
+#include "d_button.h"
+#include "d_armcomm.h"
+#include "d_timer.h"
+
+
+#define INPUTPOWER_ONTIME 3000 // [uS] time between input A/D samples
+#define COPYRIGHT_TIME 300000L // [mS] time to power down if no copy right string found
+
+#define POWERUP_ENABLE_MEASURE_TIME 10 // [mS] time to enable voltage divider for measurement
+#define POWERUP_DISABLE_MEASURE_TIME 10 // [mS] time to disable voltage divider for measurement
+#define POWERUP_DISABLE_AMP_TIME 10 // [mS] time after amp is disenabled
+#define POWERUP_ENABLE_AMP_TIME 100 // [mS] time before amp is enabled
+#define POWERUP_RECHARGE_TEST_TIME 1000 // [mS] time testing voltage if rechargeable (to show low batt on display)
+#define ON_ARM_TIMEOUT_TIME 2000 // [mS] time between ARM communication (max)
+#define LED_TOGGLE_TIME 500 // [mS] time between led toggles on and off
+#define CHECK_TEST_BUTTON_TIME 2000 // [mS] time for stable button reading (samba activate)
+#define BUTTON_ACCEPT_TIME 200 // [mS] time from samba accept to actual active
+#define SAMBA_POWEROFF_TIME 1000 // [mS] time for ARM power to drop
+#define SAMBA_BOOT_TIME 10000 // [mS] time for copying samba boot loader
+#define POWEROFF_TIME 1000 // [mS] time from ARM off to sleep
+
+#define RECHARGEABLE_SWITCH_VOLTAGE 500L // [mV] trigger point for rechageable battery detect switch
+#define ARM_POWERUP_MAX_VOLTAGE 11800L // [mV] maximum allowable voltage when turning on ARM
+#define ARM_ON_MAX_VOLTAGE 12200L // [mV] maximum allowable voltage when running ARM
+#define ARM_ON_OK_VOLTAGE 10000L // [mV] maximum allowable voltage when turning on ARM (after high voltage)
+#define ARM_ON_MIN_VOLTAGE 6500L // [mV] minimum allowable voltage when turning on ARM (rechargeable)
+
+
+
+
+
+// Use compiler to calculate ticks from time
+#define INPUTPOWER_ONTICK (UBYTE)(((ULONG)TIMER_RESOLUTION / (1000000L / (ULONG)INPUTPOWER_ONTIME)))
+#define COPYRIGHT_TICK (ULONG)(((ULONG)COPYRIGHT_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWERUP_ENABLE_MEASURE_TICK (UWORD)(((ULONG)POWERUP_ENABLE_MEASURE_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWERUP_DISABLE_MEASURE_TICK (UWORD)(((ULONG)POWERUP_DISABLE_MEASURE_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWERUP_DISABLE_AMP_TICK (UWORD)(((ULONG)POWERUP_DISABLE_AMP_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWERUP_ENABLE_AMP_TICK (UWORD)(((ULONG)POWERUP_ENABLE_AMP_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWERUP_RECHARGE_TEST_TICK (UWORD)(((ULONG)POWERUP_RECHARGE_TEST_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define ON_ARM_TIMEOUT_TICK (UWORD)(((ULONG)ON_ARM_TIMEOUT_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define LED_TOGGLE_TICK (UWORD)(((ULONG)LED_TOGGLE_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define CHECK_TEST_BUTTON_TICK (UWORD)(((ULONG)CHECK_TEST_BUTTON_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define SAMBA_POWEROFF_TICK (UWORD)(((ULONG)SAMBA_POWEROFF_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define SAMBA_BOOT_TICK (UWORD)(((ULONG)SAMBA_BOOT_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define BUTTON_ACCEPT_TICK (UWORD)(((ULONG)BUTTON_ACCEPT_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+#define POWEROFF_TICK (UWORD)(((ULONG)POWEROFF_TIME * 1000L) / (ULONG)INPUTPOWER_ONTIME)
+
+
+// Use compiler to calculate counts from voltage
+#define ADC_REFERENCE 5000L // [mv]
+#define ADC_RESOLUTION 1023L // [Count]
+#define RESISTOR_HIGH 22000L // [ohm]
+#define RESISTOR_LOW 12000L // [ohm]
+#define RECHARGEABLE_SWITCH_COUNT (UWORD)(((((RECHARGEABLE_SWITCH_VOLTAGE * RESISTOR_LOW) / (RESISTOR_LOW + RESISTOR_HIGH)) * ADC_RESOLUTION) / ADC_REFERENCE))
+#define ARM_POWERUP_MAX_COUNT (UWORD)(((((ARM_POWERUP_MAX_VOLTAGE * RESISTOR_LOW) / (RESISTOR_LOW + RESISTOR_HIGH)) * ADC_RESOLUTION) / ADC_REFERENCE))
+#define ARM_ON_MAX_COUNT (UWORD)(((((ARM_ON_MAX_VOLTAGE * RESISTOR_LOW) / (RESISTOR_LOW + RESISTOR_HIGH)) * ADC_RESOLUTION) / ADC_REFERENCE))
+#define ARM_ON_OK_COUNT (UWORD)(((((ARM_ON_OK_VOLTAGE * RESISTOR_LOW) / (RESISTOR_LOW + RESISTOR_HIGH)) * ADC_RESOLUTION) / ADC_REFERENCE))
+#define ARM_ON_MIN_COUNT (UWORD)(((((ARM_ON_MIN_VOLTAGE * RESISTOR_LOW) / (RESISTOR_LOW + RESISTOR_HIGH)) * ADC_RESOLUTION) / ADC_REFERENCE))
+
+#define TEST_BUTTON_VALUE (ADC_RESOLUTION - 10)
+
+// State machine states
+enum
+{
+ RESET,
+ POWERUP,
+ POWERUP_CHECK_FOR_RECHARGEABLE,
+ POWERUP_CHECK_VOLTAGE_FOR_ARM_ON,
+ POWERUP_DISABLE_AMP,
+ POWERUP_TURN_ARM_ON,
+ POWERUP_ENABLE_AMP,
+ POWERUP_CHECK_RECHARGEABLE_VOLTAGE,
+ ON,
+ ON_RUNNING,
+ ON_HIGH_VOLTAGE,
+ ON_CHECK_BUTTON,
+ SAMBA,
+ SAMBA_ACTIVATE,
+ SAMBA_TURN_ARM_OFF_AND_WAIT,
+ SAMBA_TURN_ARM_ON_AND_WAIT,
+ SAMBA_TURN_ARM_OFF_FOR_RESET,
+ SAMBA_TURN_ARM_ON,
+ POWERDOWN,
+ POWERDOWN_DISABLE_AMP,
+ POWERDOWN_TURN_ARM_OFF,
+ OFF,
+ SLEEP
+};
+
+
+UBYTE State;
+UBYTE OldState;
+UBYTE OverwriteFloat;
+UWORD StateTimer;
+UBYTE Rechargeable;
+UWORD ArmTimer;
+UBYTE ArmFucked;
+UBYTE LedState;
+UWORD ButtonTimer;
+ULONG CopyRightTimer;
+
+
+void cArmCommInit(void)
+{
+ dPowerInit();
+ dOutputInit();
+ dInputInit();
+ dButtonInit();
+ dArmCommInit();
+ dTimerInit();
+
+ State = RESET;
+ OldState = ~State;
+}
+
+
+UBYTE cArmCommCtrl(void)
+{
+ UBYTE Result = TRUE;
+
+ // Update state machine if timeout (or RESET)
+ if ((dTimerRead() >= INPUTPOWER_ONTICK) || (State == RESET))
+ {
+ dTimerClear();
+
+ // Maintain StateTimer (clear if state changes else increament)
+ if (State != OldState)
+ {
+ OldState = State;
+ StateTimer = 0;
+ }
+ else
+ {
+ StateTimer++;
+ }
+
+ // STATE MACHINE
+ switch (State)
+ {
+
+ case RESET :
+ {
+ if (!StateTimer)
+ {
+ OverwriteFloat = TRUE;
+ State = POWERUP;
+ }
+ }
+ break;
+
+ case POWERUP :
+ {
+ State = POWERUP_CHECK_FOR_RECHARGEABLE;
+ }
+ break;
+
+ case POWERUP_CHECK_FOR_RECHARGEABLE :
+ {
+ if (!StateTimer)
+ {
+ dPowerDeselect();
+ }
+ if (StateTimer >= POWERUP_DISABLE_MEASURE_TICK)
+ {
+ if (dPowerConvert() > RECHARGEABLE_SWITCH_COUNT)
+ {
+ Rechargeable = TRUE;
+ }
+ dPowerRechargeable(Rechargeable);
+ State = POWERUP_CHECK_VOLTAGE_FOR_ARM_ON;
+ }
+ }
+ break;
+
+ case POWERUP_CHECK_VOLTAGE_FOR_ARM_ON :
+ {
+ if (!StateTimer)
+ {
+ dPowerSelect();
+ }
+ if (StateTimer >= POWERUP_ENABLE_MEASURE_TICK)
+ {
+ if (dPowerConvert() <= ARM_POWERUP_MAX_COUNT)
+ {
+ State = POWERUP_DISABLE_AMP;
+ }
+ }
+ }
+ break;
+
+ case POWERUP_DISABLE_AMP :
+ {
+ if (!StateTimer)
+ {
+ dPowerDeselect();
+ }
+ if (StateTimer >= POWERUP_DISABLE_AMP_TICK)
+ {
+ State = POWERUP_TURN_ARM_ON;
+ }
+ }
+ break;
+
+ case POWERUP_TURN_ARM_ON :
+ {
+ dPowerWriteOn(TRUE);
+ OverwriteFloat = FALSE;
+ State = POWERUP_ENABLE_AMP;
+ }
+ break;
+
+ case POWERUP_ENABLE_AMP :
+ {
+ if (StateTimer >= POWERUP_ENABLE_AMP_TICK)
+ {
+ dPowerSelect();
+ State = POWERUP_CHECK_RECHARGEABLE_VOLTAGE;
+ }
+ }
+ break;
+
+ case POWERUP_CHECK_RECHARGEABLE_VOLTAGE :
+ {
+ if (Rechargeable == TRUE)
+ {
+ if (dPowerConvert() < ARM_ON_MIN_COUNT)
+ {
+ if (StateTimer >= POWERUP_RECHARGE_TEST_TICK)
+ {
+ State = OFF;
+ }
+ }
+ else
+ {
+ State = ON;
+ }
+ }
+ else
+ {
+ State = ON;
+ }
+ }
+ break;
+
+ case ON :
+ {
+ CopyRightTimer = 0L;
+ State = ON_RUNNING;
+ }
+ break;
+
+ case ON_RUNNING :
+ {
+
+ // Read all inputs
+ dInputSelect(0);
+ dInputConvert(0);
+ dInputConvert(0);
+ dInputDeselect(0);
+
+ dInputSelect(1);
+ dInputConvert(1);
+ dInputConvert(1);
+ dInputDeselect(1);
+
+ dInputSelect(2);
+ dInputConvert(2);
+ dInputConvert(2);
+ dInputDeselect(2);
+
+ dInputSelect(3);
+ dInputConvert(3);
+ dInputConvert(3);
+ dInputDeselect(3);
+
+ // Update buttons
+ dButtonUpdate();
+
+ // Check for ARM communication
+ if (dArmCommCheck() == TRUE)
+ {
+ ArmTimer = 0;
+ ArmFucked = FALSE;
+ }
+
+ if (ArmTimer >= ON_ARM_TIMEOUT_TICK)
+ {
+ ArmFucked = TRUE;
+ }
+ else
+ {
+ ArmTimer++;
+ }
+
+ // Check for high voltage
+ dPowerSelect();
+ if (dPowerConvert() > ARM_ON_MAX_COUNT)
+ {
+ State = ON_HIGH_VOLTAGE;
+ }
+
+ // Control led
+ if (ArmFucked == TRUE)
+ {
+ if (StateTimer >= LED_TOGGLE_TICK)
+ {
+ StateTimer = 0;
+ if (LedState == TRUE)
+ {
+ LedState = FALSE;
+ }
+ else
+ {
+ LedState = TRUE;
+ }
+ }
+ }
+ else
+ {
+ LedState = TRUE;
+ }
+
+ if (LedState == FALSE)
+ {
+ dPowerDeselect();
+ }
+
+ // Check for SAMBA request
+ if (dPowerReadBoot() == TRUE)
+ {
+ State = SAMBA;
+ }
+
+ // Check for POWERDOWN request
+ if (dPowerReadOn() == FALSE)
+ {
+ State = POWERDOWN;
+ }
+
+ // Check for CopyRight valid
+ if (dArmCommCopyRight() != TRUE)
+ {
+ if (++CopyRightTimer >= COPYRIGHT_TICK)
+ {
+ State = POWERDOWN;
+ }
+ }
+ }
+ break;
+
+ case ON_HIGH_VOLTAGE :
+ {
+ dInputInit();
+ dPowerWriteOn(FALSE);
+ OverwriteFloat = TRUE;
+ ButtonTimer = CHECK_TEST_BUTTON_TICK;
+ State = ON_CHECK_BUTTON;
+ }
+ break;
+
+ case ON_CHECK_BUTTON :
+ {
+ dPowerSelect();
+ if (ButtonTimer)
+ {
+ dPowerDeselect();
+ if (dPowerConvert() >= TEST_BUTTON_VALUE)
+ {
+ ButtonTimer++;
+ if (ButtonTimer > (CHECK_TEST_BUTTON_TICK * 2))
+ {
+ dPowerSelect();
+ State = SAMBA;
+ }
+ }
+ else
+ {
+ ButtonTimer--;
+ }
+ }
+ else
+ {
+ if (dPowerConvert() <= ARM_ON_OK_COUNT)
+ {
+ State = RESET;
+ }
+ }
+ }
+ break;
+
+ case POWERDOWN :
+ {
+ State = POWERDOWN_DISABLE_AMP;
+ }
+ break;
+
+ case POWERDOWN_DISABLE_AMP :
+ {
+ if (!StateTimer)
+ {
+ dPowerDeselect();
+ }
+ if (StateTimer >= POWERUP_DISABLE_AMP_TICK)
+ {
+ State = POWERDOWN_TURN_ARM_OFF;
+ }
+ }
+ break;
+
+ case POWERDOWN_TURN_ARM_OFF :
+ {
+ if (!StateTimer)
+ {
+ dPowerWriteOn(FALSE);
+ }
+ if (StateTimer >= POWEROFF_TICK)
+ {
+ State = OFF;
+ }
+ }
+ break;
+
+ case OFF :
+ {
+ State = SLEEP;
+ }
+ break;
+
+ case SAMBA :
+ {
+ State = SAMBA_ACTIVATE;
+ }
+ break;
+
+ case SAMBA_ACTIVATE :
+ {
+ if (++StateTimer >= BUTTON_ACCEPT_TICK)
+ {
+ State = SAMBA_TURN_ARM_OFF_AND_WAIT;
+ }
+ }
+ break;
+
+ case SAMBA_TURN_ARM_OFF_AND_WAIT :
+ {
+ if (!StateTimer)
+ {
+ dPowerHigh();
+ dPowerDeselect();
+ dPowerWriteOn(FALSE);
+ }
+ if (++StateTimer >= SAMBA_POWEROFF_TICK)
+ {
+ State = SAMBA_TURN_ARM_ON_AND_WAIT;
+ }
+ }
+ break;
+
+ case SAMBA_TURN_ARM_ON_AND_WAIT :
+ {
+ if (!StateTimer)
+ {
+ dPowerWriteOn(TRUE);
+ }
+ if (++StateTimer >= SAMBA_BOOT_TICK)
+ {
+ State = SAMBA_TURN_ARM_OFF_FOR_RESET;
+ }
+ }
+ break;
+
+ case SAMBA_TURN_ARM_OFF_FOR_RESET :
+ {
+ if (!StateTimer)
+ {
+ dPowerWriteOn(FALSE);
+ dPowerFloat();
+ }
+ if (++StateTimer >= SAMBA_POWEROFF_TICK)
+ {
+ State = SAMBA_TURN_ARM_ON;
+ }
+ }
+ break;
+
+ case SAMBA_TURN_ARM_ON :
+ {
+ dPowerWriteOn(TRUE);
+ State = ON;
+ }
+ break;
+
+ case SLEEP :
+ {
+ Result = FALSE;
+ }
+ break;
+
+ }
+ }
+
+ // Update allways output
+ dOutputUpdate(OverwriteFloat);
+
+ return(Result);
+}
+
+
+void cArmCommExit(void)
+{
+ dTimerExit();
+ dArmCommExit();
+ dButtonExit();
+ dInputExit();
+ dOutputExit();
+ dPowerExit();
+}
diff --git a/ATmega48/Source/c_armcomm.h b/ATmega48/Source/c_armcomm.h
new file mode 100644
index 0000000..239ab73
--- /dev/null
+++ b/ATmega48/Source/c_armcomm.h
@@ -0,0 +1,44 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dkandlun $
+//
+// Revision date $Date:: 28-12-04 14:19 $
+//
+// Filename $Workfile:: c_armcomm.h $
+//
+// Version $Revision:: 1 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Peripheral/Firmware/Source/c_ar $
+//
+// Platform C
+//
+
+
+#ifndef C_ARMCOMM
+#define C_ARMCOMM
+
+#define NOS_OF_MOTORS 4
+#define NOS_OF_SENSORS 4
+#define NOS_OF_BTNS 5
+
+typedef struct
+{
+ UBYTE TimerTik;
+ UBYTE MotorStatus[NOS_OF_MOTORS];
+ UBYTE MotorSpeed[NOS_OF_MOTORS];
+}InputMap;
+
+typedef struct
+{
+ SWORD SensorValue[NOS_OF_SENSORS];
+ UBYTE ButtonState[NOS_OF_BTNS];
+}OutputMap;
+
+void cArmCommInit(void);
+UBYTE cArmCommCtrl(void);
+void cArmCommExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_armcomm.c b/ATmega48/Source/d_armcomm.c
new file mode 100644
index 0000000..bdcce63
--- /dev/null
+++ b/ATmega48/Source/d_armcomm.c
@@ -0,0 +1,48 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: d_armcomm.c $
+//
+// Version $Revision:: 5 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_armcom $
+//
+// Platform C
+//
+
+
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "c_armcomm.h"
+#include "d_armcomm.r"
+
+
+void dArmCommInit(void)
+{
+ ARMCOMMInit;
+}
+
+
+UBYTE dArmCommCheck(void)
+{
+ return (ARMCOMMCheck);
+}
+
+
+UBYTE dArmCommCopyRight(void)
+{
+ return (ARMCOMMCopyRight);
+}
+
+
+void dArmCommExit(void)
+{
+ ARMCOMMExit;
+}
diff --git a/ATmega48/Source/d_armcomm.h b/ATmega48/Source/d_armcomm.h
new file mode 100644
index 0000000..416753e
--- /dev/null
+++ b/ATmega48/Source/d_armcomm.h
@@ -0,0 +1,28 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: d_armcomm.h $
+//
+// Version $Revision:: 4 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_armcom $
+//
+// Platform C
+//
+
+
+#ifndef D_ARMCOMM
+#define D_ARMCOMM
+
+void dArmCommInit(void);
+UBYTE dArmCommCheck(void);
+UBYTE dArmCommCopyRight(void);
+void dArmCommExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_armcomm.r b/ATmega48/Source/d_armcomm.r
new file mode 100644
index 0000000..42712aa
--- /dev/null
+++ b/ATmega48/Source/d_armcomm.r
@@ -0,0 +1,253 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: d_armcomm.r $
+//
+// Version $Revision:: 15 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_armcom $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+/****************************************************************************
+ TWI State codes
+****************************************************************************/
+
+#define TWI_START 0x08 // START has been transmitted
+#define TWI_REP_START 0x10 // Repeated START has been transmitted
+#define TWI_ARB_LOST 0x38 // Arbitration lost
+
+// TWI Master Transmitter staus codes
+#define TWI_MTX_ADR_ACK 0x18 // SLA+W has been tramsmitted and ACK received
+#define TWI_MTX_ADR_NACK 0x20 // SLA+W has been tramsmitted and NACK received
+#define TWI_MTX_DATA_ACK 0x28 // Data byte has been tramsmitted and ACK received
+#define TWI_MTX_DATA_NACK 0x30 // Data byte has been tramsmitted and NACK received
+
+// TWI Master Receiver staus codes
+#define TWI_MRX_ADR_ACK 0x40 // SLA+R has been tramsmitted and ACK received
+#define TWI_MRX_ADR_NACK 0x48 // SLA+R has been tramsmitted and NACK received
+#define TWI_MRX_DATA_ACK 0x50 // Data byte has been received and ACK tramsmitted
+#define TWI_MRX_DATA_NACK 0x58 // Data byte has been received and NACK tramsmitted
+
+// TWI Slave Transmitter staus codes
+#define TWI_STX_ADR_ACK 0xA8 // Own SLA+R has been received; ACK has been returned
+#define TWI_STX_ADR_ACK_M_ARB_LOST 0xB0 // Arbitration lost in SLA+R/W as Master; own SLA+R has been received; ACK has been returned
+#define TWI_STX_DATA_ACK 0xB8 // Data byte in TWDR has been transmitted; ACK has been received
+#define TWI_STX_DATA_NACK 0xC0 // Data byte in TWDR has been transmitted; NOT ACK has been received
+#define TWI_STX_DATA_ACK_LAST_BYTE 0xC8 // Last data byte in TWDR has been transmitted (TWEA = “0”); ACK has been received
+
+// TWI Slave Receiver staus codes
+#define TWI_SRX_ADR_ACK 0x60 // Own SLA+W has been received ACK has been returned
+#define TWI_SRX_ADR_ACK_M_ARB_LOST 0x68 // Arbitration lost in SLA+R/W as Master; own SLA+W has been received; ACK has been returned
+#define TWI_SRX_GEN_ACK 0x70 // General call address has been received; ACK has been returned
+#define TWI_SRX_GEN_ACK_M_ARB_LOST 0x78 // Arbitration lost in SLA+R/W as Master; General call address has been received; ACK has been returned
+#define TWI_SRX_ADR_DATA_ACK 0x80 // Previously addressed with own SLA+W; data has been received; ACK has been returned
+#define TWI_SRX_ADR_DATA_NACK 0x88 // Previously addressed with own SLA+W; data has been received; NOT ACK has been returned
+#define TWI_SRX_GEN_DATA_ACK 0x90 // Previously addressed with general call; data has been received; ACK has been returned
+#define TWI_SRX_GEN_DATA_NACK 0x98 // Previously addressed with general call; data has been received; NOT ACK has been returned
+#define TWI_SRX_STOP_RESTART 0xA0 // A STOP condition or repeated START condition has been received while still addressed as Slave
+
+// TWI Miscellaneous status codes
+#define TWI_NO_STATE 0xF8 // No relevant state information available; TWINT = “0”
+#define TWI_BUS_ERROR 0x00 // Bus error due to an illegal START or STOP condition
+
+
+
+/***********************************************************************************/
+/*********************** Declaration of variables *******************************/
+/***********************************************************************************/
+
+#define ADDRESS 1
+#define INBYTES BYTES_TO_TX // (sizeof(IoToAvr))
+#define OUTBYTES BYTES_TO_RX // (sizeof(IoFromAvr))
+
+__flash UBYTE CopyRightString[COPYRIGHTSTRINGLENGTH + 1] = COPYRIGHTSTRING;
+
+static UBYTE I2CInByte;
+static UBYTE I2CInBuffer[INBYTES + 1];
+static UBYTE *pI2CInBuffer;
+static UBYTE I2CInPointer;
+static UBYTE I2COutBuffer[OUTBYTES + 1];
+static UBYTE *pI2COutBuffer;
+static UBYTE I2COutPointer;
+static UBYTE Chksum;
+static UBYTE I2CInState;
+static UBYTE ArmCommFlag;
+static UBYTE ArmCopyRightValid;
+
+#define ARMCOMMInit TWAR = (UBYTE)(ADDRESS << 1);\
+ TWCR = 0xC5;\
+ ArmCommFlag = FALSE;\
+ ArmCopyRightValid = FALSE
+
+
+#pragma vector=TWI_vect
+__interrupt void I2CInterrupt(void)
+{
+ switch ((TWSR & 0xF8))
+ {
+
+ // Write command
+
+ case TWI_SRX_ADR_ACK :
+ {
+ I2CInPointer = 0;
+ I2CInState = 0;
+ }
+ break;
+
+ case TWI_SRX_ADR_DATA_ACK :
+ {
+ I2CInByte = TWDR;
+
+ switch (I2CInState)
+ {
+ case 0 :
+ {
+ if (I2CInByte != 0xCC)
+ {
+ I2CInBuffer[I2CInPointer++] = I2CInByte;
+ I2CInState++;
+ }
+ else
+ {
+ I2CInState = 2;
+ }
+ }
+ break;
+
+ case 1 :
+ {
+ I2CInBuffer[I2CInPointer++] = I2CInByte;
+ if (I2CInPointer >= (INBYTES + 1))
+ {
+ Chksum = 0;
+ for (I2CInPointer = 0;I2CInPointer < (INBYTES + 1);I2CInPointer++)
+ {
+ Chksum += I2CInBuffer[I2CInPointer];
+ }
+
+ if (Chksum == 0xFF)
+ {
+ pI2CInBuffer = (UBYTE*)&IoToAvr;
+ for (I2CInPointer = 0;I2CInPointer < INBYTES;I2CInPointer++)
+ {
+ *pI2CInBuffer = I2CInBuffer[I2CInPointer];
+ pI2CInBuffer++;
+ }
+ ArmCommFlag = TRUE;
+ }
+ I2CInState = 99;
+ }
+ }
+ break;
+
+ case 2 :
+ {
+ if (I2CInByte == CopyRightString[I2CInPointer++])
+ {
+ if (I2CInPointer >= COPYRIGHTSTRINGLENGTH)
+ {
+ ArmCopyRightValid = TRUE;
+ }
+ }
+ else
+ {
+ I2CInState = 99;
+ }
+ }
+ break;
+
+ default :
+ {
+ }
+ break;
+
+ }
+ }
+ break;
+
+ // Read command
+
+ case TWI_STX_ADR_ACK :
+ {
+ Chksum = 0;
+ pI2COutBuffer = (UBYTE*)&IoFromAvr;
+ for (I2COutPointer = 0;I2COutPointer < OUTBYTES;I2COutPointer++)
+ {
+ I2COutBuffer[I2COutPointer] = *pI2COutBuffer;
+ Chksum += *pI2COutBuffer;
+ pI2COutBuffer++;
+ }
+ I2COutBuffer[I2COutPointer] = ~Chksum;
+ I2COutPointer = 0;
+ TWDR = I2COutBuffer[I2COutPointer++];
+ }
+ break;
+
+ case TWI_STX_DATA_ACK :
+ {
+ if (I2COutPointer >= (OUTBYTES + 1))
+ {
+
+ }
+ else
+ {
+ TWDR = I2COutBuffer[I2COutPointer++];
+ }
+ }
+ break;
+ case TWI_NO_STATE:
+ {
+ TWCR |= 0x90;
+ }
+ break;
+ case TWI_BUS_ERROR:
+ {
+ UBYTE volatile Tmp;
+ Tmp = 1;
+ TWCR &= ~0x20;
+ Tmp = 0;
+ TWCR |= 0x90;
+ Tmp = 2;
+ }
+ break;
+
+ default:
+ {
+ }
+ break;
+
+ }
+ TWCR |= 0x80;
+}
+
+UBYTE ArmCommCheck(void)
+{
+ UBYTE Result;
+
+ Result = ArmCommFlag;
+ ArmCommFlag = FALSE;
+
+ return (Result);
+}
+
+
+#define ARMCOMMCheck ArmCommCheck()
+
+#define ARMCOMMCopyRight ArmCopyRightValid
+
+#define ARMCOMMExit PORTC &= ~0x30;\
+ DDRC |= 0x30;\
+ TWCR = 0x80
+
+#endif
diff --git a/ATmega48/Source/d_button.c b/ATmega48/Source/d_button.c
new file mode 100644
index 0000000..5fd3ebf
--- /dev/null
+++ b/ATmega48/Source/d_button.c
@@ -0,0 +1,40 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: d_button.c $
+//
+// Version $Revision:: 7 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_button $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_button.h"
+#include "d_button.r"
+
+
+void dButtonInit(void)
+{
+ BUTTONInit;
+}
+
+
+void dButtonUpdate(void)
+{
+ IoFromAvr.Buttons = BUTTONRead;
+}
+
+
+void dButtonExit(void)
+{
+ BUTTONExit;
+}
diff --git a/ATmega48/Source/d_button.h b/ATmega48/Source/d_button.h
new file mode 100644
index 0000000..3fc62c8
--- /dev/null
+++ b/ATmega48/Source/d_button.h
@@ -0,0 +1,27 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: d_button.h $
+//
+// Version $Revision:: 3 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_button $
+//
+// Platform C
+//
+
+
+#ifndef D_BUTTON
+#define D_BUTTON
+
+void dButtonInit(void);
+void dButtonUpdate(void);
+void dButtonExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_button.r b/ATmega48/Source/d_button.r
new file mode 100644
index 0000000..a1ab5c5
--- /dev/null
+++ b/ATmega48/Source/d_button.r
@@ -0,0 +1,68 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_button.r $
+//
+// Version $Revision:: 10 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_button $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+#pragma language=extended
+#pragma vector = INT1_vect
+__interrupt void OnInterrupt(void)
+{
+ EIMSK &= ~0x02;
+ HARDWAREReset;
+}
+
+#define BUTTONInit {\
+ EIMSK &= ~0x02;\
+ PORTD |= 0x08;\
+ DDRD &= ~0x08;\
+ PORTC &= ~0x08;\
+ DDRC &= ~0x08;\
+ DIDR0 |= 0x08;\
+ }
+
+
+UWORD ButtonRead(void)
+{
+ UWORD Result;
+
+ ADMUX = 0x43;
+ ADCSRA &= ~0x07;
+ ADCSRA |= 0x05;
+ ADCSRA |= 0x40;
+ while ((ADCSRA & 0x40));
+ ADCSRA |= 0x40;
+ while ((ADCSRA & 0x40));
+ Result = ADC;
+ if (!(PIND & 0x08))
+ {
+ Result += 0x7FF;
+ }
+ return (Result);
+}
+
+
+#define BUTTONRead ButtonRead()
+
+#define BUTTONExit {\
+ PORTD |= 0x08;\
+ DDRD &= ~0x08;\
+ EICRA &= ~0x0C;\
+ EIFR |= 0x02;\
+ EIMSK |= 0x02;\
+ }
+#endif
diff --git a/ATmega48/Source/d_input.c b/ATmega48/Source/d_input.c
new file mode 100644
index 0000000..e7d2c42
--- /dev/null
+++ b/ATmega48/Source/d_input.c
@@ -0,0 +1,52 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 16-06-05 14:32 $
+//
+// Filename $Workfile:: d_input.c $
+//
+// Version $Revision:: 3 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_input. $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_input.h"
+#include "d_input.r"
+
+
+void dInputInit(void)
+{
+ INPUTInit;
+}
+
+
+void dInputSelect(UBYTE No)
+{
+ INPUTSelect(No);
+}
+
+
+void dInputConvert(UBYTE No)
+{
+ INPUTConvert(No);
+}
+
+
+void dInputDeselect(UBYTE No)
+{
+ INPUTDeselect(No);
+}
+
+
+void dInputExit(void)
+{
+ INPUTExit;
+}
diff --git a/ATmega48/Source/d_input.h b/ATmega48/Source/d_input.h
new file mode 100644
index 0000000..15ef795
--- /dev/null
+++ b/ATmega48/Source/d_input.h
@@ -0,0 +1,29 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 16-06-05 14:32 $
+//
+// Filename $Workfile:: d_input.h $
+//
+// Version $Revision:: 3 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_input. $
+//
+// Platform C
+//
+
+
+#ifndef D_INPUT
+#define D_INPUT
+
+void dInputInit(void);
+void dInputSelect(UBYTE No);
+void dInputConvert(UBYTE No);
+void dInputDeselect(UBYTE No);
+void dInputExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_input.r b/ATmega48/Source/d_input.r
new file mode 100644
index 0000000..88f1eae
--- /dev/null
+++ b/ATmega48/Source/d_input.r
@@ -0,0 +1,209 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_input.r $
+//
+// Version $Revision:: 13 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_input. $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+// ADC input used for sensors :
+
+__flash UBYTE AdcInputNo[NOS_OF_AVR_INPUTS] =
+{
+ 7,0,1,6
+};
+
+#define ONInputPower0 {\
+ PORTD |= 0x02;\
+ DDRD |= 0x02;\
+ }
+
+#define OFFInputPower0 {\
+ PORTD &= ~0x02;\
+ DDRD |= 0x02;\
+ }
+
+#define ONInputPower1 {\
+ PORTD |= 0x01;\
+ DDRD |= 0x01;\
+ }
+
+#define OFFInputPower1 {\
+ PORTD &= ~0x01;\
+ DDRD |= 0x01;\
+ }
+
+#define ONInputPower2 {\
+ PORTB |= 0x10;\
+ DDRB |= 0x10;\
+ }
+
+#define OFFInputPower2 {\
+ PORTB &= ~0x10;\
+ DDRB |= 0x10;\
+ }
+
+#define ONInputPower3 {\
+ PORTB |= 0x20;\
+ DDRB |= 0x20;\
+ }
+
+#define OFFInputPower3 {\
+ PORTB &= ~0x20;\
+ DDRB |= 0x20;\
+ }
+
+void OnInputPower(UBYTE No)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ ONInputPower0;
+ }
+ break;
+
+ case 1 :
+ {
+ ONInputPower1;
+ }
+ break;
+
+ case 2 :
+ {
+ ONInputPower2;
+ }
+ break;
+
+ case 3 :
+ {
+ ONInputPower3;
+ }
+ break;
+
+ }
+}
+
+void OffInputPower(UBYTE No)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OFFInputPower0;
+ }
+ break;
+
+ case 1 :
+ {
+ OFFInputPower1;
+ }
+ break;
+
+ case 2 :
+ {
+ OFFInputPower2;
+ }
+ break;
+
+ case 3 :
+ {
+ OFFInputPower3;
+ }
+ break;
+
+ }
+}
+
+
+#define STARTInput {\
+ ADCSRA &= ~0x07;\
+ ADCSRA |= 0x05;\
+ ADCSRA |= 0x40;\
+ }
+
+#define SELECTInput(No) {\
+ UBYTE Mask;\
+ Mask = 1 << AdcInputNo[No];\
+ PORTC &= ~Mask;\
+ DDRC &= ~Mask;\
+ DIDR0 |= Mask;\
+ ADMUX = 0x40 + (AdcInputNo[No]);\
+ ADCSRA &= ~0x07;\
+ ADCSRA |= 0x04;\
+ ADCSRA |= 0x40;\
+ }
+
+#define BUSYInput ((ADCSRA & 0x40))
+
+#define READInput ADC
+
+#define EXITInput(No) {\
+ UBYTE Mask;\
+ Mask = 1 << AdcInputNo[No];\
+ PORTC &= ~Mask;\
+ DDRC |= Mask;\
+ }
+
+#define INPUTInit {\
+ UBYTE AdcTmp;\
+ for (AdcTmp = 0;AdcTmp < NOS_OF_AVR_INPUTS;AdcTmp++)\
+ {\
+ OffInputPower(AdcTmp);\
+ }\
+ ADCSRA = 0x94;\
+ ADCSRB = 0x00;\
+ }
+
+
+#define INPUTSelect(Inp) {\
+ SELECTInput(Inp);\
+ if ((IoToAvr.InputPower & (0x10 << Inp)))\
+ {\
+ OnInputPower(Inp);\
+ }\
+ else\
+ {\
+ OffInputPower(Inp);\
+ }\
+ }
+
+
+#define INPUTConvert(Inp) {\
+ STARTInput;\
+ while (BUSYInput);\
+ IoFromAvr.AdValue[Inp] = ADC;\
+ }
+
+
+#define INPUTDeselect(Inp) {\
+ if ((IoToAvr.InputPower & (0x01 << Inp)))\
+ {\
+ OnInputPower(Inp);\
+ }\
+ }
+
+
+#define INPUTExit {\
+ UBYTE AdcTmp;\
+ for (AdcTmp = 0;AdcTmp < NOS_OF_AVR_INPUTS;AdcTmp++)\
+ {\
+ OffInputPower(AdcTmp);\
+ EXITInput(AdcTmp);\
+ }\
+ ADCSRA = 0x10;\
+ }
+
+#endif
diff --git a/ATmega48/Source/d_output.c b/ATmega48/Source/d_output.c
new file mode 100644
index 0000000..7141ef9
--- /dev/null
+++ b/ATmega48/Source/d_output.c
@@ -0,0 +1,86 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 17-08-05 8:20 $
+//
+// Filename $Workfile:: d_output.c $
+//
+// Version $Revision:: 13 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_output $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_output.h"
+#include "d_output.r"
+
+static SBYTE Dutycycle[NOS_OF_AVR_OUTPUTS];
+static UBYTE Frequency;
+static UBYTE LastOutputMode;
+
+
+void dOutputInit(void)
+{
+ UBYTE Tmp;
+
+ OUTPUTInit;
+ for (Tmp = 0;Tmp < NOS_OF_AVR_OUTPUTS;Tmp++)
+ {
+ Dutycycle[Tmp] = 0;
+ OUTPUTWrite(Tmp,Dutycycle[Tmp]);
+ }
+ LastOutputMode = 0x00;
+}
+
+
+void dOutputUpdate(UBYTE Brake)
+{
+ UBYTE Tmp;
+ UBYTE TmpMask;
+
+ Tmp = IoToAvr.PwmFreq;
+ if (Frequency != Tmp)
+ {
+ if ((Tmp >= 1) && (Tmp <= 32))
+ {
+ Frequency = Tmp;
+ OUTPUTFreq(Frequency);
+ for (Tmp = 0;Tmp < NOS_OF_AVR_OUTPUTS;Tmp++)
+ {
+ Dutycycle[Tmp] = 0;
+ }
+ }
+ }
+
+ TmpMask = IoToAvr.OutputMode;
+
+ for (Tmp = 0;Tmp < NOS_OF_AVR_OUTPUTS;Tmp++)
+ {
+ if (Brake == TRUE)
+ {
+ TmpMask |= (0x01 << Tmp);
+ IoToAvr.PwmValue[Tmp] = 0;
+ }
+ if ((Dutycycle[Tmp] != IoToAvr.PwmValue[Tmp]) || ((LastOutputMode ^ TmpMask) & (0x01 << Tmp)))
+ {
+ OUTPUTWriteBrakeMask(TmpMask);
+ Dutycycle[Tmp] = IoToAvr.PwmValue[Tmp];
+ OUTPUTWrite(Tmp,Dutycycle[Tmp]);
+ }
+ }
+ LastOutputMode = TmpMask;
+ OUTPUTUpdate;
+}
+
+
+void dOutputExit(void)
+{
+ OUTPUTExit;
+}
diff --git a/ATmega48/Source/d_output.h b/ATmega48/Source/d_output.h
new file mode 100644
index 0000000..d130ba9
--- /dev/null
+++ b/ATmega48/Source/d_output.h
@@ -0,0 +1,27 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 16-06-05 14:32 $
+//
+// Filename $Workfile:: d_output.h $
+//
+// Version $Revision:: 4 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_output $
+//
+// Platform C
+//
+
+
+#ifndef D_OUTPUT
+#define D_OUTPUT
+
+void dOutputInit(void);
+void dOutputUpdate(UBYTE Brake);
+void dOutputExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_output.r b/ATmega48/Source/d_output.r
new file mode 100644
index 0000000..f883bde
--- /dev/null
+++ b/ATmega48/Source/d_output.r
@@ -0,0 +1,425 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_output.r $
+//
+// Version $Revision:: 17 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_output $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+// Schematics Function PORT
+// ---------- -------- ----
+// MAIN0 PB0 (PD6)
+// MAPWM OC1B PB2 (PD5)
+// MAIN1 PB3 (PD7)
+
+#define OUTPUTAFloat PORTB &= ~0x0B;\
+ DDRB |= 0x0B;\
+ TCCR1A &= ~0x30
+
+#define OUTPUTABrake PORTB |= 0x0B;\
+ DDRB |= 0x0B;\
+ TCCR1A &= ~0x30
+
+#define OUTPUTAInit OUTPUTABrake;\
+ TCCR1A = 0x01;\
+ TCCR1B = 0x09;\
+ TCNT1 = 0;\
+ OCR1B = 0;\
+ TIMSK1 = 0x00
+
+#define OUTPUTAFwdFloat(D) OUTPUTAFloat;\
+ DDRB &= ~0x01;\
+ TCCR1A |= 0x20;\
+ OCR1B = D
+
+#define OUTPUTAFwdBrake(D) OUTPUTABrake;\
+ PORTB &= ~0x08;\
+ DDRB &= ~0x08;\
+ TCCR1A |= 0x30;\
+ OCR1B = D
+
+#define OUTPUTABwdFloat(D) OUTPUTAFloat;\
+ DDRB &= ~0x08;\
+ TCCR1A |= 0x20;\
+ OCR1B = D
+
+#define OUTPUTABwdBrake(D) OUTPUTABrake;\
+ PORTB &= ~0x01;\
+ DDRB &= ~0x01;\
+ TCCR1A |= 0x30;\
+ OCR1B = D
+
+#define OUTPUTAExit OUTPUTAFloat
+
+
+
+
+
+// Schematics Function PORT
+// ---------- -------- ----
+// MBIN0 PD6 (PB0)
+// MBPWM OC1A PB1 (PB1)
+// MBIN1 PD7 (PB3)
+
+#define OUTPUTBFloat PORTD &= ~0xE0;\
+ DDRD |= 0xE0;\
+ TCCR1A &= ~0xC0
+
+#define OUTPUTBBrake PORTD |= 0xE0;\
+ DDRD |= 0xE0;\
+ TCCR1A &= ~0xC0
+
+#define OUTPUTBInit OUTPUTBBrake;\
+ TCCR1A = 0x01;\
+ TCCR1B = 0x09;\
+ TCNT1 = 0;\
+ OCR1A = 0;\
+ TIMSK1 = 0x00
+
+#define OUTPUTBFwdFloat(D) OUTPUTBFloat;\
+ DDRD &= ~0x40;\
+ TCCR1A |= 0x80;\
+ OCR1A = D
+
+#define OUTPUTBFwdBrake(D) OUTPUTBBrake;\
+ PORTD &= ~0x80;\
+ DDRD &= ~0x80;\
+ TCCR1A |= 0xC0;\
+ OCR1A = D
+
+#define OUTPUTBBwdFloat(D) OUTPUTBFloat;\
+ DDRD &= ~0x80;\
+ TCCR1A |= 0x80;\
+ OCR1A = D
+
+#define OUTPUTBBwdBrake(D) OUTPUTBBrake;\
+ PORTD &= ~0x40;\
+ DDRD &= ~0x40;\
+ TCCR1A |= 0xC0;\
+ OCR1A = D
+
+#define OUTPUTBExit OUTPUTBFloat
+
+
+
+// Schematics Function PORT
+// ---------- -------- ----
+// MCIN0 PB7 (PB7)
+// MCPWM OC0B PD5 (PB2)
+// MCIN1 PB6 (PB6)
+
+#define OUTPUTCFloat PORTB &= ~0xC4;\
+ DDRB |= 0xC4;\
+ TCCR0A &= ~0x30
+
+#define OUTPUTCBrake PORTB |= 0xC4;\
+ DDRB |= 0xC4;\
+ TCCR0A &= ~0x30
+
+#define OUTPUTCInit OUTPUTCBrake;\
+ TCCR0A = 0x03;\
+ TCCR0B = 0x01;\
+ TCNT0 = 0;\
+ OCR0B = 0;\
+ TIMSK0 = 0x00
+
+#define OUTPUTCFwdFloat(D) OUTPUTCFloat;\
+ DDRB &= ~0x80;\
+ TCCR0A |= 0x20;\
+ OCR0B = D
+
+#define OUTPUTCFwdBrake(D) OUTPUTCBrake;\
+ PORTB &= ~0x40;\
+ DDRB &= ~0x40;\
+ TCCR0A |= 0x30;\
+ OCR0B = D
+
+#define OUTPUTCBwdFloat(D) OUTPUTCFloat;\
+ DDRB &= ~0x40;\
+ TCCR0A |= 0x20;\
+ OCR0B = D
+
+#define OUTPUTCBwdBrake(D) OUTPUTCBrake;\
+ PORTB &= ~0x80;\
+ DDRB &= ~0x80;\
+ TCCR0A |= 0x30;\
+ OCR0B = D
+
+#define OUTPUTCExit OUTPUTCFloat
+
+
+
+UBYTE TopValue = 255;
+UBYTE BrakeMask;
+
+void WriteFreq(UBYTE Freq)
+{
+ if (Freq >= 4)
+ {
+ TopValue = (UBYTE)(((ULONG)OSC / 8000L) / (ULONG)Freq);
+ TCCR0B &= ~0x0F;
+ TCCR0B |= 0x0A;
+
+ TCCR1A &= ~0x03;
+ TCCR1A |= 0x02;
+ TCCR1B &= ~0x1F;
+ TCCR1B |= 0x1A;
+ }
+ else
+ {
+ TopValue = (UBYTE)(((ULONG)OSC / 64000L) / (ULONG)Freq);
+ TCCR0B &= ~0x0F;
+ TCCR0B |= 0x0B;
+
+ TCCR1A &= ~0x03;
+ TCCR1A |= 0x02;
+ TCCR1B &= ~0x1F;
+ TCCR1B |= 0x1B;
+ }
+ OCR0B = 0;
+ OCR0A = TopValue;
+ OCR1A = 0;
+ OCR1B = 0;
+ ICR1L = TopValue;
+ ICR1H = 0;
+}
+
+
+void OutputBrake(UBYTE No)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTABrake;
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBBrake;
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCBrake;
+ }
+ break;
+
+ }
+}
+
+void OutputFloat(UBYTE No)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTAFloat;
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBFloat;
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCFloat;
+ }
+ break;
+
+ }
+}
+
+void OutputFwdBrake(UBYTE No,UBYTE Pwm)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTAFwdBrake(Pwm);
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBFwdBrake(Pwm);
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCFwdBrake(Pwm);
+ }
+ break;
+
+ }
+}
+
+void OutputBwdBrake(UBYTE No,UBYTE Pwm)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTABwdBrake(Pwm);
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBBwdBrake(Pwm);
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCBwdBrake(Pwm);
+ }
+ break;
+
+ }
+}
+
+void OutputFwdFloat(UBYTE No,UBYTE Pwm)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTAFwdFloat(Pwm);
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBFwdFloat(Pwm);
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCFwdFloat(Pwm);
+ }
+ break;
+
+ }
+}
+
+void OutputBwdFloat(UBYTE No,UBYTE Pwm)
+{
+ switch (No)
+ {
+ case 0 :
+ {
+ OUTPUTABwdFloat(Pwm);
+ }
+ break;
+
+ case 1 :
+ {
+ OUTPUTBBwdFloat(Pwm);
+ }
+ break;
+
+ case 2 :
+ {
+ OUTPUTCBwdFloat(Pwm);
+ }
+ break;
+
+ }
+}
+
+void OutputWrite(UBYTE No,SBYTE Duty)
+{
+ UBYTE Pwm;
+
+ if (No < NOS_OF_AVR_OUTPUTS)
+ {
+ if (Duty < 0)
+ {
+ Pwm = (UBYTE)(0 - Duty);
+ }
+ else
+ {
+ Pwm = (UBYTE)Duty;
+ }
+ Pwm = (UBYTE)(((UWORD)Pwm * (UWORD)TopValue) / 100);
+
+
+ if ((BrakeMask & (0x01 << No)))
+ {
+ if (Duty)
+ {
+ if (Duty > 0)
+ {
+ OutputFwdBrake(No,Pwm);
+ }
+ else
+ {
+ OutputBwdBrake(No,Pwm);
+ }
+ }
+ else
+ {
+ OutputBrake(No);
+ }
+ }
+ else
+ {
+ if (Duty)
+ {
+ if (Duty > 0)
+ {
+ OutputFwdFloat(No,Pwm);
+ }
+ else
+ {
+ OutputBwdFloat(No,Pwm);
+ }
+ }
+ else
+ {
+ OutputFloat(No);
+ }
+ }
+ }
+}
+
+
+
+#define OUTPUTInit OUTPUTAInit;\
+ OUTPUTBInit;\
+ OUTPUTCInit;\
+ BrakeMask = 0xFF
+
+#define OUTPUTWriteBrakeMask(M) BrakeMask = M
+
+#define OUTPUTWrite(No,Duty) OutputWrite(No,Duty)
+
+#define OUTPUTFreq(Freq) WriteFreq(Freq)
+
+#define OUTPUTUpdate
+
+#define OUTPUTExit OUTPUTAExit;\
+ OUTPUTBExit;\
+ OUTPUTCExit
+
+#endif
diff --git a/ATmega48/Source/d_pccomm.c b/ATmega48/Source/d_pccomm.c
new file mode 100644
index 0000000..b2e3c6c
--- /dev/null
+++ b/ATmega48/Source/d_pccomm.c
@@ -0,0 +1,33 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 8-04-05 9:51 $
+//
+// Filename $Workfile:: d_pccomm.c $
+//
+// Version $Revision:: 3 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_pccomm $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_pccomm.h"
+#include "d_pccomm.r"
+
+
+void dPcCommInit(void)
+{
+ //INITPcComm;
+}
+
+void dPcCommExit(void)
+{
+ //EXITPcComm;
+}
diff --git a/ATmega48/Source/d_pccomm.h b/ATmega48/Source/d_pccomm.h
new file mode 100644
index 0000000..29ca916
--- /dev/null
+++ b/ATmega48/Source/d_pccomm.h
@@ -0,0 +1,26 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dkandlun $
+//
+// Revision date $Date:: 28-12-04 14:19 $
+//
+// Filename $Workfile:: d_pccomm.h $
+//
+// Version $Revision:: 1 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Peripheral/Firmware/Source/d_pc $
+//
+// Platform C
+//
+
+
+#ifndef D_PCCOMM
+#define D_PCCOMM
+
+void dPcCommInit(void);
+void dPcCommExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_pccomm.r b/ATmega48/Source/d_pccomm.r
new file mode 100644
index 0000000..0660ac7
--- /dev/null
+++ b/ATmega48/Source/d_pccomm.r
@@ -0,0 +1,93 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 22-02-05 11:10 $
+//
+// Filename $Workfile:: d_pccomm.r $
+//
+// Version $Revision:: 6 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_pccomm $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+#define BAUD_RATE 4800L
+
+#define RX_BUFFERSIZE (BYTES_TO_TX)
+#define TX_BUFFERSIZE (BYTES_TO_RX)
+
+UBYTE RxBuffer[RX_BUFFERSIZE];
+UBYTE RxPointer;
+
+UBYTE TxBuffer[TX_BUFFERSIZE];
+UBYTE TxPointer;
+
+#pragma language=extended
+#pragma vector = USART_RX_vect
+__interrupt void RxInterrupt(void)
+{
+ UBYTE *pBuffer;
+
+ RxBuffer[RxPointer] = UDR0;
+ RxPointer++;
+ if (RxPointer >= RX_BUFFERSIZE)
+ {
+ pBuffer = (UBYTE*)&IoToAvr;
+ for (RxPointer = 0;RxPointer < RX_BUFFERSIZE;RxPointer++)
+ {
+ *pBuffer = RxBuffer[RxPointer];
+ pBuffer++;
+ }
+ RxPointer = 0;
+ pBuffer = (UBYTE*)&IoFromAvr;
+ for (TxPointer = 0;TxPointer < TX_BUFFERSIZE;TxPointer++)
+ {
+ TxBuffer[TxPointer] = *pBuffer;
+ pBuffer++;
+ }
+ TxPointer = 0;
+ UDR0 = TxBuffer[TxPointer];
+ TxPointer++;
+ UCSR0B |= 0x40;
+ }
+}
+
+#pragma language=extended
+#pragma vector = USART_TX_vect
+__interrupt void TxInterrupt(void)
+{
+ UDR0 = TxBuffer[TxPointer];
+ TxPointer++;
+ if (TxPointer >= TX_BUFFERSIZE)
+ {
+ UCSR0B &= ~0x40;
+ TxPointer = 0;
+ RxPointer = 0;
+ }
+}
+
+#define INITPcComm {\
+ DDRD |= 0x02;\
+ DDRD &= ~0x01;\
+ UBRR0 = (UWORD)((OSC/(16 * BAUD_RATE)) - 1);\
+ UCSR0A = 0x40;\
+ UCSR0B = 0x98;\
+ UCSR0C = 0x36;\
+ RxPointer = 0;\
+ }
+
+#define EXITPcComm {\
+ UCSR0B = 0x00;\
+ PORTD &= ~0x01;\
+ DDRD |= 0x01;\
+ }
+
+
+#endif
diff --git a/ATmega48/Source/d_power.c b/ATmega48/Source/d_power.c
new file mode 100644
index 0000000..f28179a
--- /dev/null
+++ b/ATmega48/Source/d_power.c
@@ -0,0 +1,122 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_power.c $
+//
+// Version $Revision:: 7 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_power. $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_power.h"
+#include "d_power.r"
+
+
+void dPowerInit(void)
+{
+ POWERInit;
+}
+
+
+void dPowerRechargeable(UBYTE Mounted)
+{
+ if (Mounted)
+ {
+ IoFromAvr.Battery |= 0x8000;
+ }
+ else
+ {
+ IoFromAvr.Battery &= ~0x8000;
+ }
+}
+
+
+UBYTE dPowerReadOn(void)
+{
+ UBYTE Result = TRUE;
+
+ if (IoToAvr.Power == 0x5A)
+ {
+ Result = FALSE;
+ }
+
+ return (Result);
+}
+
+
+UBYTE dPowerReadBoot(void)
+{
+ UBYTE Result = FALSE;
+
+ if ((IoToAvr.Power == 0xA5) && (IoToAvr.PwmFreq == 0x5A))
+ {
+ IoToAvr.Power = 0x00;
+ IoToAvr.PwmFreq = 0x00;
+ Result = TRUE;
+ }
+
+ return (Result);
+}
+
+
+void dPowerSelect(void)
+{
+ POWERSelect;
+}
+
+
+UWORD dPowerConvert(void)
+{
+ UWORD Result;
+
+ POWERConvert(Result);
+
+ return (Result);
+}
+
+
+void dPowerDeselect(void)
+{
+ POWERDeselect;
+}
+
+
+void dPowerWriteOn(UBYTE On)
+{
+ if (On == TRUE)
+ {
+ POWEROn;
+ }
+ else
+ {
+ POWEROff;
+ }
+}
+
+
+void dPowerHigh(void)
+{
+ POWERHigh;
+}
+
+
+void dPowerFloat(void)
+{
+ POWERFloat;
+}
+
+
+void dPowerExit(void)
+{
+ POWERExit;
+}
diff --git a/ATmega48/Source/d_power.h b/ATmega48/Source/d_power.h
new file mode 100644
index 0000000..f1b5c2f
--- /dev/null
+++ b/ATmega48/Source/d_power.h
@@ -0,0 +1,35 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_power.h $
+//
+// Version $Revision:: 4 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_power. $
+//
+// Platform C
+//
+
+
+#ifndef D_POWER
+#define D_POWER
+
+void dPowerInit(void);
+void dPowerRechargeable(UBYTE Mounted);
+UBYTE dPowerReadOn(void);
+UBYTE dPowerReadBoot(void);
+void dPowerWriteOn(UBYTE On);
+void dPowerSelect(void);
+UWORD dPowerConvert(void);
+void dPowerDeselect(void);
+void dPowerHigh(void);
+void dPowerFloat(void);
+void dPowerExit(void);
+
+#endif
diff --git a/ATmega48/Source/d_power.r b/ATmega48/Source/d_power.r
new file mode 100644
index 0000000..de229a3
--- /dev/null
+++ b/ATmega48/Source/d_power.r
@@ -0,0 +1,79 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_power.r $
+//
+// Version $Revision:: 8 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_power. $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+#define POWERInit {\
+ PORTC &= ~0x04;\
+ DDRC &= ~0x04;\
+ DIDR0 |= 0x04;\
+ }
+
+#define POWEROff {\
+ PORTD &= ~0x10;\
+ DDRD |= 0x10;\
+ }
+
+#define POWEROn {\
+ PORTD |= 0x10;\
+ DDRD |= 0x10;\
+ }
+
+#define POWERSelect {\
+ PORTD |= 0x04;\
+ DDRD |= 0x04;\
+ }
+
+#define POWERConvert(V) {\
+ ADMUX = 0x42;\
+ ADCSRA &= ~0x07;\
+ ADCSRA |= 0x05;\
+ ADCSRA |= 0x40;\
+ while ((ADCSRA & 0x40));\
+ ADCSRA |= 0x40;\
+ while ((ADCSRA & 0x40));\
+ V = ADC;\
+ V &= 0x7FFF;\
+ IoFromAvr.Battery &= 0x8000;\
+ IoFromAvr.Battery |= V;\
+ }
+
+#define POWERDeselect {\
+ PORTD &= ~0x04;\
+ DDRD |= 0x04;\
+ }
+
+#define POWERHigh {\
+ PORTC |= 0x04;\
+ DDRC |= 0x04;\
+ }
+
+#define POWERFloat {\
+ PORTC &= ~0x04;\
+ DDRC &= ~0x04;\
+ }
+
+
+
+#define POWERExit {\
+ POWEROff;\
+ POWERDeselect;\
+ POWERConvert(ADC);\
+ }
+
+#endif
diff --git a/ATmega48/Source/d_timer.c b/ATmega48/Source/d_timer.c
new file mode 100644
index 0000000..94758c9
--- /dev/null
+++ b/ATmega48/Source/d_timer.c
@@ -0,0 +1,48 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 16-06-05 14:32 $
+//
+// Filename $Workfile:: d_timer.c $
+//
+// Version $Revision:: 2 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_timer. $
+//
+// Platform C
+//
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "d_timer.h"
+#include "d_timer.r"
+
+UBYTE Timer;
+
+
+void dTimerInit(void)
+{
+ TIMERInit;
+}
+
+
+void dTimerClear(void)
+{
+ Timer = TIMERRead;
+}
+
+
+UBYTE dTimerRead(void)
+{
+ return ((UBYTE)(TIMERRead - Timer));
+}
+
+
+void dTimerExit(void)
+{
+ TIMERExit;
+}
diff --git a/ATmega48/Source/d_timer.h b/ATmega48/Source/d_timer.h
new file mode 100644
index 0000000..862f4f4
--- /dev/null
+++ b/ATmega48/Source/d_timer.h
@@ -0,0 +1,30 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 16-06-05 14:32 $
+//
+// Filename $Workfile:: d_timer.h $
+//
+// Version $Revision:: 2 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_timer. $
+//
+// Platform C
+//
+
+
+#ifndef D_TIMER
+#define D_TIMER
+
+void dTimerInit(void);
+void dTimerClear(void);
+UBYTE dTimerRead(void);
+void dTimerExit(void);
+
+#define TIMER_RESOLUTION (8000000L / 256L)
+
+#endif
diff --git a/ATmega48/Source/d_timer.r b/ATmega48/Source/d_timer.r
new file mode 100644
index 0000000..9798be9
--- /dev/null
+++ b/ATmega48/Source/d_timer.r
@@ -0,0 +1,34 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: d_timer.r $
+//
+// Version $Revision:: 4 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/d_timer. $
+//
+// Platform C
+//
+
+#ifdef ATMEGAX8
+
+#define TIMERInit {\
+ TCCR2A = 0x00;\
+ TCCR2B = 0x06;\
+ TCNT2 = 0x00;\
+ }
+
+#define TIMERRead TCNT2
+
+
+#define TIMERExit {\
+ }
+
+
+#endif
diff --git a/ATmega48/Source/m_sched.c b/ATmega48/Source/m_sched.c
new file mode 100644
index 0000000..d208469
--- /dev/null
+++ b/ATmega48/Source/m_sched.c
@@ -0,0 +1,54 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 2-09-05 14:37 $
+//
+// Filename $Workfile:: m_sched.c $
+//
+// Version $Revision:: 2 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/m_sched. $
+//
+// Platform C
+//
+
+
+#define INCLUDE_OS
+
+
+#include "stdconst.h"
+#include "m_sched.h"
+#include "c_armcomm.h"
+
+
+UBYTE Run;
+
+
+void mSchedInit(void)
+{
+ Run = FALSE;
+
+ cArmCommInit();
+ Run = TRUE;
+}
+
+
+UBYTE mSchedCtrl(void)
+{
+ Run = cArmCommCtrl();
+
+ return (Run);
+}
+
+
+void mSchedExit(void)
+{
+ Run = FALSE;
+
+ cArmCommExit();
+}
+
diff --git a/ATmega48/Source/m_sched.h b/ATmega48/Source/m_sched.h
new file mode 100644
index 0000000..1dd7a09
--- /dev/null
+++ b/ATmega48/Source/m_sched.h
@@ -0,0 +1,87 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dktochpe $
+//
+// Revision date $Date:: 28-10-05 13:46 $
+//
+// Filename $Workfile:: m_sched.h $
+//
+// Version $Revision:: 15 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Ioctrl/Firmware/Source/m_sched. $
+//
+// Platform C
+//
+
+
+#define COPYRIGHTSTRING "Let's samba nxt arm in arm, (c)LEGO System A/S"
+
+#define COPYRIGHTSTRINGLENGTH 46 // Number of bytes checked in COPYRIGHTSTRING
+
+#define OSC 8000000L // Main oscillator frequency
+
+#include "..\mega48\include\atmega48.h"
+
+#define BYTES_TO_TX 8 // Number of bytes received from ARM = sizeof(IOTOAVR)
+#define BYTES_TO_RX 12 // Number of bytes transmitted to ARM = sizeof(IOFROMAVR)
+#define NOS_OF_AVR_OUTPUTS 4 // Number of motor outputs
+#define NOS_OF_AVR_INPUTS 4 // Number of a/d inputs
+
+
+typedef struct // From AVR to ARM
+{
+ UWORD AdValue[NOS_OF_AVR_INPUTS]; // Raw a/d converter values [0..1023]
+ UWORD Buttons; // Raw a/d converter value [0..1023] (Enter -> +0x07FF)
+ UWORD Battery; // Raw a/d converter value [0..1023] (rechargeable -> +0x8000)
+}IOFROMAVR;
+
+
+typedef struct // From ARM to AVR
+{
+ UBYTE Power; // Command descriped below
+ UBYTE PwmFreq; // Common pwm freq [Khz] [1..32]
+ SBYTE PwmValue[NOS_OF_AVR_OUTPUTS]; // Pwm value [%] [-100..100]
+ UBYTE OutputMode; // Bitwise Bit 0 = Motor A [0 = float, 1 = brake]
+ UBYTE InputPower; // Bitwise Bit 0 and 4 = input 1 [00 = inactive,01 = pulsed, 11 = constant]
+}IOTOAVR;
+
+/*
+ Powerdown request: Power = 0x5A
+ Samba boot request: Power = 0xA5 and PwmFreq = 0x5A
+ Copyright string: Power = 0xCC
+*/
+
+
+#ifdef INCLUDE_OS
+
+#include "..\mega48\include\atmega48.c"
+
+IOFROMAVR IoFromAvr =
+{
+ { 0,0,0,0 },
+ 0,
+ 0
+};
+
+IOTOAVR IoToAvr =
+{
+ 0,
+ 4,
+ { 0,0,0,0 },
+ 0x0F,0x0F
+};
+
+#endif
+
+extern IOTOAVR IoToAvr;
+extern IOFROMAVR IoFromAvr;
+extern UBYTE Run;
+
+
+
+
+
+
diff --git a/ATmega48/Source/stdconst.h b/ATmega48/Source/stdconst.h
new file mode 100644
index 0000000..392633e
--- /dev/null
+++ b/ATmega48/Source/stdconst.h
@@ -0,0 +1,44 @@
+//
+// Programmer
+//
+// Date init 14.12.2004
+//
+// Reviser $Author:: Dkandlun $
+//
+// Revision date $Date:: 28-12-04 14:19 $
+//
+// Filename $Workfile:: stdconst.h $
+//
+// Version $Revision:: 1 $
+//
+// Archive $Archive:: /LMS2006/Sys01/Peripheral/Firmware/Source/stdc $
+//
+// Platform C
+//
+
+
+#ifndef STDCONST
+#define STDCONST
+
+
+#define TRUE 1
+#define FALSE 0
+
+typedef unsigned char UCHAR;
+typedef unsigned short USHORT;
+typedef unsigned char UBYTE;
+typedef signed char SBYTE;
+typedef unsigned int UWORD;
+typedef signed int SWORD;
+typedef unsigned long ULONG;
+typedef signed long SLONG;
+
+typedef ULONG* PULONG;
+typedef USHORT* PUSHORT;
+typedef UCHAR* PUCHAR;
+typedef char* PSZ;
+
+#define BASETYPES
+
+
+#endif