mirror of https://github.com/ArduPilot/ardupilot
imported PPMEncoder
This commit is contained in:
parent
d24674dc5d
commit
13681612c2
|
@ -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>
|
|
@ -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
|
@ -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/*)
|
||||
|
|
@ -0,0 +1,5 @@
|
|||
:1000000001000100010001000100010001000100E8
|
||||
:1000100001000100E907E907E907E907E907E9073E
|
||||
:10002000E907E907E907E907E90702020202020214
|
||||
:050030000202020202C1
|
||||
:00000001FF
|
Binary file not shown.
File diff suppressed because it is too large
Load Diff
|
@ -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
|
|
@ -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:
|
|
@ -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
|
|
@ -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
|
Loading…
Reference in New Issue