more directories for the archive

This commit is contained in:
Andrew Tridgell 2011-09-09 12:48:34 +10:00
parent 4682634ab1
commit ef87933d63
18 changed files with 5243 additions and 0 deletions

View File

@ -0,0 +1 @@
<AVRStudio><MANAGEMENT><ProjectName>ap_ppm_encoder</ProjectName><Created>03-Dec-2009 19:19:14</Created><LastEdit>23-Jan-2010 22:43:53</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>03-Dec-2009 19:19:14</Created><Version>4</Version><Build>4, 17, 0, 655</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\ap_ppm_encoder.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET>AVR Simulator</CURRENT_TARGET><CURRENT_PART>ATmega328P.xml</CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM>Auto</COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><modules><module></module></modules><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>ap_ppm_encoder.c</SOURCEFILE><HEADERFILE>servo2ppm_settings.h</HEADERFILE><OTHERFILE>default\ap_ppm_encoder.lss</OTHERFILE><OTHERFILE>default\ap_ppm_encoder.map</OTHERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega328p</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>ap_ppm_encoder.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>0</ISDIRTY><OPTIONS/><INCDIRS/><LIBDIRS/><LIBS/><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\WinAVR-20090313\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\WinAVR-20090313\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><ProjectFiles><Files><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h</Name><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c</Name></Files></ProjectFiles><IOView><usergroups/><sort sorted="0" column="0" ordername="1" orderaddress="1" ordergroup="1"/></IOView><Files><File00000><FileId>00000</FileId><FileName>ap_ppm_encoder.c</FileName><Status>259</Status></File00000><File00001><FileId>00001</FileId><FileName>servo2ppm_settings.h</FileName><Status>1</Status></File00001></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>

View File

@ -0,0 +1 @@
<AVRWorkspace><IOSettings><CurrentRegisters/></IOSettings><part name="ATMEGA328P"/><Files><File00000 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c" Position="266 97 1157 411" LineCol="1016 8" State="Maximized"/><File00001 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h" Position="258 67 1286 518" LineCol="96 47" State="Maximized"/></Files></AVRWorkspace>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,77 @@
###############################################################################
# Makefile for the project ap_ppm_encoder
###############################################################################
## General Flags
PROJECT = ap_ppm_encoder
MCU = atmega328p
TARGET = ap_ppm_encoder.elf
CC = avr-gcc
CPP = avr-g++
## Options common to compile, link and assembly rules
COMMON = -mmcu=$(MCU)
## Compile options common for all C compilation units.
CFLAGS = $(COMMON)
CFLAGS += -Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
CFLAGS += -MD -MP -MT $(*F).o -MF dep/$(@F).d
## Assembly specific flags
ASMFLAGS = $(COMMON)
ASMFLAGS += $(CFLAGS)
ASMFLAGS += -x assembler-with-cpp -Wa,-gdwarf2
## Linker flags
LDFLAGS = $(COMMON)
LDFLAGS += -Wl,-Map=ap_ppm_encoder.map
## Intel Hex file production flags
HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
HEX_EEPROM_FLAGS = -j .eeprom
HEX_EEPROM_FLAGS += --set-section-flags=.eeprom="alloc,load"
HEX_EEPROM_FLAGS += --change-section-lma .eeprom=0 --no-change-warnings
## Objects that must be built in order to link
OBJECTS = ap_ppm_encoder.o
## Objects explicitly added by the user
LINKONLYOBJECTS =
## Build
all: $(TARGET) ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss size
## Compile
ap_ppm_encoder.o: ../ap_ppm_encoder.c
$(CC) $(INCLUDES) $(CFLAGS) -c $<
##Link
$(TARGET): $(OBJECTS)
$(CC) $(LDFLAGS) $(OBJECTS) $(LINKONLYOBJECTS) $(LIBDIRS) $(LIBS) -o $(TARGET)
%.hex: $(TARGET)
avr-objcopy -O ihex $(HEX_FLASH_FLAGS) $< $@
%.eep: $(TARGET)
-avr-objcopy $(HEX_EEPROM_FLAGS) -O ihex $< $@ || exit 0
%.lss: $(TARGET)
avr-objdump -h -S $< > $@
size: ${TARGET}
@echo
@avr-size -C --mcu=${MCU} ${TARGET}
## Clean target
.PHONY: clean
clean:
-rm -rf $(OBJECTS) ap_ppm_encoder.elf dep/* ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss ap_ppm_encoder.map
## Other dependencies
-include $(shell mkdir dep 2>/dev/null) $(wildcard dep/*)

View File

@ -0,0 +1,5 @@
:1000000001000100010001000100010001000100E8
:1000100001000100E907E907E907E907E907E9073E
:10002000E907E907E907E907E90702020202020214
:050030000202020202C1
:00000001FF

Binary file not shown.

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,419 @@
Archive member included because of file (symbol)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
ap_ppm_encoder.o (__udivmodhi4)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o (exit)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
ap_ppm_encoder.o (__do_copy_data)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
ap_ppm_encoder.o (__do_clear_bss)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
ap_ppm_encoder.o (__eerd_word)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
ap_ppm_encoder.o (__eewr_word)
Allocating common symbols
Common symbol size file
timer0 0x2 ap_ppm_encoder.o
isr_channel_pw 0x12 ap_ppm_encoder.o
Memory Configuration
Name Origin Length Attributes
text 0x00000000 0x00020000 xr
data 0x00800060 0x0000ffa0 rw !x
eeprom 0x00810000 0x00010000 rw !x
fuse 0x00820000 0x00000400 rw !x
lock 0x00830000 0x00000400 rw !x
signature 0x00840000 0x00000400 rw !x
*default* 0x00000000 0xffffffff
Linker script and memory map
Address of section .data set to 0x800100
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
LOAD ap_ppm_encoder.o
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
.hash
*(.hash)
.dynsym
*(.dynsym)
.dynstr
*(.dynstr)
.gnu.version
*(.gnu.version)
.gnu.version_d
*(.gnu.version_d)
.gnu.version_r
*(.gnu.version_r)
.rel.init
*(.rel.init)
.rela.init
*(.rela.init)
.rel.text
*(.rel.text)
*(.rel.text.*)
*(.rel.gnu.linkonce.t*)
.rela.text
*(.rela.text)
*(.rela.text.*)
*(.rela.gnu.linkonce.t*)
.rel.fini
*(.rel.fini)
.rela.fini
*(.rela.fini)
.rel.rodata
*(.rel.rodata)
*(.rel.rodata.*)
*(.rel.gnu.linkonce.r*)
.rela.rodata
*(.rela.rodata)
*(.rela.rodata.*)
*(.rela.gnu.linkonce.r*)
.rel.data
*(.rel.data)
*(.rel.data.*)
*(.rel.gnu.linkonce.d*)
.rela.data
*(.rela.data)
*(.rela.data.*)
*(.rela.gnu.linkonce.d*)
.rel.ctors
*(.rel.ctors)
.rela.ctors
*(.rela.ctors)
.rel.dtors
*(.rel.dtors)
.rela.dtors
*(.rela.dtors)
.rel.got
*(.rel.got)
.rela.got
*(.rela.got)
.rel.bss
*(.rel.bss)
.rela.bss
*(.rela.bss)
.rel.plt
*(.rel.plt)
.rela.plt
*(.rela.plt)
.text 0x00000000 0xc1e
*(.vectors)
.vectors 0x00000000 0x68 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000000 __vectors
0x00000000 __vector_default
*(.vectors)
*(.progmem.gcc*)
*(.progmem*)
0x00000068 . = ALIGN (0x2)
0x00000068 __trampolines_start = .
*(.trampolines)
.trampolines 0x00000068 0x0 linker stubs
*(.trampolines*)
0x00000068 __trampolines_end = .
*(.jumptables)
*(.jumptables*)
*(.lowtext)
*(.lowtext*)
0x00000068 __ctors_start = .
*(.ctors)
0x00000068 __ctors_end = .
0x00000068 __dtors_start = .
*(.dtors)
0x00000068 __dtors_end = .
SORT(*)(.ctors)
SORT(*)(.dtors)
*(.init0)
.init0 0x00000068 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000068 __init
*(.init0)
*(.init1)
*(.init1)
*(.init2)
.init2 0x00000068 0xc c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init2)
*(.init3)
*(.init3)
*(.init4)
.init4 0x00000074 0x16 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
0x00000074 __do_copy_data
.init4 0x0000008a 0x10 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x0000008a __do_clear_bss
*(.init4)
*(.init5)
*(.init5)
*(.init6)
*(.init6)
*(.init7)
*(.init7)
*(.init8)
*(.init8)
*(.init9)
.init9 0x0000009a 0x8 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init9)
*(.text)
.text 0x000000a2 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x000000a2 __vector_22
0x000000a2 __vector_1
0x000000a2 __vector_24
0x000000a2 __bad_interrupt
0x000000a2 __vector_6
0x000000a2 __vector_3
0x000000a2 __vector_23
0x000000a2 __vector_25
0x000000a2 __vector_11
0x000000a2 __vector_13
0x000000a2 __vector_17
0x000000a2 __vector_19
0x000000a2 __vector_7
0x000000a2 __vector_4
0x000000a2 __vector_9
0x000000a2 __vector_2
0x000000a2 __vector_21
0x000000a2 __vector_15
0x000000a2 __vector_8
0x000000a2 __vector_14
0x000000a2 __vector_10
0x000000a2 __vector_18
0x000000a2 __vector_20
.text 0x000000a6 0xaf6 ap_ppm_encoder.o
0x0000038a load_failsafe_values
0x00000428 __vector_12
0x00000528 check_for_setup_mode
0x0000047e __vector_5
0x0000026c get_channel_pw
0x000004ca write_default_values_to_eeprom
0x000008ae main
0x000001d6 detect_connected_channels
0x000000d0 initialize_mcu
0x0000072e load_values_from_eeprom
0x000002fe wait_for_rx
0x000003e2 mux_control
0x00000406 __vector_16
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.text 0x00000b9c 0x2c c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
0x00000b9c __eerd_word
.text 0x00000bc8 0x2a c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
0x00000bc8 __eewr_word
0x00000bf2 . = ALIGN (0x2)
*(.text.*)
.text.libgcc 0x00000bf2 0x28 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
0x00000bf2 __udivmodhi4
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x00000c1a . = ALIGN (0x2)
*(.fini9)
.fini9 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
0x00000c1a exit
0x00000c1a _exit
*(.fini9)
*(.fini8)
*(.fini8)
*(.fini7)
*(.fini7)
*(.fini6)
*(.fini6)
*(.fini5)
*(.fini5)
*(.fini4)
*(.fini4)
*(.fini3)
*(.fini3)
*(.fini2)
*(.fini2)
*(.fini1)
*(.fini1)
*(.fini0)
.fini0 0x00000c1a 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
*(.fini0)
0x00000c1e _etext = .
.data 0x00800100 0x14 load address 0x00000c1e
0x00800100 PROVIDE (__data_start, .)
*(.data)
.data 0x00800100 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.data 0x00800100 0x13 ap_ppm_encoder.o
0x00800112 rc_lost_channel
0x00800100 version_info
0x00800110 ppm_off_threshold
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.data*)
*(.rodata)
*(.rodata*)
*(.gnu.linkonce.d*)
0x00800114 . = ALIGN (0x2)
*fill* 0x00800113 0x1 00
0x00800114 _edata = .
0x00800114 PROVIDE (__data_end, .)
.bss 0x00800114 0x1c
0x00800114 PROVIDE (__bss_start, .)
*(.bss)
.bss 0x00800114 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.bss 0x00800114 0x8 ap_ppm_encoder.o
0x00800119 channel_mask
0x0080011a isr_timer0
0x00800115 isr_channel_number
0x00800118 channels_in_use
0x00800114 pin_interrupt_detected
0x00800116 isr_timer0_16
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.bss*)
*(COMMON)
COMMON 0x0080011c 0x14 ap_ppm_encoder.o
0x0080011c timer0
0x0080011e isr_channel_pw
0x00800130 PROVIDE (__bss_end, .)
0x00000c1e __data_load_start = LOADADDR (.data)
0x00000c32 __data_load_end = (__data_load_start + SIZEOF (.data))
.noinit 0x00800130 0x0
0x00800130 PROVIDE (__noinit_start, .)
*(.noinit*)
0x00800130 PROVIDE (__noinit_end, .)
0x00800130 _end = .
0x00800130 PROVIDE (__heap_start, .)
.eeprom 0x00810000 0x35
*(.eeprom*)
.eeprom 0x00810000 0x35 ap_ppm_encoder.o
0x00810014 ppm_off_threshold_e
0x00810000 dummy_int
0x0081002a rc_lost_channel_e
0x00810035 __eeprom_end = .
.fuse
*(.fuse)
*(.lfuse)
*(.hfuse)
*(.efuse)
.lock
*(.lock*)
.signature
*(.signature*)
.stab
*(.stab)
.stabstr
*(.stabstr)
.stab.excl
*(.stab.excl)
.stab.exclstr
*(.stab.exclstr)
.stab.index
*(.stab.index)
.stab.indexstr
*(.stab.indexstr)
.comment
*(.comment)
.debug
*(.debug)
.line
*(.line)
.debug_srcinfo
*(.debug_srcinfo)
.debug_sfnames
*(.debug_sfnames)
.debug_aranges 0x00000000 0x20
*(.debug_aranges)
.debug_aranges
0x00000000 0x20 ap_ppm_encoder.o
.debug_pubnames
0x00000000 0x22c
*(.debug_pubnames)
.debug_pubnames
0x00000000 0x22c ap_ppm_encoder.o
.debug_info 0x00000000 0x914
*(.debug_info)
.debug_info 0x00000000 0x914 ap_ppm_encoder.o
*(.gnu.linkonce.wi.*)
.debug_abbrev 0x00000000 0x262
*(.debug_abbrev)
.debug_abbrev 0x00000000 0x262 ap_ppm_encoder.o
.debug_line 0x00000000 0xc94
*(.debug_line)
.debug_line 0x00000000 0xc94 ap_ppm_encoder.o
.debug_frame 0x00000000 0x100
*(.debug_frame)
.debug_frame 0x00000000 0x100 ap_ppm_encoder.o
.debug_str 0x00000000 0x43c
*(.debug_str)
.debug_str 0x00000000 0x43c ap_ppm_encoder.o
0x4ac (size before relaxing)
.debug_loc 0x00000000 0x3b4
*(.debug_loc)
.debug_loc 0x00000000 0x3b4 ap_ppm_encoder.o
.debug_macinfo
*(.debug_macinfo)
OUTPUT(ap_ppm_encoder.elf elf32-avr)
LOAD linker stubs
.debug_ranges 0x00000000 0x18
.debug_ranges 0x00000000 0x18 ap_ppm_encoder.o

View File

@ -0,0 +1,46 @@
ap_ppm_encoder.o: ../ap_ppm_encoder.c \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h \
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h \
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h \
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h \
../servo2ppm_settings.h
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h:
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h:
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h:
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h:
../servo2ppm_settings.h:

View File

@ -0,0 +1,17 @@
@echo *********************************
@echo Visit DIYdrones.com!
@echo This Bat is for PPM_encoder!
@echo *********************************
@echo Press enter to do some Magic!
pause
:A
@echo Programming Arduino...
"C:\Program Files\Atmel\AVR Tools\STK500\Stk500.exe" -cUSB -dATmega328P -fD9E2 -EFD -FD9E2 -GFD -e -ifap_ppm_encoder.hex -pf -lCF -LCF
@echo ****************************************************************
@echo Jordi: CHECK FOR PROBLEMS ABOVE before closing this window!
@echo Press enter to do the Magic again!
@echo ****************************************************************
pause
Goto A

View File

@ -0,0 +1,128 @@
/*********************************************************************************************************
Title : header file for the rc ppm encoder (servo2ppm_settings.h)
Author: Chris Efstathiou
E-mail: hendrix at vivodinet dot gr
Homepage: ........................
Date: 03/Aug/2009
Compiler: AVR-GCC with AVR-AS
MCU type: ATmega168
Comments: This software is FREE. Use it at your own risk.
*********************************************************************************************************/
#ifndef SERVO2PPM_SETTINGS_H
#define SERVO2PPM_SETTINGS_H
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK START */
/********************************************************************************************************/
/*
The cpu frequency is defined in the makefile, the below definition is used only if the cpu frequency
is not defined in the makefile.
*/
#ifndef F_CPU
#define F_CPU 8000000UL /* CPU CLOCK FREQUENCY */
#endif
/*
Those values are the failsafe servo values and the values for the non used channels
If for example you leave unconnected channel 7, the servo pulse of channel 7 in the PPM train
will be the failsafe value set below as "RC_FAILSAFE_CHANNEL_7" thus 1000 microseconds.
*/
#define RC_FAILSAFE_CHANNEL_1 1500UL
#define RC_FAILSAFE_CHANNEL_2 1500UL
#define RC_FAILSAFE_CHANNEL_3 1000UL
#define RC_FAILSAFE_CHANNEL_4 1500UL
#define RC_FAILSAFE_CHANNEL_5 1000UL
#define RC_FAILSAFE_CHANNEL_6 1000UL
#define RC_FAILSAFE_CHANNEL_7 1000UL
#define RC_FAILSAFE_CHANNEL_8 1000UL
/*
When signal is lost 1= ppm waveform remain on with failsafe values, 0= ppm waveform is off
For use with Paparazzi use "0", the autopilot has it's own failsafe values when PPM signal is lost.
The above failsafe values will kick in only if the servo inputs are lost which cannot happen with
a receiver with dsp processing that provides "hold" or "failsafe" features.
If the receiver only provides "hold" on the last good servo signals received it is not suitable
for use with the Paparazzi autopilot as it will prohibit the autopilot entering the "AUTO2" or "HOME" mode.
If you use a receiver with failsafe ability then remember to set the failsafe value of the receiver
to 2000 microseconds for the "MODE" channel so the autopilot can go to "AUTO2" or "HOME" mode when the receiver
loose the tx signal. The servo signals on receivers like PCM, IPD and any receiver with servo hold AND failsafe
will not stop outputing servo pulses thus the encoder will never stop producing a PPM pulse train
except if the throttle channel is used as an indication by setting the "RC_LOST_CHANNEL" to a value above 0.
If you use the throttle channel as an indication that the TX signal is lost then:
RC_USE_FAILSAFE set to 0 means that the ppm output will be shut down and if you set
RC_USE_FAILSAFE to 1 the ppm output will NOT shut down but it will now output the failsafe values
defined above.
*/
#define RC_USE_FAILSAFE 1
/*
The channel number (1,2,3...7,8) that will be used as a receiver ready indicator.
If set above 0 then this channel should be always connected otherwise
the PPM output will not be enabled as the ppm encoder will wait for ever for this channel
to produce a valid servo pulse.
If 0 then the first connected channel going from channel 1 to 8 will be used, in other words
which ever connected channel comes on first it will indicate that the receiver is operational.
The detection of all connected channels is independent of this setting, this channel
is used as an indication that the receiver is up and running only.
Valid only if greater than 0.
*/
#define RC_RX_READY_CHANNEL 0 /* 0 = No channel will be exclusively checked. */
/*
The default value for the rc signal lost indicator channel and it's threshold value in microseconds .
If the value is above 1500 microseconds then when the signal lost indicator channel servo pulse exceeds
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the value is below 1500 microseconds then when the signal lost indicator channel servo pulse gets lower than
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the RC_USE_FAILSAFE is set to 1 then the ppm output will not stop producing pulses but now
the ppm wavetrain will contain the failsafe values defined in the beginning of this file.
Valid only if RC_LOST_CHANNEL > 0
*/
#define RC_LOST_CHANNEL 3 /* Defaul is the throttle channel. You can use any channel. */
#define RC_LOST_THRESHOLD 2025 /* Any value below 1300 or above 1700 microseconds. */
#define RC_PPM_GEN_CHANNELS 8 /* How many channels the PPM output frame will have. */
#define RC_PPM_OUTPUT_TYPE 0 /* 1 = POSITIVE PULSE, 0= NEGATIVE PULSE */
#define RC_MUX_CHANNEL 8 /*Jordi: Channel that will control the MUX */
#define RC_MUX_REVERSE 0 /*Jordi: Inverted the MUX output (NOT), 0 = normal, 1 = Rev*/
#define RC_MUX_MIN 0 /*Jordi: the min point */
#define RC_MUX_MAX 1250 /*Jordi: the max point */
/*
0 = the reset period is constant but the total PPM frame period is varying.
1 = the reset period is varying but the total PPM frame period is constant (always 23,5 ms for example).
*/
#define RC_CONSTANT_PPM_FRAME_TIME 0
/********************************************************************************************************/
/*
D A N G E R
The below settings are good for almost every situation and probably you don't need to change them.
Be carefull because you can cause a lot of problems if you change anything without knowing
exactly what you are doing.
*/
#define RC_SERVO_MIN_PW 800UL /* in microseconds */
#define RC_SERVO_CENTER_PW 1500UL /* in microseconds */
#define RC_SERVO_MAX_PW 2200UL /* in microseconds */
#define RC_PPM_CHANNEL_SYNC_PW 300UL /* the width of the PPM channel sync pulse in microseconds. */
#define RC_PPM_RESET_PW 0UL /* Min reset time in microseconds(ie. 7500UL), 0=AUTO */
#define RC_PPM_FRAME_LENGTH_MS 0UL /* Max PPM frame period in microseconds(ie. 23500UL), 0=AUTO */
#define RC_MAX_TIMEOUT 30000UL /* in microseconds, max ~65000 @ 8 mHZ, ~32000 @ 16 Mhz */
#define RC_MAX_BAD_PPM_FRAMES 4 /* Max consecutive bad servo pulse samples before failsafe */
#define RC_LED_FREQUENCY 5UL /* In Hertz, not accurate, min=1, max=you will get a warning */
#define RC_THROTTLE_CH_OFFSET_PW 25 /* in microseconds. */
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK END */
/********************************************************************************************************/
#endif //#ifndef SERVO2PPM_SETTINGS_H

View File

@ -0,0 +1,105 @@
void writePoints()
{
int mem;
struct Location loc;
for (byte i = 0; i < waypoint_total; i++){
loc.id = (uint8_t) mission[i][0];
loc.options = (uint8_t) mission[i][1];
loc.p1 = (uint8_t) mission[i][2];
loc.alt = (long)(mission[i][3] * 100);
loc.lat = (long)(mission[i][4] * t7);
loc.lng = (long)(mission[i][5] * t7);
switch(loc.id){
case MAV_CMD_NAV_WAYPOINT:
//loc.p1 = (byte)mission[i][4];// wp_radius
//loc.p1 = WP_RADIUS;
break;
case MAV_CMD_CONDITION_YAW:
loc.alt = (long)mission[i][3]; // speed
loc.lat = (long)mission[i][4]; // rotation direction
loc.lng = (long)mission[i][5]; // target yaw in deg
break;
}
set_wp_with_index(loc,(i+1));
/*
Serial.print((i+1),DEC);
Serial.print(": ");
Serial.print(loc.id,DEC);
Serial.print(", ");
Serial.print(loc.p1,DEC);
Serial.print(", ");
Serial.print(loc.alt,DEC);
Serial.print(", ");
Serial.print(loc.lat,DEC);
Serial.print(", ");
Serial.println(loc.lng,DEC);
*/
}
}
struct Location get_wp_with_index(int i)
{
struct Location temp;
long mem;
// Find out proper location in memory by using the start_byte position + the index
// --------------------------------------------------------------------------------
if (i > waypoint_total) {
temp.id = CMD_BLANK;
}else{
// read WP position
mem = (WP_START_BYTE) + (i * WP_SIZE);
temp.id = eeprom_read_byte((uint8_t*)mem);
mem++;
temp.options = eeprom_read_byte((uint8_t*)mem);
mem++;
temp.p1 = eeprom_read_byte((uint8_t*)mem);
mem++;
temp.alt = (long)eeprom_read_dword((uint32_t*)mem); // alt is stored in CM!
mem += 4;
temp.lat = (long)eeprom_read_dword((uint32_t*)mem);
mem += 4;
temp.lng = (long)eeprom_read_dword((uint32_t*)mem);
}
return temp;
}
void set_wp_with_index(struct Location temp, int i)
{
i = constrain(i, 0, waypoint_total.get());
uint32_t mem = WP_START_BYTE + (i * WP_SIZE);
eeprom_write_byte((uint8_t *) mem, temp.id);
mem++;
eeprom_write_byte((uint8_t *) mem, temp.options);
mem++;
eeprom_write_byte((uint8_t *) mem, temp.p1);
mem++;
eeprom_write_dword((uint32_t *) mem, temp.alt); // alt is stored in CM!
mem += 4;
eeprom_write_dword((uint32_t *) mem, temp.lat);
mem += 4;
eeprom_write_dword((uint32_t *) mem, temp.lng);
}

View File

@ -0,0 +1,108 @@
/*
Arducopter 2 Waypoint writer
Use this release to manually upload waypoints
*/
#include "defines.h"
#include <FastSerial.h>
#include <AP_Common.h>
#include <GCS_MAVLink.h> // MAVLink GCS definitions
FastSerialPort0(Serial); // FTDI/console
// EEPROM addresses
#define EEPROM_MAX_ADDR 4096
// parameters get the first 1KiB of EEPROM, remainder is for waypoints
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
#define WP_SIZE 15
// you can keep your missions stored here, just uncommment the mission to load: (only 1 at a time.)
//#include "mission_example.h"
#include "sparkfun.h"
//#include "takeoff.h"
//#include "SFO_T3.h"
//#include "SFO_landMe.h"
//#include "Basic_mission_example.h"
const long t7 = 10000000; // used to scale GPS values for EEPROM storage
byte yaw_tracking = TRACK_NONE; // no tracking, point at next wp, or at a target
#define k_param_RTL_altitude 163
#define k_param_waypoint_total 221
#define k_param_waypoint_radius 224
AP_Int16 RTL_altitude ((int8_t)9, k_param_RTL_altitude, NULL);
AP_Int8 waypoint_total ((int8_t)0, k_param_waypoint_total, NULL);
AP_Int8 waypoint_radius ((int8_t)WP_RADIUS, k_param_waypoint_radius, NULL);
// You DON'T need to edit below this line
// ----------------------------------
#include <avr/io.h>
#include <avr/eeprom.h>
void setup()
{
Serial.begin(38400);
delay(1000);
Serial.println("\nACM Waypoint writer 1.0.3 Public Alpha \n\n");
Serial.printf("Test: %d\n", (int)MAV_CMD_NAV_LAND);
//*
// number of waypoints, add 1 for home
waypoint_total.set_and_save((sizeof(mission) / 24));
waypoint_radius.set_and_save(WP_RADIUS);
RTL_altitude.set_and_save(ALT_TO_HOLD * 100);
writePoints(); // saves Waypoint Array
delay(1000);
if(RTL_altitude < 0){
Serial.print("Hold current altitude above home after RTL.\n");
}else{
Serial.printf("Hold this altitude over home: %ld meters\n", (long)RTL_altitude.get());
}
Serial.printf("WP Radius: %ld meters\n", (long)RTL_altitude.get());
Serial.printf("WP Radius: %d meters\n", (int)waypoint_radius.get());
Serial.printf("total # of commands: %d\n", (int)waypoint_total.get());
report_wp(255);
//*/
}
void loop()
{
}
void report_wp(byte index)
{
if(index == 255){
for(byte i = 0; i <= waypoint_total; i++){
struct Location temp = get_wp_with_index(i);
print_wp(&temp, i);
}
}else{
struct Location temp = get_wp_with_index(index);
print_wp(&temp, index);
}
}
void print_wp(struct Location *cmd, byte index)
{
Serial.printf_P(PSTR("command #: %d \tid:%d\top:%d\tp1:%d\tp2:%ld\tp3:%ld\tp4:%ld \n"),
(int)index,
(int)cmd->id,
(int)cmd->options,
(int)cmd->p1,
cmd->alt,
cmd->lat,
cmd->lng);
}

View File

@ -0,0 +1,298 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// ACM:
// Motors
#define RIGHT CH_1
#define LEFT CH_2
#define FRONT CH_3
#define BACK CH_4
#define RIGHTFRONT CH_7
#define LEFTBACK CH_8
#define MAX_SERVO_OUTPUT 2700
// active altitude sensor
// ----------------------
#define SONAR 0
#define BARO 1
// Frame types
#define PLUS_FRAME 0
#define X_FRAME 1
#define TRI_FRAME 2
#define HEXAX_FRAME 3
#define Y6_FRAME 4
#define HEXAP_FRAME 5
// Internal defines, don't edit and expect things to work
// -------------------------------------------------------
#define TRUE 1
#define FALSE 0
#define ToRad(x) (x*0.01745329252) // *pi/180
#define ToDeg(x) (x*57.2957795131) // *180/pi
#define DEBUG 0
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
#define T6 1000000
#define T7 10000000
// GPS type codes - use the names, not the numbers
#define GPS_PROTOCOL_NONE -1
#define GPS_PROTOCOL_NMEA 0
#define GPS_PROTOCOL_SIRF 1
#define GPS_PROTOCOL_UBLOX 2
#define GPS_PROTOCOL_IMU 3
#define GPS_PROTOCOL_MTK 4
#define GPS_PROTOCOL_HIL 5
#define GPS_PROTOCOL_MTK16 6
// Radio channels
// Note channels are from 0!
//
// XXX these should be CH_n defines from RC.h at some point.
#define CH_1 0
#define CH_2 1
#define CH_3 2
#define CH_4 3
#define CH_5 4
#define CH_6 5
#define CH_7 6
#define CH_8 7
#define CH_ROLL CH_1
#define CH_PITCH CH_2
#define CH_THROTTLE CH_3
#define CH_RUDDER CH_4
#define CH_YAW CH_4
// HIL enumerations
#define HIL_PROTOCOL_XPLANE 1
#define HIL_PROTOCOL_MAVLINK 2
#define HIL_MODE_DISABLED 0
#define HIL_MODE_ATTITUDE 1
#define HIL_MODE_SENSORS 2
// GCS enumeration
#define GCS_PROTOCOL_STANDARD 0 // standard APM protocol
#define GCS_PROTOCOL_LEGACY 1 // legacy ArduPilot protocol
#define GCS_PROTOCOL_XPLANE 2 // X-Plane HIL simulation
#define GCS_PROTOCOL_DEBUGTERMINAL 3 //Human-readable debug interface for use with a dumb terminal
#define GCS_PROTOCOL_MAVLINK 4 // binary protocol for qgroundcontrol
#define GCS_PROTOCOL_NONE -1 // No GCS output
// Auto Pilot modes
// ----------------
#define STABILIZE 0 // hold level position
#define ACRO 1 // rate control
#define ALT_HOLD 2 // AUTO control
#define SIMPLE 3 //
#define AUTO 4 // AUTO control
#define GCS_AUTO 5 // AUTO control
#define LOITER 6 // Hold a single location
#define RTL 7 // AUTO control
#define NUM_MODES 8
// YAW debug
// ---------
#define YAW_HOLD 0
#define YAW_BRAKE 1
#define YAW_RATE 2
// CH_6 Tuning
// -----------
#define CH6_NONE 0
#define CH6_STABLIZE_KP 1
#define CH6_STABLIZE_KD 2
#define CH6_BARO_KP 3
#define CH6_BARO_KD 4
#define CH6_SONAR_KP 5
#define CH6_SONAR_KD 6
#define CH6_Y6_SCALING 7
// nav byte mask
// -------------
#define NAV_LOCATION 1
#define NAV_ALTITUDE 2
#define NAV_DELAY 4
// Commands - Note that APM now uses a subset of the MAVLink protocol commands. See enum MAV_CMD in the GCS_Mavlink library
#define CMD_BLANK 0 // there is no command stored in the mem location requested
#define NO_COMMAND 0
// Nav Yaw Tracking
#define TRACK_NONE 1
#define TRACK_NEXT_WP 2
#define TRACK_TARGET_WP 4
// Waypoint options
#define WP_OPTION_ALT_RELATIVE 1
#define WP_OPTION_ALT_CHANGE 2
#define WP_OPTION_YAW 4
#define WP_OPTION_ALT_REQUIRED 8
#define WP_OPTION_RELATIVE 16
//#define WP_OPTION_ 32
//#define WP_OPTION_ 64
#define WP_OPTION_NEXT_CMD 128
//repeating events
#define NO_REPEAT 0
#define CH_5_TOGGLE 1
#define CH_6_TOGGLE 2
#define CH_7_TOGGLE 3
#define CH_8_TOGGLE 4
#define RELAY_TOGGLE 5
#define STOP_REPEAT 10
//#define MAV_CMD_CONDITION_YAW 23
// GCS Message ID's
#define MSG_ACKNOWLEDGE 0x00
#define MSG_HEARTBEAT 0x01
#define MSG_ATTITUDE 0x02
#define MSG_LOCATION 0x03
#define MSG_PRESSURE 0x04
#define MSG_STATUS_TEXT 0x05
#define MSG_PERF_REPORT 0x06
#define MSG_MODE_CHANGE 0x07 //This is different than HEARTBEAT because it occurs only when the mode is actually changed
#define MSG_VERSION_REQUEST 0x08
#define MSG_VERSION 0x09
#define MSG_EXTENDED_STATUS 0x0a
#define MSG_CPU_LOAD 0x0b
#define MSG_COMMAND_REQUEST 0x20
#define MSG_COMMAND_UPLOAD 0x21
#define MSG_COMMAND_LIST 0x22
#define MSG_COMMAND_MODE_CHANGE 0x23
#define MSG_CURRENT_WAYPOINT 0x24
#define MSG_VALUE_REQUEST 0x30
#define MSG_VALUE_SET 0x31
#define MSG_VALUE 0x32
#define MSG_PID_REQUEST 0x40
#define MSG_PID_SET 0x41
#define MSG_PID 0x42
#define MSG_VFR_HUD 0x4a
#define MSG_TRIM_STARTUP 0x50
#define MSG_TRIM_MIN 0x51
#define MSG_TRIM_MAX 0x52
#define MSG_RADIO_OUT 0x53
#define MSG_RADIO_IN 0x54
#define MSG_RAW_IMU 0x60
#define MSG_GPS_STATUS 0x61
#define MSG_GPS_RAW 0x62
#define MSG_SERVO_OUT 0x70
#define MSG_PIN_REQUEST 0x80
#define MSG_PIN_SET 0x81
#define MSG_DATAFLASH_REQUEST 0x90
#define MSG_DATAFLASH_SET 0x91
#define MSG_EEPROM_REQUEST 0xa0
#define MSG_EEPROM_SET 0xa1
#define MSG_POSITION_CORRECT 0xb0
#define MSG_ATTITUDE_CORRECT 0xb1
#define MSG_POSITION_SET 0xb2
#define MSG_ATTITUDE_SET 0xb3
#define MSG_LOCAL_LOCATION 0xb4
#define SEVERITY_LOW 1
#define SEVERITY_MEDIUM 2
#define SEVERITY_HIGH 3
#define SEVERITY_CRITICAL 4
// Logging parameters
#define LOG_INDEX_MSG 0xF0
#define LOG_ATTITUDE_MSG 0x01
#define LOG_GPS_MSG 0x02
#define LOG_MODE_MSG 0X03
#define LOG_CONTROL_TUNING_MSG 0X04
#define LOG_NAV_TUNING_MSG 0X05
#define LOG_PERFORMANCE_MSG 0X06
#define LOG_RAW_MSG 0x07
#define LOG_CMD_MSG 0x08
#define LOG_CURRENT_MSG 0x09
#define LOG_STARTUP_MSG 0x0A
#define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01
#define MAX_NUM_LOGS 50
#define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1)
#define MASK_LOG_GPS (1<<2)
#define MASK_LOG_PM (1<<3)
#define MASK_LOG_CTUN (1<<4)
#define MASK_LOG_NTUN (1<<5)
#define MASK_LOG_MODE (1<<6)
#define MASK_LOG_RAW (1<<7)
#define MASK_LOG_CMD (1<<8)
#define MASK_LOG_CURRENT (1<<9)
#define MASK_LOG_SET_DEFAULTS (1<<15)
// Waypoint Modes
// ----------------
#define ABS_WP 0
#define REL_WP 1
// Command Queues
// ---------------
#define COMMAND_MUST 0
#define COMMAND_MAY 1
#define COMMAND_NOW 2
// Events
// ------
#define EVENT_WILL_REACH_WAYPOINT 1
#define EVENT_SET_NEW_WAYPOINT_INDEX 2
#define EVENT_LOADED_WAYPOINT 3
#define EVENT_LOOP 4
// Climb rate calculations
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
#define CURRENT_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*CURR_VOLT_DIV_RATIO
#define CURRENT_AMPS(x) (x*(INPUT_VOLTAGE/1024.0))*CURR_AMP_DIV_RATIO
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
#define BATTERY_PIN2 1
#define BATTERY_PIN3 2
#define BATTERY_PIN4 3
#define VOLTAGE_PIN_0 0 // These are the pins for current sensor: voltage
#define CURRENT_PIN_1 1 // and current
#define RELAY_PIN 47
// sonar
#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters
// Hardware Parameters
#define SLIDE_SWITCH_PIN 40
#define PUSHBUTTON_PIN 41
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
#define B_LED_PIN 36
#define C_LED_PIN 35
// EEPROM addresses
#define EEPROM_MAX_ADDR 4096
// parameters get the first 1KiB of EEPROM, remainder is for waypoints
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
#define WP_SIZE 15
#define ONBOARD_PARAM_NAME_LENGTH 15
#define MAX_WAYPOINTS ((EEPROM_MAX_ADDR - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe

View File

@ -0,0 +1,15 @@
// Mission example:
#define WP_RADIUS 3 // What is the minimum distance to reach a waypoint?
#define ALT_TO_HOLD -1 // Altitude to hold above home in meters
// Enter -1 to maintain current altitude when returning to home
// The mission:
float mission[][5] = {
{MAV_CMD_NAV_TAKEOFF, 0, 6, 0, 0}, // pitch 20, Altitude meters
{MAV_CMD_NAV_WAYPOINT, 0, 6, 37.776849, -122.405752}, // go to waypoint
{MAV_CMD_CONDITION_YAW, 180, 5, 1, 1}, // 180°, 5 seconds, clockwise, relative
{MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0, 0}, // no options for RTL
{MAV_CMD_NAV_LAND, 0, 0, 0, 0}, //
};

View File

@ -0,0 +1,35 @@
// Mission example:
#define WP_RADIUS 3 // What is the minimum distance to reach a waypoint?
#define ALT_TO_HOLD -1 // Altitude to hold above home in meters
// Enter -1 to maintain current altitude when returning to home
// The mission:
float mission[][6] = {
// CMD options P1 Alt Lat Long
{MAV_CMD_NAV_TAKEOFF, 0, 0, 3.2, 0, 0}, // 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.2, 37.716899, -122.381898}, // 2 turn 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.2, 37.717475, -122.381394}, // 3 turn 2
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.2, 37.717149, -122.380819}, // 4 turn 3
{MAV_CMD_NAV_WAYPOINT, 0, 2, 3.2, 37.716592, -122.381358}, // 5 turn 4 with delay
{MAV_CMD_NAV_WAYPOINT, 0, 5, 3.2, 37.716752, -122.381632}, // 6 Land WP with delay
{MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}, // 7 LAND!
};
/*
command #: 0 id:16 op:0 p1:0 p2:5007 p3:377659180 p4:-1224329500
command #: 1 id:22 op:0 p1:0 p2:220 p3:0 p4:0
command #: 2 id:16 op:0 p1:0 p2:220 p3:377168992 p4:-1223819008
command #: 3 id:16 op:0 p1:0 p2:220 p3:377174752 p4:-1223813888
command #: 4 id:16 op:0 p1:0 p2:220 p3:377171488 p4:-1223808256
command #: 5 id:16 op:0 p1:2 p2:220 p3:377165920 p4:-1223813504
command #: 6 id:16 op:0 p1:5 p2:220 p3:377167520 p4:-1223816320
command #: 7 id:21 op:0 p1:0 p2:0 p3:0 p4:0
*/
/*
Sparkfun
*/

View File

@ -0,0 +1,53 @@
// Mission example:
#define WP_RADIUS 5 // What is the minimum distance to reach a waypoint?
#define ALT_TO_HOLD -1 // Altitude to hold above home in meters
/* // Enter -1 to maintain current altitude when returning to home
// The mission:
float mission[][6] = {
// CMD options P1 Alt Lat Long
{MAV_CMD_NAV_TAKEOFF, 0, 0, 3.0, 0, 0}, // 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.065219, -105.209760}, // 2 turn 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.064561, -105.209798}, // 3 turn 2
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.064511, -105.210402}, // 4 turn 3
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.065167, -105.210453}, // 5 turn 4 with delay
{MAV_CMD_NAV_WAYPOINT, 0, 5, 3.0, 40.065189, -105.210007}, // 6 Land WP with delay
{MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}, // 7 LAND!
};
*/
///*
// Enter -1 to maintain current altitude when returning to home
// The mission:
float mission[][6] = {
// CMD options P1 Alt Lat Long
{MAV_CMD_NAV_TAKEOFF, 0, 0, 3.0, 0, 0}, // 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.065219, -105.209760}, // turn 1
{MAV_CMD_NAV_WAYPOINT, 0, 4, 3.0, 40.064561, -105.209798}, // turn 2 pause
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.064508, -105.209808}, // turn 2
{MAV_CMD_NAV_WAYPOINT, 0, 4, 3.0, 40.064507, -105.210303}, // turn 3 pause
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.064524, -105.210464}, // turn 3
{MAV_CMD_NAV_WAYPOINT, 0, 1, 3.0, 40.065092, -105.210483}, // turn 4 pause
{MAV_CMD_NAV_WAYPOINT, 0, 0, 3.0, 40.065191, -105.210349}, // turn 4
{MAV_CMD_NAV_WAYPOINT, 0, 4, 3.0, 40.065189, -105.210007}, // Land WP with delay
{MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}, // LAND!
};
//*/
/*
// The mission:
float mission[][6] = {
// CMD options P1 Alt Lat Long
{MAV_CMD_NAV_TAKEOFF, 0, 0, 6.0, 0, 0}, // 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 6.0, 40.065219, -105.209760}, // 2 turn 1
{MAV_CMD_NAV_WAYPOINT, 0, 0, 6.0, 40.064561, -105.209798}, // 3 turn 2
{MAV_CMD_NAV_WAYPOINT, 0, 0, 6.0, 40.064511, -105.210402}, // 4 turn 3
{MAV_CMD_NAV_WAYPOINT, 0, 0, 6.0, 40.065167, -105.210453}, // 5 turn 4 with delay
{MAV_CMD_NAV_WAYPOINT, 0, 5, 6.0, 40.065189, -105.210007}, // 6 Land WP with delay
{MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}, // 7 LAND!
};
//*/

View File

@ -0,0 +1,12 @@
// Mission example:
#define WP_RADIUS 5 // What is the minimum distance to reach a waypoint?
#define ALT_TO_HOLD -1 // Altitude to hold above home in meters
// Enter -1 to maintain current altitude when returning to home
// The mission:
float mission[][6] = {
// CMD options P1 Alt Lat Long
{MAV_CMD_NAV_TAKEOFF, 0, 0, 3.0, 0, 0}, // 1
{MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}, // 7 LAND!
};