From e1166b065a5bc29db28a26888f3f992f53b01997 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 18:08:10 +0800 Subject: [PATCH 01/14] seperate toolchain and workspace path part of Makefile --- program/Makefile | 86 +++------------------------------- program/makefiles/toolchain.mk | 64 +++++++++++++++++++++++++ program/makefiles/workspace.mk | 19 ++++++++ 3 files changed, 90 insertions(+), 79 deletions(-) create mode 100644 program/makefiles/toolchain.mk create mode 100644 program/makefiles/workspace.mk diff --git a/program/Makefile b/program/Makefile index 353003b3..bbd2b48e 100644 --- a/program/Makefile +++ b/program/Makefile @@ -3,87 +3,15 @@ PROJECT=firmware EXECUTABLE=$(PROJECT).elf BIN_IMAGE=$(PROJECT).bin TEST_EXE=run_test +export WORKSPACE_DIR=./ #============================================================================# -HOST_CC=gcc -#Cross Compiler -CC=arm-none-eabi-gcc -OBJCOPY=arm-none-eabi-objcopy -GDB=arm-none-eabi-gdb -LD=arm-none-eabi-gcc -CMSIS=./lib/CMSIS -ST=./lib/STM32F4xx_StdPeriph_Driver -EXTERNAL_DEVICE=./ext_device -MCU_PERIPH=./mcu_periph -ESTIMATOR=./estimator -ACTUATORS=./actuators -COMMON=./common -RADIO_CONTROLLER=./radio_controller -CONTROLLER =./controller -MAVLINK=./mavlink -FREERTOS=./lib/FreeRTOS -MAVLINK_LIB=./lib/mavlink -TEST=./test +include ./makefiles/toolchain.mk +include ./makefiles/workspace.mk #============================================================================# -BOARD_CONFIG=./vertigo_v2_config.h -DEBUG_CONFIG=./debug_config.h -CFLAGS_INCLUDE=-I./ \ - -I$(TEST) \ - -I$(ACTUATORS) \ - -I$(CONTROLLER) \ - -I$(MCU_PERIPH) \ - -I$(EXTERNAL_DEVICE) \ - -I$(ESTIMATOR)\ - -I$(COMMON)\ - -I$(RADIO_CONTROLLER) \ - -I$(FREERTOS)/Source/include \ - -I$(FREERTOS)/Source/portable/GCC/ARM_CM4F \ - -I$(CMSIS) \ - -I$(ST)/inc \ - -I$(MAVLINK) \ - -I$(MAVLINK_LIB) \ - -I$(MAVLINK_LIB)/common -CFLAGS_DEFINE= \ - -D USE_STDPERIPH_DRIVER \ - -D __FPU_PRESENT=1 \ - -D ARM_MATH_CM4 \ - -D __FPU_USED=1 \ - -include $(BOARD_CONFIG) \ - -include $(DEBUG_CONFIG) \ - -U printf -D printf=printf_base - - #__CC_ARM -CFLAGS_OPTIMIZE= \ - -O2 -CFLAGS_NEW_LIB_NANO= \ - --specs=nano.specs --specs=nosys.specs -u _printf_float -CFLAGS_WARNING= \ - -Wall \ - -Wextra \ - -Wdouble-promotion \ - -Wshadow \ - -Werror=array-bounds \ - -Wfatal-errors \ - -Wmissing-prototypes \ - -Wbad-function-cast \ - -Wstrict-prototypes \ - -Wmissing-parameter-type - -ARCH_FLAGS=-mlittle-endian -mthumb -mcpu=cortex-m4 \ - -mfpu=fpv4-sp-d16 -mfloat-abi=hard - -CFLAGS=-g $(ARCH_FLAGS)\ - ${CFLAGS_INCLUDE} ${CFLAGS_DEFINE} \ - ${CFLAGS_WARNING} - - -LDFLAGS +=$(CFLAGS_NEW_LIB_NANO) --static -Wl,--gc-sections - -LDFLAGS +=-T STM32F427VI_FLASH.ld -LDLIBS +=-Wl,--start-group -lm -Wl,--end-group #============================================================================# -STARTUP=./startup_stm32f427xx.o +STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o EXTERNAL_DEVICE_SRC = $(EXTERNAL_DEVICE)/AT24C04C.o \ $(EXTERNAL_DEVICE)/mpu9250.o \ $(EXTERNAL_DEVICE)/hmc5983.o \ @@ -131,7 +59,7 @@ MAVLINK_SRC=$(MAVLINK)/communication.o \ $(MAVLINK)/command_parser.o \ $(MAVLINK)/global.o -OBJS= ./system_stm32f4xx.o \ +OBJS= $(WORKSPACE_DIR)system_stm32f4xx.o \ $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ $(CMSIS)/FastMathFunctions/arm_sin_f32.o \ $(ST)/src/misc.o \ @@ -144,8 +72,8 @@ OBJS= ./system_stm32f4xx.o \ $(ST)/src/stm32f4xx_spi.o \ $(ST)/src/stm32f4xx_i2c.o \ $(ST)/src/stm32f4xx_sdio.o \ - ./interrupt.o \ - ./main.o \ + $(WORKSPACE_DIR)/interrupt.o \ + $(WORKSPACE_DIR)/main.o \ $(STARTUP) \ $(EXTERNAL_DEVICE_SRC) $(MCU_PERIPH_SRC) \ $(ESTIMATOR_SRC) $(ACTUATORS_SRC) $(RADIO_CONTROLLER_SRC) \ diff --git a/program/makefiles/toolchain.mk b/program/makefiles/toolchain.mk new file mode 100644 index 00000000..3828087a --- /dev/null +++ b/program/makefiles/toolchain.mk @@ -0,0 +1,64 @@ +HOST_CC=gcc +CC=arm-none-eabi-gcc +OBJCOPY=arm-none-eabi-objcopy +GDB=arm-none-eabi-gdb +LD=arm-none-eabi-gcc +AR =arm-none-eabi-ar +RANLIB =arm-none-eabi-ranlib + +CFLAGS_OPTIMIZE= \ + -O2 +CFLAGS_NEW_LIB_NANO= \ + --specs=nano.specs --specs=nosys.specs -u _printf_float +CFLAGS_WARNING= \ + -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Werror=array-bounds \ + -Wfatal-errors \ + -Wmissing-prototypes \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wmissing-parameter-type + +ARCH_FLAGS=-mlittle-endian -mthumb -mcpu=cortex-m4 \ + -mfpu=fpv4-sp-d16 -mfloat-abi=hard + +LDFLAGS =$(CFLAGS_NEW_LIB_NANO) --static -Wl,--gc-sections \ + -T ./STM32F427VI_FLASH.ld + +LDLIBS =-Wl,--start-group -lm -Wl,--end-group + +CFLAGS_INCLUDE=-I$(WORKSPACE_DIR)/ \ + -I$(TEST) \ + -I$(ACTUATORS) \ + -I$(CONTROLLER) \ + -I$(MCU_PERIPH) \ + -I$(EXTERNAL_DEVICE) \ + -I$(ESTIMATOR)\ + -I$(COMMON)\ + -I$(RADIO_CONTROLLER) \ + -I$(FREERTOS)/Source/include \ + -I$(FREERTOS)/Source/portable/GCC/ARM_CM4F \ + -I$(CMSIS) \ + -I$(ST)/inc \ + -I$(MAVLINK) \ + -I$(MAVLINK_LIB) \ + -I$(MAVLINK_LIB)/common + +CFLAGS_DEFINE= \ + -D USE_STDPERIPH_DRIVER \ + -D __FPU_PRESENT=1 \ + -D ARM_MATH_CM4 \ + -D __FPU_USED=1 \ + -include $(BOARD_CONFIG) \ + -include $(DEBUG_CONFIG) \ + -U printf -D printf=printf_base + + #__CC_ARM + + +CFLAGS=-g $(ARCH_FLAGS)\ + ${CFLAGS_INCLUDE} ${CFLAGS_DEFINE} \ + ${CFLAGS_WARNING} \ No newline at end of file diff --git a/program/makefiles/workspace.mk b/program/makefiles/workspace.mk new file mode 100644 index 00000000..f6686017 --- /dev/null +++ b/program/makefiles/workspace.mk @@ -0,0 +1,19 @@ +#export abs path + +export CMSIS=$(abspath $(WORKSPACE_DIR)/lib/CMSIS)/ +export ST=$(abspath $(WORKSPACE_DIR)/lib/STM32F4xx_StdPeriph_Driver)/ +export EXTERNAL_DEVICE=$(abspath $(WORKSPACE_DIR)/ext_device)/ +export MCU_PERIPH=$(abspath $(WORKSPACE_DIR)/mcu_periph)/ +export ESTIMATOR=$(abspath $(WORKSPACE_DIR)/estimator)/ +export ACTUATORS=$(abspath $(WORKSPACE_DIR)/actuators)/ +export COMMON=$(abspath $(WORKSPACE_DIR)/common)/ +export RADIO_CONTROLLER=$(abspath $(WORKSPACE_DIR)/radio_controller)/ +export CONTROLLER =$(abspath $(WORKSPACE_DIR)/controller)/ +export MAVLINK=$(abspath $(WORKSPACE_DIR)/mavlink)/ +export FREERTOS=$(abspath $(WORKSPACE_DIR)/lib/FreeRTOS)/ +export MAVLINK_LIB=$(abspath $(WORKSPACE_DIR)/lib/mavlink)/ +export TEST=$(abspath $(WORKSPACE_DIR)/test)/ + +#inclue dir +BOARD_CONFIG=$(WORKSPACE_DIR)/vertigo_v2_config.h +DEBUG_CONFIG=$(WORKSPACE_DIR)/debug_config.h From 69711a04a8faa7b0d035f4872d27ccc3de72c633 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 18:17:46 +0800 Subject: [PATCH 02/14] Seperate rules --- program/Makefile | 9 +-------- program/makefiles/rules.mk | 8 ++++++++ 2 files changed, 9 insertions(+), 8 deletions(-) create mode 100644 program/makefiles/rules.mk diff --git a/program/Makefile b/program/Makefile index bbd2b48e..2b844033 100644 --- a/program/Makefile +++ b/program/Makefile @@ -7,6 +7,7 @@ export WORKSPACE_DIR=./ #============================================================================# include ./makefiles/toolchain.mk include ./makefiles/workspace.mk +include ./makefiles/rules.mk #============================================================================# #============================================================================# @@ -93,14 +94,6 @@ $(EXECUTABLE): $(OBJS) @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ @echo 'LD $(EXECUTABLE)' -%.o: %.c - @$(CC) $(CFLAGS) -c $< -o $@ - @echo 'CC $<' - -%.o: %.s - @$(CC) $(CFLAGS) -c $< -o $@ - @echo 'CC $<' - PC_SIM:$(TEST_EXE) $(TEST_EXE):$(HOST_SRC) diff --git a/program/makefiles/rules.mk b/program/makefiles/rules.mk new file mode 100644 index 00000000..79b1208a --- /dev/null +++ b/program/makefiles/rules.mk @@ -0,0 +1,8 @@ +#makefile rules +%.o: %.c + @$(CC) $(CFLAGS) -c $< -o $@ + @echo 'CC $<' + +%.o: %.s + @$(CC) $(CFLAGS) -c $< -o $@ + @echo 'CC $<' \ No newline at end of file From 959198db5a8ce1c78a8d6eaba5bfb47af1f4b978 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 18:35:11 +0800 Subject: [PATCH 03/14] Let estimator part to be a static lib --- program/Makefile | 3 --- program/estimator/Makefile | 20 ++++++++++++++++++++ program/estimator/libestimator.a | Bin 0 -> 20562 bytes program/makefiles/toolchain.mk | 2 +- 4 files changed, 21 insertions(+), 4 deletions(-) create mode 100644 program/estimator/Makefile create mode 100644 program/estimator/libestimator.a diff --git a/program/Makefile b/program/Makefile index 2b844033..9ff01605 100644 --- a/program/Makefile +++ b/program/Makefile @@ -28,9 +28,6 @@ MCU_PERIPH_SRC = \ $(MCU_PERIPH)/usart.o \ $(MCU_PERIPH)/input_capture.o \ $(MCU_PERIPH)/system_time.o -ESTIMATOR_SRC = $(ESTIMATOR)/attitude_estimator.o \ - $(ESTIMATOR)/vertical_estimator.o \ - $(ESTIMATOR)/estimator.o ACTUATORS_SRC = $(ACTUATORS)/pwm.o RADIO_CONTROLLER_SRC = $(RADIO_CONTROLLER)/radio_control.o \ diff --git a/program/estimator/Makefile b/program/estimator/Makefile new file mode 100644 index 00000000..be5c01ca --- /dev/null +++ b/program/estimator/Makefile @@ -0,0 +1,20 @@ +export WORKSPACE_DIR=../ +include $(WORKSPACE_DIR)/makefiles/toolchain.mk +include $(WORKSPACE_DIR)/makefiles/workspace.mk +include $(WORKSPACE_DIR)/makefiles/rules.mk + +LIB_ESTIMATOR=libestimator.a + +ESTIMATOR_SRC = $(WORKSPACE_DIR)/estimator/ + +ESTIMATOR_OBJS= $(ESTIMATOR_SRC)/attitude_estimator.o \ + $(ESTIMATOR_SRC)/vertical_estimator.o \ + $(ESTIMATOR_SRC)/estimator.o + +all: $(LIB_ESTIMATOR) + +$(LIB_ESTIMATOR): $(ESTIMATOR_OBJS) + $(AR) -r $(LIB_ESTIMATOR) $(ESTIMATOR_OBJS) + $(RANLIB) $(LIB_ESTIMATOR) +clean: + rm -rf $(LIB_ESTIMATOR) \ No newline at end of file diff --git a/program/estimator/libestimator.a b/program/estimator/libestimator.a new file mode 100644 index 0000000000000000000000000000000000000000..de4cadca2d9c8aae6aed871f88c4877c5041f32b GIT binary patch literal 20562 zcmd^H3wRvWb-p|M)aqfaB-^rVU~Ozr0PA7Pwrpdt`~p{gD7Fbk5LPSgO1rM4U3OQN zy`qs5Amq`c2uOIuUrAz0k`@}b32}%ZNkbB#p$$ozDoG)R7DCe?7YZp9rJ?_S=gjP^ zECYqKU(#M{=0A^n&wbA9opWZq@cd||CvicrFx*Y1z5UTX70u<6xuIA* zQqU&{levOC8z0QZRU#gZB?tQ=CTABKO2?wPxGIz_vb{f^$t8QD{nKr~E7BR+5Y40_ z{b>a{7TLOEw@pOinM^8EVEa>peYtpMU?%w<$anVkX5%@XUmJ4f)0K2&;`I&MUYB!)E)fluJS0rsT7migp>|9yRO-<0+=anl_M{7%~EUm8K=;m!(TrL+Dn3-Iv zUKKc{9-E`(-WCn@sz!y>p)X!{RDJ%HuKT*KpL7L}olyCSNmqW=iN5?);s=u|fA)#9 z^W&uUQQmvvGx=dij-KcX)~tG9%e!CkjHE9r*vNOS?V3vLd|nxKf}Mi5ca4kO#7@n> zXV>jrBO*7kQ}dLs6}gF>ny1{;t`^m$3$?4Su{($ET{>xe_*Ur)+wtA@srcWvkK-7L zqebqu`aBgQJ+99q`n*=3r+T!!=fU=o9&;4R^ADk?4^5Wkzt%q0t+o0*qR(sfc`B;q z`aBZNC&m+%Tjp)KWpZxtwU>9j_WX(U`H{qf7{!r9-D%?q&+>wHqpfv8>wY0%j3)vP z{c>AxXnh&u1_}x7JreU+K_S+j@`I*Faz6(7SED7y6rY8?E^s!F;>+>9d~k zRTu|yhL#yctKhYlfBo9^lQpt(YGll+#pc9hb-quJVx^Y2u(~YCEG;n{k_xP}ngj zd7jzxiOFD5c~kC^@K+DwW^7;?<9y z|5QVK!^C7oQF&(%%{zrT*5)|!Ucr@Pj-Ni;rFs7_S5B3zoGMv4A$wdxdhQEj#kEtA znX|*yQ;?bMkr~tWta^^(N{mc4Yl~CGv;QH^gEgD>OzfMvy}Y6yMxTo9US!*K<-2fK zeBe3b!-pPFUpsW~hwS?i?-QrKbBrfGksRsf>i6p_t#IEB=xfexkK998tK(Rae!cQW zK)Lm-QD){7 z=8(nT4$d8<=$!MQcdsP5;sTOKVb9ZcscB;y!24;Od|eRNc>Vtl+8^!dQQiPa6{v>X zTSD6BAHYV<8zfy8pjmI}EjU-H5`qsM2;Kw2P;MIYmfc5b8&37!Sv#OL?N*W$yCKqL zrrj#iwWi(bD?u+-B?KN~*YJ40g|hB8oV+z5D16VMrdIEqZ-F+=&vi7r*3s;FX0u0F zw2oEP1is2v&LGPDEM!lz{!T3IeQ<<;C1xa8Z^7w*mj|%L^fci>Fd;ABZ z!^&4iI-uMv;46O&XH4p!p_mcy)a#k@yoai1QM$}uyA2xu0p*{k&G`>1f1PP8ul)1H z6tnslEJRM<5frWUpME!+aVLwOq00rjnI)`C28Kv4)MW#H(u+u!1s))MCh5vRiu7XA zHOft+{w0^fTGF$+UX$xDM@Dd$Yh401Iq(&pI4oCqIA)d2 zAdR|*k?lrIf$Q*J;cVKkqkZ?-;Zd`KI+}Ek-8yR4AneVfW)*d;!aa7wXlOfIa~j)@ zUW8V#X5kW{0HwmkLhohH)6JY+q1zqY6`=~YTXcIvPdRjZLVM9fLr<77))BguIfdI6 zTI1j@uIg2WoY<=iDX47-%9=m@u^bXqB)94=i@@QyB=j3AA`nq_##l|_+Dww-xcQYUTMzQ z-tt-+xRTk7u|1(Lv+gc)jB=qbQzu+H)X1?Fu0J%J6-CXQiO?kuE{3`0O0T?(1%|tD z+guN|>+mtVEyLDY(yM3KY)iVlmbDL?tEazwjxNqZ##q8^wd7Rg|H=A>AJ94v>f_z3 z!o%B0^#z!&z-N44M2?#E5R`cS5TqBzkX#|xl8Wk5cg6gQkgLj9ITvOYtJ2a7Ai@C8 zQSOR0rE5#K;+fea@&F32P?Y$pUG9p~Qf6?0^_MGmz|7rRiaNncVX`GI*Vbxg3ob4ezi=LNs0BDMEl3zwN!BkR*>=vE`a7-^*HlHh z!XqJQg~QdDz*B8wZ+9w_%r;&%6pi7T7mkDBROa`y>1a>9aUhi%T-qIvW*P?$MtYN( zf#GN--k8p$`ZCdh#-7x`Kx$AmG&DBa53P-=aVVQ z!()68Cn6Gy_eO{MbCKM^bUcf^SlHPdyec`+n4;vs5C~itGZ;wFfIXJT2DT@aiAQ<{ zTEO8#g&DXuhSD^~A0g#M7NzFx4_x3e+y`^}+uOIjLWnoq>hTf#z#J zJv_XwbKMn5!;QtWCo>d}>{7eoAL;K`yWkxeimUC>zP+ZyBpy@P#YD1jlEhUmK9IJ% zsdhx#@{vCFKLT%3G?G)jz;y5&_e^62_zb=|oiZr-swfY!*(iR5XWHo2E^!*x5w~R9K&AZhyQ7 zH7t)sdSS|zvhCtb!s1W&#|Pqrxi($VV7w3RqWy5N4fV$}XvYxDw6YzR=k0a9PVg(m zl0CV2EYfyBIhcb^CU3SRmKy5D=-P&JYG^Q<>>G^7!aa#-M(Gw5yRCA1h!4Eoi^5)- zn7TrJeFrlsM>G5M^r~3AACpYoUI%@dgYHzA(RhEvnxnpGa!@Z1bcgFFW~~zrdnP(; z+TBG`Cf@Ehrwop}h^gFYE>1ld&@5kuY2Xq)px7K)L-z35ox;+AN7OWgBf1d+`N26 z>$}5C2l|t_TtDv0gRx|E5PU8%G|&y~Ne`{VjV2dAuymjWd@uOk^!}Em+4Ry_^GZs1 z0WHPdd>xipEWET&Sqr@Q{@-}=xHk0gwxuu1t$Vgdb{*I-)Z2?|q-X?j{T{&eTeu2~ zwB}{2F50+pO}L)pu_u-4&xU(bnJ{`E-YmTjcVtpM@oYAg$-d(^Fkq^!75COCf5Vik zfj8TY<``{n!83?|dx;VBRe5S$vt4uDwXS)tI@f&n0@vxjMXoYrehtZ`jH@fk$`ya8 zt+WY5TZQL(S6fAGTe;uXQGV?-T^Kx*wI6S*2wZP`)U~0a(%a!_t4OmvHvml5o>KC( zRWwm+ZV;%q_Ib8m*A7KP_TWG++6~NQOiWl57Fh!pMNT#FmaQ7Pvsu+ZVJzM~)Q1bE zHwBfZqut%~z&o^2EW^HdQGtH`{7V7Up&Gb{z&%toU>X~+bTY~Ap;w>Ai!{?E%`<~5v{fuAoDTZhQp%CUyXcs zlaORJ;bY*P{rFK>sSe24k6AdZeuO|V?-VIT1TKCkx(L1N9!=hC(KnLi2Q~O+W+G*}!kw z8C*I)?^9+n^|jXEAwTUobc)AaT^E)ZmJo10%NGkC7dLUQYs<>bqB zdpVwF;*1rNThE}A*KQ13;8qpt9B^zEkC6Je*V=%aaa@a|3ewAfkKmx+gnRel5EF=DYN<~@@t6TYcb|Q zTw`hC>BvvSkIErpSg8*Y7b^8}B7WEb%D}ykzxf6(eqR4X+(tCQG~CTfp@=dt@%18K zDyUsl$bX^m+XQzD?iGv+_6ueO^MW4`{D|PKf=2|83VucK`-1->=*K!_yQ>7x5!@gc z73>w%o-O46pzxm(yhrdp!EXzGPw)xBp9^wqSnn*sIfADNE)vv^MC98md`vJcc(vdM z1aB7nq~JY*+Jy!?-yn};Qsj8N)$IrnA)71w62awyZGzo`2_o_j3;%w>j|tu>_yxhg z68x^<6N0}G{0~7t)~8-af@cag3u?C~`q3vmUFOVxo#4%aM+E;;@Ed{;6VdJo;hzzF zQP73!LC=feX@chpt`^)OxQ7UPJ;GllI4bxN!A}T&PVk$8j|o0b#PzDLE8K>8ucY0l zxL$zxxmN~$B)O+1-y}TuRpj;c1AT|^Y0>k3OZ^SP-z%L?yl+DVI6xDZ>UZVC}f*S_PEpR%KvX1vza-qg;R{V>Y@ z=ZR;@>TAJSvTh?1GW=-xV z54P7OrV@1+>G_GZF~&^IIR9EuX0(+uL&u1n(bicycFngGDs@fF??Nqws5_&#Q;9YE zZtuDU6yxa}hhE)ob4230rKzu3N^@=+sh)x&BVmIdEE5GI(?bNwDNaj!&sZka4WdosE`%e2jAX-|`sX_PYl z{OMXVG3nP)=J`7JxWu*1H!oh+vl+x}KD%#9kBW0nIVPQn1?_cRm6+Mtz>9TkSzn@f zzv1q0o!!cJ9fA`_)~bN9UZcuyN>yF6nt2}l<$^Xmk#8{bo9E$2&t0a%`Ay{31utbF zSOq7}JfArC*gISQ=FvyjnX)6}KgRtPe@Grz6!&`9$3dQj8xzy7AYeiaI|Y%OKcaRF zdrIE{yvOiaUA{!adIi|rvcu3a0=9Wf8ZWM zeI<9|w9cc8ixnP)A5 z#O2r7QDPGg*I_oW(u_}&L}aqqF~&>^W=`>YUSd;D9pDHM#VhwtRu>pIyT|=b5^W*eH?VYXnl)~-7Q2Yc< zsq%1r%smU8E%}V^Y2>ec1md8FZ-JO$(%KqYsiRF1e2^`h?-2Zgf&~u2AF!9FIRx*a zjnf^1PBv7pNHO|Z+R)2S1kbUEUV|birO_n?8*ejyYlUR}R!BBb?b7jFFQc#}62L_; zlmXnJgm;B4mDn&?Tm;3D;PT=~Fs>^reoI3L+gd@}X>s4m;<#_9IPP0z#eJ(!j_yj} zxaMSy#C>NM0=W$1&H?L)`_2`u9rvv*WPhEwul4JJX;LdWdFr1yLI3yTzJ+M*Z!Um* zin#9#FKWN3xNkN$uzXo>%Yg%C^cS%uGoo8?#^`YG4CbeYf$@BVc*?26z{8z70^IJd z+`E6>?_bb(U2^E2`+xE?{7SiePy3z;4DY%ia7AFz#=ykUJHGR?XFeZT_?^E#64=-7 zuK7J<1wyP0)dgfNEFejj2RIw z1Z^2$n;r|cz7#-MaInwu=Kr)X(+uO(gE+AnC^DnQ<`)MMGd`;WOA?ebgR?reX4mHU zV8B%Cc$NL_07BRLg8;<0X9_Iu+;dsSW=6%G@#T}7Xhs+dF)oHJJ1*(K=0?lN+6|%v zlWctuVaGo=?B2EOVzqteCe(MzptBh;x0hD2AJ1-=9g%Ls>k0@u?=OVpbnLV*f>%Fs ziJ1e+Z}UR4+jep&nSsTk$tg68BSf{H96eNpZ$FBn#O4|+iXqMv6}CrPPrur^yJPca zYc`4s+hbu#WjNkSOm`E?NxZkx8LzeWx^_Ia!;IJde~8CAH!9e5>NGtbdkBv6 zE@u^|F6# zDlv}3Dg#n|0`}IReO9t`Q3#y<_z~=}Jnf-~ZSN}3EW>^?{SX(xzG>q^{na>}`7VSH znq{p-9gpj9U@p>@{3!Bihl&W8hv_yP7ES&+}A19w+ocdmML;owcSws`IgZZ?lYmcaT)u$tnMzipScO zq4$ih7Lr@@x7rPNwub%T3NEDIrugb6G|P&wvW1)ndIq@ONn1SQtJd{E{U3nmJ=@ZA zy>R|4o-QgrM_c>@pfQy;|0rlIDVu*1G?SU%t$q&rgE;7~VEbO7QWEQ_a11f|`e{7g zF`WM0?0+vFdvbYme~C@aZ}WGz`tf2HV!c}j(?hvU2o!JNhsd#P^RkweItbjhX`>m& z<=bm&d&l0D&CM$!ees-r3ozPmhL1Va-^an&?Bm3+Qcn{XD#dkf%vS1tBHo*Mn2787 zQ6kK=_|rs8_H)EKrRWPa@PnjdP;e1&9WlnsdkGPyHKM4FDWOVbz*|=@ z@}+`n1lt6+2<{f#E6BA>yL2EDhXu8d20ZVbl;0$HtKbpAKNq}D@Y{kf3i77J^5uec zg1m20&JS~lmkW*vUN3lu;4#6!7yJjoe-_kEH`w`i;kCyaJio`HeSYmkJVWqY!Bv7A z1v>;U7u4=8l+!U?;2%?t;}OwoUn}HKi~L2AyEu=K>rWMc3&=xvuE^I2ZWY`s*e5t9 zc!%IUg5!dZ2tF_PYr!(yBv|j+g3ARjB;p5UlkgoxEG9axnLkRzI_(ucL&SO=7XBI{ z*6jy`*D+o!!rO%Z6C&2{p9=paBG&P^@DCBO&L0*2M?_p7dY$9PpZ6(_&-0u=p!PFD zh$=PTL3JkjFG-kEOmLS^=14U$5IdT=8mlv>$YR5_rA}LgEC%t zeDVw(C$hfCWPEF_jzNy-c;fNNxijkd)ik4J#}S?Db9~WhmFHL4rrtlJ-jfgL7!tmX zz5fdsI}9t5$Ms3jE;>oMz?p6~0X{k3%@AX`U?8n;6tiRuFF%Yk4F3(_++m7VUCOh^ zJ4%Je|5b7U?-k?%{wu&0A~|Q#Xe&?Vhl%YZ+w?Sf{JUAg6RF;g9DfMXyB^ldyd@p1B#)Cf$c)OzJ+ilyv?suq{=H?S5vO1QZ#kn4CC!lVnl=a0 zb@(F?2CvsblJN8gpV8b+noFxv59=xQuuEk}pz?jj$D3dIOQ8Lp_u_22vfrxby4ca| zEA}k=&F_-<<&on@uQg@eTo=2FYSTsGYuT>hrq!Pa6!Cl%L(p~5^*cLx`H)?Vl9 zod1OncnXeO?S3uXPkI!Ze$ux!xT@@LYp^T|*-!O}j+Q$V1pPikr| ze-WR|7+yF;3mp)B?t7O$1UcVF1K7FD5}ZG9nNH5{K#pnC1vvp@YQ z^q(y=-KPZyu^wKXg<4I>5Ia9W`7QlG;y30Y{oQesmErPn`pB@=uoLe_wy#Tj!XWs6 z@a=)~E^O`#l$!4Ais9KIjNzc~0{1z+f8cg!iSYU-5A?%0oQZjvru({1m9GVPtuidf zeB9Gp$s(H|aQcX@Mf>(b$@cLc$$qeX>v33RK&nyPkiSMklBL@P-lD0x038aGkYwq0 zfOppWIQGPqkg;CYXVn`AZIuD3u7thw9RiDtLg%#i9PH5!?dc5;ko;9RScd&(x*ZiA zLSL*z9gnL8t$cOfC?-$XvkHhF8k(0AeN$4icJc|Bj(OR#qr z4M}1jn23(Jos$@_tvC&?bA2JS4FJEdM>vZpsv^c zxiwuti%q8oNJa_D&=d)W3gM$*Z&1$_L3I> literal 0 HcmV?d00001 diff --git a/program/makefiles/toolchain.mk b/program/makefiles/toolchain.mk index 3828087a..136cdfff 100644 --- a/program/makefiles/toolchain.mk +++ b/program/makefiles/toolchain.mk @@ -28,7 +28,7 @@ ARCH_FLAGS=-mlittle-endian -mthumb -mcpu=cortex-m4 \ LDFLAGS =$(CFLAGS_NEW_LIB_NANO) --static -Wl,--gc-sections \ -T ./STM32F427VI_FLASH.ld -LDLIBS =-Wl,--start-group -lm -Wl,--end-group +LDLIBS = -Wl,--start-group -lm -L$(ESTIMATOR) -lestimator -Wl,--end-group CFLAGS_INCLUDE=-I$(WORKSPACE_DIR)/ \ -I$(TEST) \ From 448134d282e7fef2ed0e57cbb6d51dd9a329a1e6 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 18:43:56 +0800 Subject: [PATCH 04/14] Delete private source code` --- program/estimator/Makefile | 20 ---- program/estimator/attitude_estimator.c | 134 ---------------------- program/estimator/estimator.c | 11 -- program/estimator/vertical_estimator.c | 147 ------------------------- 4 files changed, 312 deletions(-) delete mode 100644 program/estimator/Makefile delete mode 100644 program/estimator/attitude_estimator.c delete mode 100644 program/estimator/estimator.c delete mode 100644 program/estimator/vertical_estimator.c diff --git a/program/estimator/Makefile b/program/estimator/Makefile deleted file mode 100644 index be5c01ca..00000000 --- a/program/estimator/Makefile +++ /dev/null @@ -1,20 +0,0 @@ -export WORKSPACE_DIR=../ -include $(WORKSPACE_DIR)/makefiles/toolchain.mk -include $(WORKSPACE_DIR)/makefiles/workspace.mk -include $(WORKSPACE_DIR)/makefiles/rules.mk - -LIB_ESTIMATOR=libestimator.a - -ESTIMATOR_SRC = $(WORKSPACE_DIR)/estimator/ - -ESTIMATOR_OBJS= $(ESTIMATOR_SRC)/attitude_estimator.o \ - $(ESTIMATOR_SRC)/vertical_estimator.o \ - $(ESTIMATOR_SRC)/estimator.o - -all: $(LIB_ESTIMATOR) - -$(LIB_ESTIMATOR): $(ESTIMATOR_OBJS) - $(AR) -r $(LIB_ESTIMATOR) $(ESTIMATOR_OBJS) - $(RANLIB) $(LIB_ESTIMATOR) -clean: - rm -rf $(LIB_ESTIMATOR) \ No newline at end of file diff --git a/program/estimator/attitude_estimator.c b/program/estimator/attitude_estimator.c deleted file mode 100644 index 8c38ba14..00000000 --- a/program/estimator/attitude_estimator.c +++ /dev/null @@ -1,134 +0,0 @@ -#include "attitude_estimator.h" -#include -#include "basic_filter.h" - -void attitude_estimator_init(attitude_t* attitude,imu_data_t* imu_raw_data, imu_data_t *imu_filtered_data,vector3d_f_t* True_R){ - - attitude->roll=0.0; - attitude->pitch=0.0; - attitude->yaw=0.0; - - imu_raw_data->acc[0]=0.0; - imu_raw_data->acc[1]=0.0; - imu_raw_data->acc[2]=1.0; - - imu_filtered_data->acc[0] =0.0; - imu_filtered_data->acc[1] =0.0; - imu_filtered_data->acc[2] =1.0; - - True_R->x =0.0; - True_R->y =0.0; - True_R->z =1.0; - - estimator_trigger_flag=0; -} - -void attitude_sense(attitude_t *attitude, imu_data_t *imu_raw_data, imu_data_t *imu_filtered_data, vector3d_f_t *True_R) -{ - - float accel_lowpass_gain = 0.03f, gyro_lowpass_gain =0.03f,complementAlpha = 0.0001f; - float R_raw = 0.0f, inv_R_raw = 0.0f, R_true = 0.0f, inv_R_true = 0.0f; - float N_Ax_g = 0.0f, N_Ay_g = 0.0f, N_Az_g = 0.0f; - - float f=4000.0f; - float dt=1.0f/f; - float degtorad=0.01745329251994329f; - float delta_gyroX=0.0f,delta_gyroY=0.0f,delta_gyroZ=0.0f; - float predicted_Ax=0.0f,predicted_Ay=0.0f,predicted_Az=0.0f; - - - imu_filtered_data->acc[0] = lowpass_float(&imu_filtered_data->acc[0], &imu_raw_data->acc[0], accel_lowpass_gain); - imu_filtered_data->acc[1] = lowpass_float(&imu_filtered_data->acc[1], &imu_raw_data->acc[1], accel_lowpass_gain); - imu_filtered_data->acc[2] = lowpass_float(&imu_filtered_data->acc[2], &imu_raw_data->acc[2], accel_lowpass_gain); - - imu_filtered_data->gyro[0] = lowpass_float(&imu_filtered_data->gyro[0], &imu_raw_data->gyro[0], gyro_lowpass_gain); - imu_filtered_data->gyro[1] = lowpass_float(&imu_filtered_data->gyro[1], &imu_raw_data->gyro[1], gyro_lowpass_gain); - imu_filtered_data->gyro[2] = lowpass_float(&imu_filtered_data->gyro[2], &imu_raw_data->gyro[2], gyro_lowpass_gain); - - R_raw = sqrtf(imu_filtered_data->acc[0] * imu_filtered_data->acc[0] + imu_filtered_data->acc[1] * imu_filtered_data->acc[1] + imu_filtered_data->acc[2] * imu_filtered_data->acc[2]); - inv_R_raw = 1.0f / R_raw; - N_Ax_g = imu_filtered_data->acc[0] * inv_R_raw; - N_Ay_g = imu_filtered_data->acc[1] * inv_R_raw; - N_Az_g = imu_filtered_data->acc[2] * inv_R_raw; - - delta_gyroX = imu_raw_data->gyro[0] * dt * degtorad; - delta_gyroY = imu_raw_data->gyro[1] * dt * degtorad; - delta_gyroZ = imu_raw_data->gyro[2] * dt * degtorad; - - - (True_R->x) = (True_R->x) + (True_R->y) * delta_gyroZ; - (True_R->y) = - (True_R->x) * delta_gyroZ + (True_R->y); - - (True_R->y) = (True_R->y) + (True_R->z) * delta_gyroX; - (True_R->z) = - (True_R->y) * delta_gyroX + (True_R->z) ; - - (True_R->x) = (True_R->x) - (True_R->z) * delta_gyroY ; - (True_R->z) = (True_R->x) * delta_gyroY + (True_R->z); - - predicted_Ax = (True_R->x); - predicted_Ay = (True_R->y); - predicted_Az = (True_R->z); - - - (True_R->x) = (1.0f - complementAlpha) * (predicted_Ax) + complementAlpha * (N_Ax_g); - (True_R->y) = (1.0f - complementAlpha) * (predicted_Ay) + complementAlpha * (N_Ay_g); - (True_R->z) = (1.0f - complementAlpha) * (predicted_Az) + complementAlpha * (N_Az_g); - - - R_true = sqrtf((True_R->x)*(True_R->x) + (True_R->y)*(True_R->y) + (True_R->z)*(True_R->z)); - inv_R_true = 1.0f/R_true; - (True_R->x) =(True_R->x) *inv_R_true; - (True_R->y) =(True_R->y) *inv_R_true; - (True_R->z) =(True_R->z) *inv_R_true; - - - attitude->roll=atanf(True_R->y/True_R->z)*57.2957795130823f; - - attitude->pitch=atanf(-True_R->x/sqrtf(True_R->y*True_R->y+True_R->z*True_R->z))*57.2957795130823f; - - - -} - - -void heading_sense(attitude_t *attitude,imu_data_t *imu_raw_data,euler_trigonometry_t* negative_euler){ - -float MagXx=0.0f,MagYx=0.0f,MagZx=0.0f; -float MagX_rotated=0.0f,MagY_rotated=0.0f;//,MagZ_rotated=0.0f; - - MagXx = imu_raw_data->mag[0]; - MagYx = imu_raw_data->mag[1]*(negative_euler -> C_roll)+imu_raw_data->mag[2]*(negative_euler -> S_roll); - MagZx = -imu_raw_data->mag[1]*(negative_euler -> S_roll)+imu_raw_data->mag[2]*(negative_euler -> C_roll); - - MagX_rotated=MagXx*(negative_euler -> C_pitch)-MagZx*(negative_euler -> S_pitch); - MagY_rotated=MagYx; - //MagZ_rotated=MagXx*(negative_euler -> S_pitch)+MagZx*(negative_euler -> C_pitch); - - attitude -> yaw = atan2f(-MagY_rotated,MagX_rotated)*57.32484076433121f; - - - if((attitude -> yaw) <0.0f){ - - (attitude -> yaw) += 360.0f; - } - - -} - - -void attitude_update(attitude_t *attitude, imu_data_t *imu_filtered_data, vector3d_f_t *predicted_g_data,imu_unscaled_data_t *imu_unscaled_data,imu_data_t *imu_raw_data,imu_calibrated_offset_t *imu_offset){ - - - imu_update(imu_unscaled_data); - imu_scale_data(imu_unscaled_data, imu_raw_data, imu_offset); - #ifdef USE_MAGNETIC_HEADING - magnetometer_update(imu_unscaled_data); - magnetometer_scale_data(imu_unscaled_data,imu_raw_data,imu_offset); - #endif - - - attitude_sense(attitude, imu_raw_data, imu_filtered_data, predicted_g_data); - - -} - diff --git a/program/estimator/estimator.c b/program/estimator/estimator.c deleted file mode 100644 index f266c335..00000000 --- a/program/estimator/estimator.c +++ /dev/null @@ -1,11 +0,0 @@ -#include "estimator.h" - -void inverse_rotation_trigonometry_precal(attitude_t* attitude,euler_trigonometry_t* negative_euler){ - - /* all global variable */ - negative_euler -> C_roll = arm_cos_f32(attitude->roll * (-0.01745329252392f)); - negative_euler -> S_roll = arm_sin_f32(attitude->roll * (-0.01745329252392f)); - - negative_euler -> C_pitch = arm_cos_f32(attitude->pitch * (-0.01745329252392f)); - negative_euler -> S_pitch = arm_sin_f32(attitude->pitch * (-0.01745329252392f)); -} \ No newline at end of file diff --git a/program/estimator/vertical_estimator.c b/program/estimator/vertical_estimator.c deleted file mode 100644 index 99a7eddd..00000000 --- a/program/estimator/vertical_estimator.c +++ /dev/null @@ -1,147 +0,0 @@ -//vertical_estimator.c - -#include "vertical_estimator.h" - - - -//#define VZD_DEBUGGING - -#ifdef VZD_DEBUGGING -#include -#include "usart.h" - uint8_t _buff_push[100]; -#endif - -void vertical_estimator_init(vertical_data_t* raw_data,vertical_data_t* filtered_data){ - - raw_data->Z =0.0; - raw_data->Zd =0.0; - raw_data->Zdd =0.0; - - filtered_data->Z=0.0; - filtered_data->Zd=0.0; - filtered_data->Zdd=0.0; -} - - float V_Z_Baro_lp = 0.0f; - float V_Zd_INS=0.0; - float V_Zd_INS_error=0.0; - float V_Zd_INS_longterm_error=0.0; - float V_Zd_INS_longTermOffset=0.0; - float V_Zdd_INS_error=0.0; - //float V_Zd_INS_beforeCorrection; - - float V_Zd_Baro_Prev=0.0; - float V_Zd_INS_error_Prev=0.0; - - float g_offset =-0.005f; - - -void vertical_sense(vertical_data_t* vertical_filtered_data,vertical_data_t* vertical_raw_data,imu_data_t* imu_raw_data, euler_trigonometry_t* negative_euler){ - - float estAlt_prev= V_Z_Baro_lp; - float Axx=0.0,Azx=0.0; //,Ayx=0.0 - float Az_rotated;//Ax_rotated=0.0,Ay_rotated, - - float V_Zd_INS_current_error; - float V_Zdd_INS_current_error; - float g_earth = 1.0f; - float del_g_adder; - float f=4000.0f; - float dt=1.0f/f; - - - float Z_INS_Alpha=0.00004f,Zd_INS_Alpha=0.0001f,Zdd_INS_error_Alpha=0.005f; - /* Update barometer data */ - - if(!ADS1246_DRDY_PIN_STATE()){ - vertical_raw_data->Z = barometer_read_altitude() ; - V_Z_Baro_lp= lowpass_float(&V_Z_Baro_lp, &vertical_raw_data->Z, 0.005f); - - vertical_raw_data->Zd = (V_Z_Baro_lp- estAlt_prev)*1000.0f; // Have to define it somewhere; - - } - - vertical_filtered_data->Z += vertical_filtered_data->Zd*CONTROL_DT; - - if (abs((int32_t)((vertical_filtered_data->Z) - V_Z_Baro_lp))<(int32_t)300){ - vertical_filtered_data->Z = V_Z_Baro_lp * Z_INS_Alpha + vertical_filtered_data->Z * (1.0f- Z_INS_Alpha); - }else{ - - vertical_filtered_data->Z = V_Z_Baro_lp ; - - - } - - - /* S/(negative_euler -> C_roll)/pitch will now be calculated from estimator.c precal function*/ - - Axx = imu_raw_data->acc[0]; - //Ayx = imu_raw_data->acc[1]*(negative_euler -> C_roll)+imu_raw_data->acc[2]*(negative_euler -> S_roll); - Azx = -imu_raw_data->acc[1]*(negative_euler -> S_roll)+imu_raw_data->acc[2]*(negative_euler -> C_roll); - - //Ax_rotated=Axx*(negative_euler -> C_pitch)-Azx*(negative_euler -> S_pitch); - //Ay_rotated=Ayx; - Az_rotated=Axx*(negative_euler -> S_pitch)+Azx*(negative_euler -> C_pitch); - - vertical_filtered_data->Zdd = Az_rotated; - - /* Rotation matrix */ - - - /* Starting main algorithm */ - - V_Zd_INS+=(Az_rotated-g_earth-g_offset )*9.81f*100.0f*dt; - V_Zd_INS_error = V_Zd_INS-vertical_raw_data->Zd ; - - - /* estimate longterm error haven't been corrected */ - V_Zd_INS_current_error = vertical_filtered_data->Zd - vertical_raw_data->Zd; - V_Zd_INS_longterm_error = lowpass_float(&V_Zd_INS_longterm_error,&V_Zd_INS_current_error,0.00000001f); // may not be long term enough for new one - - /* apply longterm error correction */ - V_Zd_INS_longTermOffset+=V_Zd_INS_longterm_error*1.0f*1000.5f; - /* substract applied longterm error from bank */ - V_Zd_INS_longterm_error-=V_Zd_INS_longterm_error*0.210f; - vertical_filtered_data->Zd =V_Zd_INS-V_Zd_INS_longTermOffset; - - /* estimate the stray acceleration with lowpass filter */ - V_Zdd_INS_current_error = (V_Zd_INS_error-V_Zd_INS_error_Prev)*f*0.01f; - V_Zdd_INS_error = lowpass_float(&V_Zdd_INS_error,&V_Zdd_INS_current_error,Zdd_INS_error_Alpha); - - /* calibrating earth's gravity offset */ - del_g_adder=0.00005f*V_Zdd_INS_error*0.1f; - - g_offset+=del_g_adder; - - - /* complementary filter for integrity */ - //V_Zd_INS_beforeCorrection=V_Zd_INS; - vertical_filtered_data->Zd = vertical_raw_data->Zd * Zd_INS_Alpha+(1.0f-Zd_INS_Alpha)*vertical_filtered_data->Zd; - - /* memory storage for next iteration */ - //V_Zd_INS_correctionOffset=V_Zd_INS-V_Zd_INS_beforeCorrection; - V_Zd_Baro_Prev=vertical_raw_data->Zd; - V_Zd_INS_error_Prev=V_Zd_INS_error; - -#ifdef VZD_DEBUGGING - - if (DMA_GetFlagStatus(DMA1_Stream6, DMA_FLAG_TCIF6) != RESET) { - - _buff_push[7] = 0;_buff_push[8] = 0;_buff_push[9] = 0;_buff_push[10] = 0;_buff_push[11] = 0;_buff_push[12] = 0; _buff_push[13] = 0; - - sprintf((char *)_buff_push, "%ld,%ld,%ld,%ld,%d,100000000000,\r\n", - (int32_t)(V_Z_Baro_lp* 1.0f), - (int32_t)(vertical_filtered_data->Z* 1.0f), - (int32_t)(vertical_filtered_data->Zd * 1.0f), - (int32_t)(g_offset * 100000.0f), - (int16_t)(V_Zd_INS * 1.0f)); - - usart2_dma_send(_buff_push); - - - } -#endif -} - - From 129619841eac79186ee601ec03a876f190164c46 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 23:35:24 +0800 Subject: [PATCH 05/14] unify formate, clean some path variable --- program/Makefile | 57 ++++++++++++++++--------------- program/estimator/Makefile | 12 +++---- program/estimator/libestimator.a | Bin 20562 -> 20562 bytes program/makefiles/rules.mk | 1 + program/makefiles/toolchain.mk | 10 +++--- program/makefiles/workspace.mk | 29 ++++++++-------- 6 files changed, 57 insertions(+), 52 deletions(-) diff --git a/program/Makefile b/program/Makefile index 9ff01605..44e8eb70 100644 --- a/program/Makefile +++ b/program/Makefile @@ -2,16 +2,15 @@ PROJECT=firmware EXECUTABLE=$(PROJECT).elf BIN_IMAGE=$(PROJECT).bin -TEST_EXE=run_test + export WORKSPACE_DIR=./ -#============================================================================# +# +#include .mk include ./makefiles/toolchain.mk include ./makefiles/workspace.mk include ./makefiles/rules.mk -#============================================================================# - -#============================================================================# - +# +#object file dir STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o EXTERNAL_DEVICE_SRC = $(EXTERNAL_DEVICE)/AT24C04C.o \ $(EXTERNAL_DEVICE)/mpu9250.o \ @@ -30,18 +29,20 @@ MCU_PERIPH_SRC = \ $(MCU_PERIPH)/system_time.o ACTUATORS_SRC = $(ACTUATORS)/pwm.o + RADIO_CONTROLLER_SRC = $(RADIO_CONTROLLER)/radio_control.o \ $(RADIO_CONTROLLER)/pwm_decoder.o + COMMON_SRC =$(COMMON)/test_common.o \ $(COMMON)/memory.o \ $(COMMON)/io.o \ $(COMMON)/std.o CONTROLLER_SRC = $(CONTROLLER)/attitude_stabilizer.o \ - $(CONTROLLER)/vertical_stabilizer.o \ - $(CONTROLLER)/navigation.o \ - $(CONTROLLER)/flight_controller.o \ - $(CONTROLLER)/controller.o + $(CONTROLLER)/vertical_stabilizer.o \ + $(CONTROLLER)/navigation.o \ + $(CONTROLLER)/flight_controller.o \ + $(CONTROLLER)/controller.o FREERTOS_SRC=$(FREERTOS)/Source/croutine.o \ $(FREERTOS)/Source/list.o \ @@ -55,7 +56,7 @@ MAVLINK_SRC=$(MAVLINK)/communication.o \ $(MAVLINK)/mission.o \ $(MAVLINK)/parameter.o \ $(MAVLINK)/command_parser.o \ - $(MAVLINK)/global.o + $(MAVLINK)/global.o OBJS= $(WORKSPACE_DIR)system_stm32f4xx.o \ $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ @@ -77,10 +78,11 @@ OBJS= $(WORKSPACE_DIR)system_stm32f4xx.o \ $(ESTIMATOR_SRC) $(ACTUATORS_SRC) $(RADIO_CONTROLLER_SRC) \ $(COMMON_SRC) $(CONTROLLER_SRC) $(FREERTOS_SRC) \ $(MAVLINK_SRC) - -#Make all + +# +#make target all:$(BIN_IMAGE) $(BIN_IMAGE):$(EXECUTABLE) @@ -88,41 +90,43 @@ $(BIN_IMAGE):$(EXECUTABLE) @echo 'OBJCOPY $(BIN_IMAGE)' $(EXECUTABLE): $(OBJS) - @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ + @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ @echo 'LD $(EXECUTABLE)' -PC_SIM:$(TEST_EXE) - -$(TEST_EXE):$(HOST_SRC) - $(HOST_CC) $(HOST_CFLAG) $^ -o $@ -#Make clean clean: rm -rf $(STARTUP_OBJ) rm -rf $(EXECUTABLE) rm -rf $(BIN_IMAGE) rm -f $(OBJS) -#Make flash +# +#upload firmware through st-flash flash: st-flash write $(BIN_IMAGE) 0x8000000 -#Make openocd +# +#create gdb server through openocd openocd: flash openocd -f ../debug/openocd.cfg -#Make cgdb +# +#execute cgdb cgdb: cgdb -d $(GDB) -x ./st_util_init.gdb -#Make gdbtui +# +#execute gdbtui gdbtui: $(GDB) -tui -x ./st_util_init.gdb -#Make gdbauto -gdbauto: cgdb +# +#upload firmware through black magic probe flash_bmp: $(GDB) firmware.elf -x ./gdb_black_magic.gdb -cgdb_bmp: +# +#execute and connect to black magic gdb server, no needs to open a +#local sever in PC +cgdb_bmp: cgdb -d $(GDB) firmware.elf -x ./bmp_gdbinit.gdb flash_openocd: openocd -f interface/stlink-v2.cfg \ @@ -136,6 +140,5 @@ flash_openocd: #automatically formate astyle: astyle -r --exclude=lib *.c *.h -#============================================================================# .PHONY:all clean flash openocd gdbauto gdbtui cgdb astyle diff --git a/program/estimator/Makefile b/program/estimator/Makefile index be5c01ca..4be77d8e 100644 --- a/program/estimator/Makefile +++ b/program/estimator/Makefile @@ -1,20 +1,20 @@ -export WORKSPACE_DIR=../ +export WORKSPACE_DIR=.. +# +#include makefiles include $(WORKSPACE_DIR)/makefiles/toolchain.mk include $(WORKSPACE_DIR)/makefiles/workspace.mk include $(WORKSPACE_DIR)/makefiles/rules.mk LIB_ESTIMATOR=libestimator.a - -ESTIMATOR_SRC = $(WORKSPACE_DIR)/estimator/ - +ESTIMATOR_SRC = $(WORKSPACE_DIR)/estimator ESTIMATOR_OBJS= $(ESTIMATOR_SRC)/attitude_estimator.o \ $(ESTIMATOR_SRC)/vertical_estimator.o \ $(ESTIMATOR_SRC)/estimator.o - +#make target all: $(LIB_ESTIMATOR) $(LIB_ESTIMATOR): $(ESTIMATOR_OBJS) $(AR) -r $(LIB_ESTIMATOR) $(ESTIMATOR_OBJS) $(RANLIB) $(LIB_ESTIMATOR) -clean: +clean: rm -rf $(LIB_ESTIMATOR) \ No newline at end of file diff --git a/program/estimator/libestimator.a b/program/estimator/libestimator.a index de4cadca2d9c8aae6aed871f88c4877c5041f32b..728ec4e24c6c66c89c5e5c725b8b7b786d8e9f9b 100644 GIT binary patch delta 59 zcmcb#fbr4-#tE{lmZnA~<{OnlnSd-qbMwg$l*KkrV)9gka5q0tb_c0}$v8O*@B;uO Cw-I~* delta 59 zcmcb#fbr4-#tE{l=4Pg5mK&8qnINpm50u3=Ph#>^gm5=MP Date: Mon, 15 Sep 2014 23:38:33 +0800 Subject: [PATCH 06/14] move primary makefile to the root of dir not finished --- program/Makefile => Makefile | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename program/Makefile => Makefile (100%) diff --git a/program/Makefile b/Makefile similarity index 100% rename from program/Makefile rename to Makefile From 90b23d3d37758b085c0ff52bf3bf1cd0747414a1 Mon Sep 17 00:00:00 2001 From: fboris Date: Mon, 15 Sep 2014 23:46:13 +0800 Subject: [PATCH 07/14] fix some path error --- Makefile | 11 ++++++----- program/makefiles/toolchain.mk | 2 +- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/Makefile b/Makefile index 44e8eb70..bbd514b9 100644 --- a/Makefile +++ b/Makefile @@ -3,12 +3,13 @@ PROJECT=firmware EXECUTABLE=$(PROJECT).elf BIN_IMAGE=$(PROJECT).bin -export WORKSPACE_DIR=./ +export WORKSPACE_DIR=./program + # #include .mk -include ./makefiles/toolchain.mk -include ./makefiles/workspace.mk -include ./makefiles/rules.mk +include $(WORKSPACE_DIR)/makefiles/toolchain.mk +include $(WORKSPACE_DIR)/makefiles/workspace.mk +include $(WORKSPACE_DIR)/makefiles/rules.mk # #object file dir STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o @@ -58,7 +59,7 @@ MAVLINK_SRC=$(MAVLINK)/communication.o \ $(MAVLINK)/command_parser.o \ $(MAVLINK)/global.o -OBJS= $(WORKSPACE_DIR)system_stm32f4xx.o \ +OBJS= $(WORKSPACE_DIR)/system_stm32f4xx.o \ $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ $(CMSIS)/FastMathFunctions/arm_sin_f32.o \ $(ST)/src/misc.o \ diff --git a/program/makefiles/toolchain.mk b/program/makefiles/toolchain.mk index a9d821e4..ed2bb82d 100644 --- a/program/makefiles/toolchain.mk +++ b/program/makefiles/toolchain.mk @@ -29,7 +29,7 @@ ARCH_FLAGS=-mlittle-endian -mthumb -mcpu=cortex-m4 \ -mfpu=fpv4-sp-d16 -mfloat-abi=hard LDFLAGS =$(CFLAGS_NEW_LIB_NANO) --static -Wl,--gc-sections \ - -T ./STM32F427VI_FLASH.ld + -T $(WORKSPACE_DIR)/STM32F427VI_FLASH.ld LDLIBS = -Wl,--start-group -lm -L$(ESTIMATOR) -lestimator -Wl,--end-group From fb5fee77b5a858e0f855206ea8175f10af04624e Mon Sep 17 00:00:00 2001 From: fboris Date: Tue, 16 Sep 2014 13:52:22 +0800 Subject: [PATCH 08/14] change target name, let making .bin and .elf be a rule --- Makefile | 30 ++++++++++-------------------- program/makefiles/rules.mk | 12 +++++++++++- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/Makefile b/Makefile index bbd514b9..86371094 100644 --- a/Makefile +++ b/Makefile @@ -1,15 +1,13 @@ -#Output files -PROJECT=firmware -EXECUTABLE=$(PROJECT).elf -BIN_IMAGE=$(PROJECT).bin - export WORKSPACE_DIR=./program +#Primary firmware target +export FIRMWARE=./firmware + # #include .mk include $(WORKSPACE_DIR)/makefiles/toolchain.mk include $(WORKSPACE_DIR)/makefiles/workspace.mk -include $(WORKSPACE_DIR)/makefiles/rules.mk + # #object file dir STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o @@ -80,30 +78,22 @@ OBJS= $(WORKSPACE_DIR)/system_stm32f4xx.o \ $(COMMON_SRC) $(CONTROLLER_SRC) $(FREERTOS_SRC) \ $(MAVLINK_SRC) - +include $(WORKSPACE_DIR)/makefiles/rules.mk # #make target -all:$(BIN_IMAGE) - -$(BIN_IMAGE):$(EXECUTABLE) - @$(OBJCOPY) -O binary $^ $@ - @echo 'OBJCOPY $(BIN_IMAGE)' - -$(EXECUTABLE): $(OBJS) - @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ - @echo 'LD $(EXECUTABLE)' +all: $(FIRMWARE).bin $(FIRMWARE).elf clean: rm -rf $(STARTUP_OBJ) - rm -rf $(EXECUTABLE) - rm -rf $(BIN_IMAGE) + rm -rf $(FIRMWARE).elf + rm -rf $(FIRMWARE).bin rm -f $(OBJS) # #upload firmware through st-flash flash: - st-flash write $(BIN_IMAGE) 0x8000000 + st-flash write $(FIRMWARE).bin 0x8000000 # #create gdb server through openocd @@ -136,7 +126,7 @@ flash_openocd: -c "reset init" \ -c "halt" \ -c "flash write_image erase $(PROJECT).elf" \ - -c "verify_image $(PROJECT).elf" \ + -c "verify_image $(FIRMWARE).elf" \ -c "reset run" -c shutdown #automatically formate astyle: diff --git a/program/makefiles/rules.mk b/program/makefiles/rules.mk index 1f963aba..48d2b947 100644 --- a/program/makefiles/rules.mk +++ b/program/makefiles/rules.mk @@ -1,9 +1,19 @@ # #makefile rules +%.bin: %.elf + @$(OBJCOPY) -O binary $^ $@ + @echo 'OBJCOPY $<' + +%.elf: $(OBJS) + @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ + @echo 'LD $^' + %.o: %.c @$(CC) $(CFLAGS) -c $< -o $@ @echo 'CC $<' %.o: %.s @$(CC) $(CFLAGS) -c $< -o $@ - @echo 'CC $<' \ No newline at end of file + @echo 'CC $<' + +.PRECIOUS: $(OBJS) %.bin %.elf \ No newline at end of file From 26f44dcaf61a8580e292e0b35b9f26291fc25631 Mon Sep 17 00:00:00 2001 From: fboris Date: Wed, 17 Sep 2014 16:15:38 +0800 Subject: [PATCH 09/14] move object file list to board.mk --- Makefile | 66 +---------------------- program/board/vertigo-v2/board_config.mk | 68 ++++++++++++++++++++++++ 2 files changed, 69 insertions(+), 65 deletions(-) diff --git a/Makefile b/Makefile index 86371094..be35b6f5 100644 --- a/Makefile +++ b/Makefile @@ -10,73 +10,9 @@ include $(WORKSPACE_DIR)/makefiles/workspace.mk # #object file dir -STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o -EXTERNAL_DEVICE_SRC = $(EXTERNAL_DEVICE)/AT24C04C.o \ - $(EXTERNAL_DEVICE)/mpu9250.o \ - $(EXTERNAL_DEVICE)/hmc5983.o \ - $(EXTERNAL_DEVICE)/lea6h_ubx.o \ - $(EXTERNAL_DEVICE)/ADS1246_MPX6115A.o +include $(WORKSPACE_DIR)/board/vertigo-v2/board_config.mk -MCU_PERIPH_SRC = \ - $(MCU_PERIPH)/i2c.o \ - $(MCU_PERIPH)/spi.o \ - $(MCU_PERIPH)/gpio.o \ - $(MCU_PERIPH)/tim.o \ - $(MCU_PERIPH)/led.o \ - $(MCU_PERIPH)/usart.o \ - $(MCU_PERIPH)/input_capture.o \ - $(MCU_PERIPH)/system_time.o -ACTUATORS_SRC = $(ACTUATORS)/pwm.o - -RADIO_CONTROLLER_SRC = $(RADIO_CONTROLLER)/radio_control.o \ - $(RADIO_CONTROLLER)/pwm_decoder.o - -COMMON_SRC =$(COMMON)/test_common.o \ - $(COMMON)/memory.o \ - $(COMMON)/io.o \ - $(COMMON)/std.o - -CONTROLLER_SRC = $(CONTROLLER)/attitude_stabilizer.o \ - $(CONTROLLER)/vertical_stabilizer.o \ - $(CONTROLLER)/navigation.o \ - $(CONTROLLER)/flight_controller.o \ - $(CONTROLLER)/controller.o - -FREERTOS_SRC=$(FREERTOS)/Source/croutine.o \ - $(FREERTOS)/Source/list.o \ - $(FREERTOS)/Source/queue.o \ - $(FREERTOS)/Source/tasks.o \ - $(FREERTOS)/Source/timers.o \ - $(FREERTOS)/Source/portable/MemMang/heap_1.o \ - $(FREERTOS)/Source/portable/GCC/ARM_CM4F/port.o - -MAVLINK_SRC=$(MAVLINK)/communication.o \ - $(MAVLINK)/mission.o \ - $(MAVLINK)/parameter.o \ - $(MAVLINK)/command_parser.o \ - $(MAVLINK)/global.o - -OBJS= $(WORKSPACE_DIR)/system_stm32f4xx.o \ - $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ - $(CMSIS)/FastMathFunctions/arm_sin_f32.o \ - $(ST)/src/misc.o \ - $(ST)/src/stm32f4xx_rcc.o \ - $(ST)/src/stm32f4xx_dma.o \ - $(ST)/src/stm32f4xx_flash.o \ - $(ST)/src/stm32f4xx_gpio.o \ - $(ST)/src/stm32f4xx_usart.o \ - $(ST)/src/stm32f4xx_tim.o \ - $(ST)/src/stm32f4xx_spi.o \ - $(ST)/src/stm32f4xx_i2c.o \ - $(ST)/src/stm32f4xx_sdio.o \ - $(WORKSPACE_DIR)/interrupt.o \ - $(WORKSPACE_DIR)/main.o \ - $(STARTUP) \ - $(EXTERNAL_DEVICE_SRC) $(MCU_PERIPH_SRC) \ - $(ESTIMATOR_SRC) $(ACTUATORS_SRC) $(RADIO_CONTROLLER_SRC) \ - $(COMMON_SRC) $(CONTROLLER_SRC) $(FREERTOS_SRC) \ - $(MAVLINK_SRC) include $(WORKSPACE_DIR)/makefiles/rules.mk diff --git a/program/board/vertigo-v2/board_config.mk b/program/board/vertigo-v2/board_config.mk index 9105a388..711ba0b2 100644 --- a/program/board/vertigo-v2/board_config.mk +++ b/program/board/vertigo-v2/board_config.mk @@ -1 +1,69 @@ TARGET_BOARD='Vertigo v2.0' + +STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o +EXTERNAL_DEVICE_SRC = $(EXTERNAL_DEVICE)/AT24C04C.o \ + $(EXTERNAL_DEVICE)/mpu9250.o \ + $(EXTERNAL_DEVICE)/hmc5983.o \ + $(EXTERNAL_DEVICE)/lea6h_ubx.o \ + $(EXTERNAL_DEVICE)/ADS1246_MPX6115A.o + +MCU_PERIPH_SRC = \ + $(MCU_PERIPH)/i2c.o \ + $(MCU_PERIPH)/spi.o \ + $(MCU_PERIPH)/gpio.o \ + $(MCU_PERIPH)/tim.o \ + $(MCU_PERIPH)/led.o \ + $(MCU_PERIPH)/usart.o \ + $(MCU_PERIPH)/input_capture.o \ + $(MCU_PERIPH)/system_time.o + +ACTUATORS_SRC = $(ACTUATORS)/pwm.o + +RADIO_CONTROLLER_SRC = $(RADIO_CONTROLLER)/radio_control.o \ + $(RADIO_CONTROLLER)/pwm_decoder.o + +COMMON_SRC =$(COMMON)/test_common.o \ + $(COMMON)/memory.o \ + $(COMMON)/io.o \ + $(COMMON)/std.o + +CONTROLLER_SRC = $(CONTROLLER)/attitude_stabilizer.o \ + $(CONTROLLER)/vertical_stabilizer.o \ + $(CONTROLLER)/navigation.o \ + $(CONTROLLER)/flight_controller.o \ + $(CONTROLLER)/controller.o + +FREERTOS_SRC=$(FREERTOS)/Source/croutine.o \ + $(FREERTOS)/Source/list.o \ + $(FREERTOS)/Source/queue.o \ + $(FREERTOS)/Source/tasks.o \ + $(FREERTOS)/Source/timers.o \ + $(FREERTOS)/Source/portable/MemMang/heap_1.o \ + $(FREERTOS)/Source/portable/GCC/ARM_CM4F/port.o + +MAVLINK_SRC=$(MAVLINK)/communication.o \ + $(MAVLINK)/mission.o \ + $(MAVLINK)/parameter.o \ + $(MAVLINK)/command_parser.o \ + $(MAVLINK)/global.o + +OBJS= $(WORKSPACE_DIR)/system_stm32f4xx.o \ + $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ + $(CMSIS)/FastMathFunctions/arm_sin_f32.o \ + $(ST)/src/misc.o \ + $(ST)/src/stm32f4xx_rcc.o \ + $(ST)/src/stm32f4xx_dma.o \ + $(ST)/src/stm32f4xx_flash.o \ + $(ST)/src/stm32f4xx_gpio.o \ + $(ST)/src/stm32f4xx_usart.o \ + $(ST)/src/stm32f4xx_tim.o \ + $(ST)/src/stm32f4xx_spi.o \ + $(ST)/src/stm32f4xx_i2c.o \ + $(ST)/src/stm32f4xx_sdio.o \ + $(WORKSPACE_DIR)/interrupt.o \ + $(WORKSPACE_DIR)/main.o \ + $(STARTUP) \ + $(EXTERNAL_DEVICE_SRC) $(MCU_PERIPH_SRC) \ + $(ESTIMATOR_SRC) $(ACTUATORS_SRC) $(RADIO_CONTROLLER_SRC) \ + $(COMMON_SRC) $(CONTROLLER_SRC) $(FREERTOS_SRC) \ + $(MAVLINK_SRC) \ No newline at end of file From 1a38e0e635785bb60620185cf4dc8e6070519655 Mon Sep 17 00:00:00 2001 From: fboris Date: Wed, 17 Sep 2014 16:26:36 +0800 Subject: [PATCH 10/14] make obj list with src list --- Makefile | 2 +- program/board/vertigo-v2/board_config.mk | 135 +++++++++++++---------- 2 files changed, 77 insertions(+), 60 deletions(-) diff --git a/Makefile b/Makefile index be35b6f5..fe0565c4 100644 --- a/Makefile +++ b/Makefile @@ -12,7 +12,7 @@ include $(WORKSPACE_DIR)/makefiles/workspace.mk #object file dir include $(WORKSPACE_DIR)/board/vertigo-v2/board_config.mk - +OBJS = $(sort $(patsubst %c, %o, $(SRCS) )) include $(WORKSPACE_DIR)/makefiles/rules.mk diff --git a/program/board/vertigo-v2/board_config.mk b/program/board/vertigo-v2/board_config.mk index 711ba0b2..615152d9 100644 --- a/program/board/vertigo-v2/board_config.mk +++ b/program/board/vertigo-v2/board_config.mk @@ -1,69 +1,86 @@ TARGET_BOARD='Vertigo v2.0' -STARTUP=$(WORKSPACE_DIR)/startup_stm32f427xx.o -EXTERNAL_DEVICE_SRC = $(EXTERNAL_DEVICE)/AT24C04C.o \ - $(EXTERNAL_DEVICE)/mpu9250.o \ - $(EXTERNAL_DEVICE)/hmc5983.o \ - $(EXTERNAL_DEVICE)/lea6h_ubx.o \ - $(EXTERNAL_DEVICE)/ADS1246_MPX6115A.o +STARTUP_SRCS=$(WORKSPACE_DIR)/startup_stm32f427xx.c +EXTERNAL_DEVICE_SRCS = $(EXTERNAL_DEVICE)/AT24C04C.c \ + $(EXTERNAL_DEVICE)/mpu9250.c \ + $(EXTERNAL_DEVICE)/hmc5983.c \ + $(EXTERNAL_DEVICE)/lea6h_ubx.c \ + $(EXTERNAL_DEVICE)/ADS1246_MPX6115A.c -MCU_PERIPH_SRC = \ - $(MCU_PERIPH)/i2c.o \ - $(MCU_PERIPH)/spi.o \ - $(MCU_PERIPH)/gpio.o \ - $(MCU_PERIPH)/tim.o \ - $(MCU_PERIPH)/led.o \ - $(MCU_PERIPH)/usart.o \ - $(MCU_PERIPH)/input_capture.o \ - $(MCU_PERIPH)/system_time.o +MCU_PERIPH_SRCS = \ + $(MCU_PERIPH)/i2c.c \ + $(MCU_PERIPH)/spi.c \ + $(MCU_PERIPH)/gpio.c \ + $(MCU_PERIPH)/tim.c \ + $(MCU_PERIPH)/led.c \ + $(MCU_PERIPH)/usart.c \ + $(MCU_PERIPH)/input_capture.c \ + $(MCU_PERIPH)/system_time.c -ACTUATORS_SRC = $(ACTUATORS)/pwm.o +ACTUATORS_SRCS = $(ACTUATORS)/pwm.c -RADIO_CONTROLLER_SRC = $(RADIO_CONTROLLER)/radio_control.o \ - $(RADIO_CONTROLLER)/pwm_decoder.o +RADIO_CONTROLLER_SRCS = $(RADIO_CONTROLLER)/radio_control.c \ + $(RADIO_CONTROLLER)/pwm_decoder.c -COMMON_SRC =$(COMMON)/test_common.o \ - $(COMMON)/memory.o \ - $(COMMON)/io.o \ - $(COMMON)/std.o +COMMON_SRCS =$(COMMON)/test_common.c \ + $(COMMON)/memory.c \ + $(COMMON)/io.c \ + $(COMMON)/std.c -CONTROLLER_SRC = $(CONTROLLER)/attitude_stabilizer.o \ - $(CONTROLLER)/vertical_stabilizer.o \ - $(CONTROLLER)/navigation.o \ - $(CONTROLLER)/flight_controller.o \ - $(CONTROLLER)/controller.o +CONTROLLER_SRCS = $(CONTROLLER)/attitude_stabilizer.c \ + $(CONTROLLER)/vertical_stabilizer.c \ + $(CONTROLLER)/navigation.c \ + $(CONTROLLER)/flight_controller.c \ + $(CONTROLLER)/controller.c -FREERTOS_SRC=$(FREERTOS)/Source/croutine.o \ - $(FREERTOS)/Source/list.o \ - $(FREERTOS)/Source/queue.o \ - $(FREERTOS)/Source/tasks.o \ - $(FREERTOS)/Source/timers.o \ - $(FREERTOS)/Source/portable/MemMang/heap_1.o \ - $(FREERTOS)/Source/portable/GCC/ARM_CM4F/port.o +FREERTOS_SRCS=$(FREERTOS)/Source/croutine.c \ + $(FREERTOS)/Source/list.c \ + $(FREERTOS)/Source/queue.c \ + $(FREERTOS)/Source/tasks.c \ + $(FREERTOS)/Source/timers.c \ + $(FREERTOS)/Source/portable/MemMang/heap_1.c \ + $(FREERTOS)/Source/portable/GCC/ARM_CM4F/port.c -MAVLINK_SRC=$(MAVLINK)/communication.o \ - $(MAVLINK)/mission.o \ - $(MAVLINK)/parameter.o \ - $(MAVLINK)/command_parser.o \ - $(MAVLINK)/global.o +MAVLINK_SRCS=$(MAVLINK)/communication.c \ + $(MAVLINK)/mission.c \ + $(MAVLINK)/parameter.c \ + $(MAVLINK)/command_parser.c \ + $(MAVLINK)/global.c -OBJS= $(WORKSPACE_DIR)/system_stm32f4xx.o \ - $(CMSIS)/FastMathFunctions/arm_cos_f32.o \ - $(CMSIS)/FastMathFunctions/arm_sin_f32.o \ - $(ST)/src/misc.o \ - $(ST)/src/stm32f4xx_rcc.o \ - $(ST)/src/stm32f4xx_dma.o \ - $(ST)/src/stm32f4xx_flash.o \ - $(ST)/src/stm32f4xx_gpio.o \ - $(ST)/src/stm32f4xx_usart.o \ - $(ST)/src/stm32f4xx_tim.o \ - $(ST)/src/stm32f4xx_spi.o \ - $(ST)/src/stm32f4xx_i2c.o \ - $(ST)/src/stm32f4xx_sdio.o \ - $(WORKSPACE_DIR)/interrupt.o \ - $(WORKSPACE_DIR)/main.o \ - $(STARTUP) \ - $(EXTERNAL_DEVICE_SRC) $(MCU_PERIPH_SRC) \ - $(ESTIMATOR_SRC) $(ACTUATORS_SRC) $(RADIO_CONTROLLER_SRC) \ - $(COMMON_SRC) $(CONTROLLER_SRC) $(FREERTOS_SRC) \ - $(MAVLINK_SRC) \ No newline at end of file +CMSIS_SRCS= \ + $(CMSIS)/FastMathFunctions/arm_cos_f32.c \ + $(CMSIS)/FastMathFunctions/arm_sin_f32.c + +STMF4_STD_DRIVER_SRCS= \ + $(WORKSPACE_DIR)/system_stm32f4xx.c \ + $(ST)/src/misc.c \ + $(ST)/src/stm32f4xx_rcc.c \ + $(ST)/src/stm32f4xx_dma.c \ + $(ST)/src/stm32f4xx_flash.c \ + $(ST)/src/stm32f4xx_gpio.c \ + $(ST)/src/stm32f4xx_usart.c \ + $(ST)/src/stm32f4xx_tim.c \ + $(ST)/src/stm32f4xx_spi.c \ + $(ST)/src/stm32f4xx_i2c.c \ + $(ST)/src/stm32f4xx_sdio.c + +BASIC_SRCS= \ + $(WORKSPACE_DIR)/interrupt.c \ + $(WORKSPACE_DIR)/main.c \ + + +# +#generate the source file list +# +SRCS += $(STARTUP_SRCS) +SRCS += $(EXTERNAL_DEVICE_SRCS) +SRCS += $(MCU_PERIPH_SRCS) +SRCS += $(ACTUATORS_SRCS) +SRCS += $(RADIO_CONTROLLER_SRCS) +SRCS += $(COMMON_SRCS) +SRCS += $(CONTROLLER_SRCS) +SRCS += $(FREERTOS_SRCS) +SRCS += $(MAVLINK_SRCS) +SRCS += $(CMSIS_SRCS) +SRCS += $(STMF4_STD_DRIVER_SRCS) +SRCS += $(BASIC_SRCS) From 5bf429fd22db1ed7208b3a21f63df4c531910519 Mon Sep 17 00:00:00 2001 From: fboris Date: Sun, 21 Sep 2014 01:58:10 +0800 Subject: [PATCH 11/14] objs will rebuild when any related .h file changes --- Makefile | 6 ++++-- program/makefiles/rules.mk | 3 +++ program/makefiles/toolchain.mk | 2 +- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index fe0565c4..8ad9e712 100644 --- a/Makefile +++ b/Makefile @@ -14,18 +14,20 @@ include $(WORKSPACE_DIR)/board/vertigo-v2/board_config.mk OBJS = $(sort $(patsubst %c, %o, $(SRCS) )) -include $(WORKSPACE_DIR)/makefiles/rules.mk + # #make target all: $(FIRMWARE).bin $(FIRMWARE).elf +include $(WORKSPACE_DIR)/makefiles/rules.mk + clean: rm -rf $(STARTUP_OBJ) rm -rf $(FIRMWARE).elf rm -rf $(FIRMWARE).bin rm -f $(OBJS) - + rm -f $(DEPS) # #upload firmware through st-flash flash: diff --git a/program/makefiles/rules.mk b/program/makefiles/rules.mk index 48d2b947..3fd5005a 100644 --- a/program/makefiles/rules.mk +++ b/program/makefiles/rules.mk @@ -8,6 +8,9 @@ @$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $@ @echo 'LD $^' +DEPS = $(OBJS:.o=.d) +-include $(DEPS) + %.o: %.c @$(CC) $(CFLAGS) -c $< -o $@ @echo 'CC $<' diff --git a/program/makefiles/toolchain.mk b/program/makefiles/toolchain.mk index ed2bb82d..d96a4c24 100644 --- a/program/makefiles/toolchain.mk +++ b/program/makefiles/toolchain.mk @@ -61,4 +61,4 @@ CFLAGS_DEFINE= \ CFLAGS=-g $(ARCH_FLAGS)\ ${CFLAGS_INCLUDE} ${CFLAGS_DEFINE} \ - ${CFLAGS_WARNING} \ No newline at end of file + ${CFLAGS_WARNING} -MMD -MP \ No newline at end of file From 756313716874ab5ea666f5b9720dec5b90bc08ec Mon Sep 17 00:00:00 2001 From: fboris Date: Sun, 21 Sep 2014 10:19:11 +0800 Subject: [PATCH 12/14] Do not track *.d files --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 4a11d007..5acf36fb 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ .tags* *.o +*.d cscope* *.bin *.elf From 2fa520d5837f6c3b529658ae82b560f97e7eba48 Mon Sep 17 00:00:00 2001 From: fboris Date: Thu, 18 Dec 2014 05:22:29 +0800 Subject: [PATCH 13/14] Revert "Delete private source code`" This reverts commit 448134d282e7fef2ed0e57cbb6d51dd9a329a1e6. We can keep it public now. --- program/estimator/Makefile | 20 ++++ program/estimator/attitude_estimator.c | 134 ++++++++++++++++++++++ program/estimator/estimator.c | 11 ++ program/estimator/vertical_estimator.c | 147 +++++++++++++++++++++++++ 4 files changed, 312 insertions(+) create mode 100644 program/estimator/Makefile create mode 100644 program/estimator/attitude_estimator.c create mode 100644 program/estimator/estimator.c create mode 100644 program/estimator/vertical_estimator.c diff --git a/program/estimator/Makefile b/program/estimator/Makefile new file mode 100644 index 00000000..be5c01ca --- /dev/null +++ b/program/estimator/Makefile @@ -0,0 +1,20 @@ +export WORKSPACE_DIR=../ +include $(WORKSPACE_DIR)/makefiles/toolchain.mk +include $(WORKSPACE_DIR)/makefiles/workspace.mk +include $(WORKSPACE_DIR)/makefiles/rules.mk + +LIB_ESTIMATOR=libestimator.a + +ESTIMATOR_SRC = $(WORKSPACE_DIR)/estimator/ + +ESTIMATOR_OBJS= $(ESTIMATOR_SRC)/attitude_estimator.o \ + $(ESTIMATOR_SRC)/vertical_estimator.o \ + $(ESTIMATOR_SRC)/estimator.o + +all: $(LIB_ESTIMATOR) + +$(LIB_ESTIMATOR): $(ESTIMATOR_OBJS) + $(AR) -r $(LIB_ESTIMATOR) $(ESTIMATOR_OBJS) + $(RANLIB) $(LIB_ESTIMATOR) +clean: + rm -rf $(LIB_ESTIMATOR) \ No newline at end of file diff --git a/program/estimator/attitude_estimator.c b/program/estimator/attitude_estimator.c new file mode 100644 index 00000000..8c38ba14 --- /dev/null +++ b/program/estimator/attitude_estimator.c @@ -0,0 +1,134 @@ +#include "attitude_estimator.h" +#include +#include "basic_filter.h" + +void attitude_estimator_init(attitude_t* attitude,imu_data_t* imu_raw_data, imu_data_t *imu_filtered_data,vector3d_f_t* True_R){ + + attitude->roll=0.0; + attitude->pitch=0.0; + attitude->yaw=0.0; + + imu_raw_data->acc[0]=0.0; + imu_raw_data->acc[1]=0.0; + imu_raw_data->acc[2]=1.0; + + imu_filtered_data->acc[0] =0.0; + imu_filtered_data->acc[1] =0.0; + imu_filtered_data->acc[2] =1.0; + + True_R->x =0.0; + True_R->y =0.0; + True_R->z =1.0; + + estimator_trigger_flag=0; +} + +void attitude_sense(attitude_t *attitude, imu_data_t *imu_raw_data, imu_data_t *imu_filtered_data, vector3d_f_t *True_R) +{ + + float accel_lowpass_gain = 0.03f, gyro_lowpass_gain =0.03f,complementAlpha = 0.0001f; + float R_raw = 0.0f, inv_R_raw = 0.0f, R_true = 0.0f, inv_R_true = 0.0f; + float N_Ax_g = 0.0f, N_Ay_g = 0.0f, N_Az_g = 0.0f; + + float f=4000.0f; + float dt=1.0f/f; + float degtorad=0.01745329251994329f; + float delta_gyroX=0.0f,delta_gyroY=0.0f,delta_gyroZ=0.0f; + float predicted_Ax=0.0f,predicted_Ay=0.0f,predicted_Az=0.0f; + + + imu_filtered_data->acc[0] = lowpass_float(&imu_filtered_data->acc[0], &imu_raw_data->acc[0], accel_lowpass_gain); + imu_filtered_data->acc[1] = lowpass_float(&imu_filtered_data->acc[1], &imu_raw_data->acc[1], accel_lowpass_gain); + imu_filtered_data->acc[2] = lowpass_float(&imu_filtered_data->acc[2], &imu_raw_data->acc[2], accel_lowpass_gain); + + imu_filtered_data->gyro[0] = lowpass_float(&imu_filtered_data->gyro[0], &imu_raw_data->gyro[0], gyro_lowpass_gain); + imu_filtered_data->gyro[1] = lowpass_float(&imu_filtered_data->gyro[1], &imu_raw_data->gyro[1], gyro_lowpass_gain); + imu_filtered_data->gyro[2] = lowpass_float(&imu_filtered_data->gyro[2], &imu_raw_data->gyro[2], gyro_lowpass_gain); + + R_raw = sqrtf(imu_filtered_data->acc[0] * imu_filtered_data->acc[0] + imu_filtered_data->acc[1] * imu_filtered_data->acc[1] + imu_filtered_data->acc[2] * imu_filtered_data->acc[2]); + inv_R_raw = 1.0f / R_raw; + N_Ax_g = imu_filtered_data->acc[0] * inv_R_raw; + N_Ay_g = imu_filtered_data->acc[1] * inv_R_raw; + N_Az_g = imu_filtered_data->acc[2] * inv_R_raw; + + delta_gyroX = imu_raw_data->gyro[0] * dt * degtorad; + delta_gyroY = imu_raw_data->gyro[1] * dt * degtorad; + delta_gyroZ = imu_raw_data->gyro[2] * dt * degtorad; + + + (True_R->x) = (True_R->x) + (True_R->y) * delta_gyroZ; + (True_R->y) = - (True_R->x) * delta_gyroZ + (True_R->y); + + (True_R->y) = (True_R->y) + (True_R->z) * delta_gyroX; + (True_R->z) = - (True_R->y) * delta_gyroX + (True_R->z) ; + + (True_R->x) = (True_R->x) - (True_R->z) * delta_gyroY ; + (True_R->z) = (True_R->x) * delta_gyroY + (True_R->z); + + predicted_Ax = (True_R->x); + predicted_Ay = (True_R->y); + predicted_Az = (True_R->z); + + + (True_R->x) = (1.0f - complementAlpha) * (predicted_Ax) + complementAlpha * (N_Ax_g); + (True_R->y) = (1.0f - complementAlpha) * (predicted_Ay) + complementAlpha * (N_Ay_g); + (True_R->z) = (1.0f - complementAlpha) * (predicted_Az) + complementAlpha * (N_Az_g); + + + R_true = sqrtf((True_R->x)*(True_R->x) + (True_R->y)*(True_R->y) + (True_R->z)*(True_R->z)); + inv_R_true = 1.0f/R_true; + (True_R->x) =(True_R->x) *inv_R_true; + (True_R->y) =(True_R->y) *inv_R_true; + (True_R->z) =(True_R->z) *inv_R_true; + + + attitude->roll=atanf(True_R->y/True_R->z)*57.2957795130823f; + + attitude->pitch=atanf(-True_R->x/sqrtf(True_R->y*True_R->y+True_R->z*True_R->z))*57.2957795130823f; + + + +} + + +void heading_sense(attitude_t *attitude,imu_data_t *imu_raw_data,euler_trigonometry_t* negative_euler){ + +float MagXx=0.0f,MagYx=0.0f,MagZx=0.0f; +float MagX_rotated=0.0f,MagY_rotated=0.0f;//,MagZ_rotated=0.0f; + + MagXx = imu_raw_data->mag[0]; + MagYx = imu_raw_data->mag[1]*(negative_euler -> C_roll)+imu_raw_data->mag[2]*(negative_euler -> S_roll); + MagZx = -imu_raw_data->mag[1]*(negative_euler -> S_roll)+imu_raw_data->mag[2]*(negative_euler -> C_roll); + + MagX_rotated=MagXx*(negative_euler -> C_pitch)-MagZx*(negative_euler -> S_pitch); + MagY_rotated=MagYx; + //MagZ_rotated=MagXx*(negative_euler -> S_pitch)+MagZx*(negative_euler -> C_pitch); + + attitude -> yaw = atan2f(-MagY_rotated,MagX_rotated)*57.32484076433121f; + + + if((attitude -> yaw) <0.0f){ + + (attitude -> yaw) += 360.0f; + } + + +} + + +void attitude_update(attitude_t *attitude, imu_data_t *imu_filtered_data, vector3d_f_t *predicted_g_data,imu_unscaled_data_t *imu_unscaled_data,imu_data_t *imu_raw_data,imu_calibrated_offset_t *imu_offset){ + + + imu_update(imu_unscaled_data); + imu_scale_data(imu_unscaled_data, imu_raw_data, imu_offset); + #ifdef USE_MAGNETIC_HEADING + magnetometer_update(imu_unscaled_data); + magnetometer_scale_data(imu_unscaled_data,imu_raw_data,imu_offset); + #endif + + + attitude_sense(attitude, imu_raw_data, imu_filtered_data, predicted_g_data); + + +} + diff --git a/program/estimator/estimator.c b/program/estimator/estimator.c new file mode 100644 index 00000000..f266c335 --- /dev/null +++ b/program/estimator/estimator.c @@ -0,0 +1,11 @@ +#include "estimator.h" + +void inverse_rotation_trigonometry_precal(attitude_t* attitude,euler_trigonometry_t* negative_euler){ + + /* all global variable */ + negative_euler -> C_roll = arm_cos_f32(attitude->roll * (-0.01745329252392f)); + negative_euler -> S_roll = arm_sin_f32(attitude->roll * (-0.01745329252392f)); + + negative_euler -> C_pitch = arm_cos_f32(attitude->pitch * (-0.01745329252392f)); + negative_euler -> S_pitch = arm_sin_f32(attitude->pitch * (-0.01745329252392f)); +} \ No newline at end of file diff --git a/program/estimator/vertical_estimator.c b/program/estimator/vertical_estimator.c new file mode 100644 index 00000000..99a7eddd --- /dev/null +++ b/program/estimator/vertical_estimator.c @@ -0,0 +1,147 @@ +//vertical_estimator.c + +#include "vertical_estimator.h" + + + +//#define VZD_DEBUGGING + +#ifdef VZD_DEBUGGING +#include +#include "usart.h" + uint8_t _buff_push[100]; +#endif + +void vertical_estimator_init(vertical_data_t* raw_data,vertical_data_t* filtered_data){ + + raw_data->Z =0.0; + raw_data->Zd =0.0; + raw_data->Zdd =0.0; + + filtered_data->Z=0.0; + filtered_data->Zd=0.0; + filtered_data->Zdd=0.0; +} + + float V_Z_Baro_lp = 0.0f; + float V_Zd_INS=0.0; + float V_Zd_INS_error=0.0; + float V_Zd_INS_longterm_error=0.0; + float V_Zd_INS_longTermOffset=0.0; + float V_Zdd_INS_error=0.0; + //float V_Zd_INS_beforeCorrection; + + float V_Zd_Baro_Prev=0.0; + float V_Zd_INS_error_Prev=0.0; + + float g_offset =-0.005f; + + +void vertical_sense(vertical_data_t* vertical_filtered_data,vertical_data_t* vertical_raw_data,imu_data_t* imu_raw_data, euler_trigonometry_t* negative_euler){ + + float estAlt_prev= V_Z_Baro_lp; + float Axx=0.0,Azx=0.0; //,Ayx=0.0 + float Az_rotated;//Ax_rotated=0.0,Ay_rotated, + + float V_Zd_INS_current_error; + float V_Zdd_INS_current_error; + float g_earth = 1.0f; + float del_g_adder; + float f=4000.0f; + float dt=1.0f/f; + + + float Z_INS_Alpha=0.00004f,Zd_INS_Alpha=0.0001f,Zdd_INS_error_Alpha=0.005f; + /* Update barometer data */ + + if(!ADS1246_DRDY_PIN_STATE()){ + vertical_raw_data->Z = barometer_read_altitude() ; + V_Z_Baro_lp= lowpass_float(&V_Z_Baro_lp, &vertical_raw_data->Z, 0.005f); + + vertical_raw_data->Zd = (V_Z_Baro_lp- estAlt_prev)*1000.0f; // Have to define it somewhere; + + } + + vertical_filtered_data->Z += vertical_filtered_data->Zd*CONTROL_DT; + + if (abs((int32_t)((vertical_filtered_data->Z) - V_Z_Baro_lp))<(int32_t)300){ + vertical_filtered_data->Z = V_Z_Baro_lp * Z_INS_Alpha + vertical_filtered_data->Z * (1.0f- Z_INS_Alpha); + }else{ + + vertical_filtered_data->Z = V_Z_Baro_lp ; + + + } + + + /* S/(negative_euler -> C_roll)/pitch will now be calculated from estimator.c precal function*/ + + Axx = imu_raw_data->acc[0]; + //Ayx = imu_raw_data->acc[1]*(negative_euler -> C_roll)+imu_raw_data->acc[2]*(negative_euler -> S_roll); + Azx = -imu_raw_data->acc[1]*(negative_euler -> S_roll)+imu_raw_data->acc[2]*(negative_euler -> C_roll); + + //Ax_rotated=Axx*(negative_euler -> C_pitch)-Azx*(negative_euler -> S_pitch); + //Ay_rotated=Ayx; + Az_rotated=Axx*(negative_euler -> S_pitch)+Azx*(negative_euler -> C_pitch); + + vertical_filtered_data->Zdd = Az_rotated; + + /* Rotation matrix */ + + + /* Starting main algorithm */ + + V_Zd_INS+=(Az_rotated-g_earth-g_offset )*9.81f*100.0f*dt; + V_Zd_INS_error = V_Zd_INS-vertical_raw_data->Zd ; + + + /* estimate longterm error haven't been corrected */ + V_Zd_INS_current_error = vertical_filtered_data->Zd - vertical_raw_data->Zd; + V_Zd_INS_longterm_error = lowpass_float(&V_Zd_INS_longterm_error,&V_Zd_INS_current_error,0.00000001f); // may not be long term enough for new one + + /* apply longterm error correction */ + V_Zd_INS_longTermOffset+=V_Zd_INS_longterm_error*1.0f*1000.5f; + /* substract applied longterm error from bank */ + V_Zd_INS_longterm_error-=V_Zd_INS_longterm_error*0.210f; + vertical_filtered_data->Zd =V_Zd_INS-V_Zd_INS_longTermOffset; + + /* estimate the stray acceleration with lowpass filter */ + V_Zdd_INS_current_error = (V_Zd_INS_error-V_Zd_INS_error_Prev)*f*0.01f; + V_Zdd_INS_error = lowpass_float(&V_Zdd_INS_error,&V_Zdd_INS_current_error,Zdd_INS_error_Alpha); + + /* calibrating earth's gravity offset */ + del_g_adder=0.00005f*V_Zdd_INS_error*0.1f; + + g_offset+=del_g_adder; + + + /* complementary filter for integrity */ + //V_Zd_INS_beforeCorrection=V_Zd_INS; + vertical_filtered_data->Zd = vertical_raw_data->Zd * Zd_INS_Alpha+(1.0f-Zd_INS_Alpha)*vertical_filtered_data->Zd; + + /* memory storage for next iteration */ + //V_Zd_INS_correctionOffset=V_Zd_INS-V_Zd_INS_beforeCorrection; + V_Zd_Baro_Prev=vertical_raw_data->Zd; + V_Zd_INS_error_Prev=V_Zd_INS_error; + +#ifdef VZD_DEBUGGING + + if (DMA_GetFlagStatus(DMA1_Stream6, DMA_FLAG_TCIF6) != RESET) { + + _buff_push[7] = 0;_buff_push[8] = 0;_buff_push[9] = 0;_buff_push[10] = 0;_buff_push[11] = 0;_buff_push[12] = 0; _buff_push[13] = 0; + + sprintf((char *)_buff_push, "%ld,%ld,%ld,%ld,%d,100000000000,\r\n", + (int32_t)(V_Z_Baro_lp* 1.0f), + (int32_t)(vertical_filtered_data->Z* 1.0f), + (int32_t)(vertical_filtered_data->Zd * 1.0f), + (int32_t)(g_offset * 100000.0f), + (int16_t)(V_Zd_INS * 1.0f)); + + usart2_dma_send(_buff_push); + + + } +#endif +} + + From c3a580149bb4c826798799b05fa6c957d8fd95ae Mon Sep 17 00:00:00 2001 From: fboris Date: Sun, 21 Dec 2014 12:38:00 +0800 Subject: [PATCH 14/14] fix travis ci srcipt --- .travis.yml | 1 - 1 file changed, 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index dc1239a0..bea8a8b8 100644 --- a/.travis.yml +++ b/.travis.yml @@ -9,6 +9,5 @@ before_install: - sudo apt-get install gcc-arm-none-eabi script: - - cd program/ - make - arm-none-eabi-size firmware.elf