mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-17 23:54:34 +08:00
Merge branch 'master' into nav_modules
to get altitude fixes for nav routines * master: (81 commits) [rotorcraft] gps_sim_hitl: set gps alt and hmsl [rotorcraft] simple HITL by using ref as gps [ins] gps_passthrough type for rotorcrafts [ins] no baro update if vf_reset && !baro_initialized [ins] vf_extended: rename update_alt to update_z [ins] Made it possible to use GPS altitude [ins] hf_float: remove inline from functions [ins] hf_float: fix compilation with GPS_LAG [ins] IIR filter replacing mean in hff Use PPM [usec] values for radio config files with SBUS [actuators] dualpwm fixes for nps [actuators] actuators driver that generates dual pwm pulses. [ground_segment] add libprcre to natnet [math] fix resolution in ltp_def rotation matrix [conf] remove obsolete BARO_HAS_BOARD defines [chibios] fix compilation with chibios [datalink] Fixed some small issues with UDP datalink [follow] Fixed following module [modules] Added a module for following based on received remote GPS [ardrone] Updated gains and reference model for inside ... Conflicts: sw/airborne/modules/nav/nav_drop.c sw/airborne/subsystems/navigation/OSAMNav.c sw/airborne/subsystems/navigation/poly_survey_adv.c sw/airborne/subsystems/navigation/spiral.c
This commit is contained in:
+2
-1
@@ -94,6 +94,7 @@
|
||||
/sw/ground_segment/tmtc/diadec
|
||||
/sw/ground_segment/tmtc/ivy_serial_bridge
|
||||
/sw/ground_segment/tmtc/GSM/SMS_GS
|
||||
/sw/ground_segment/tmtc/app_server
|
||||
/sw/ground_segment/tmtc/gpsd2ivy
|
||||
|
||||
# /sw/ground_segment/joystick
|
||||
@@ -140,13 +141,13 @@
|
||||
/sw/supervision/gtk_pc.ml
|
||||
|
||||
# /sw/tools/
|
||||
/sw/tools/fp_parser.ml
|
||||
/sw/tools/wiki_gen/wiki_gen
|
||||
/sw/tools/mergelogs
|
||||
|
||||
# /sw/ground_segment/misc
|
||||
/sw/ground_segment/misc/davis2ivy
|
||||
/sw/ground_segment/misc/kestrel2ivy
|
||||
/sw/ground_segment/misc/natnet2ivy
|
||||
|
||||
|
||||
# /sw/airborne/arch/lpc21/test/bootloader
|
||||
|
||||
@@ -64,7 +64,7 @@ SIMULATOR=sw/simulator
|
||||
MULTIMON=sw/ground_segment/multimon
|
||||
COCKPIT=sw/ground_segment/cockpit
|
||||
TMTC=sw/ground_segment/tmtc
|
||||
TOOLS=$(PAPARAZZI_SRC)/sw/tools
|
||||
GENERATORS=$(PAPARAZZI_SRC)/sw/tools/generators
|
||||
JOYSTICK=sw/ground_segment/joystick
|
||||
EXT=sw/ext
|
||||
|
||||
@@ -121,7 +121,7 @@ conf/%.xml :conf/%_example.xml
|
||||
ground_segment: print_build_version update_google_version conf libpprz subdirs commands static
|
||||
ground_segment.opt: ground_segment cockpit.opt tmtc.opt
|
||||
|
||||
static: cockpit tmtc tools sim_static joystick static_h
|
||||
static: cockpit tmtc generators sim_static joystick static_h
|
||||
|
||||
libpprz:
|
||||
$(MAKE) -C $(LIB)/ocaml
|
||||
@@ -141,8 +141,8 @@ tmtc: libpprz cockpit multimon
|
||||
tmtc.opt: libpprz cockpit.opt multimon
|
||||
$(MAKE) -C $(TMTC) opt
|
||||
|
||||
tools: libpprz
|
||||
$(MAKE) -C $(TOOLS)
|
||||
generators: libpprz
|
||||
$(MAKE) -C $(GENERATORS)
|
||||
|
||||
joystick: libpprz
|
||||
$(MAKE) -C $(JOYSTICK)
|
||||
@@ -168,68 +168,68 @@ $(LOGALIZER): libpprz
|
||||
|
||||
static_h: $(GEN_HEADERS)
|
||||
|
||||
$(MESSAGES_H) : $(MESSAGES_XML) tools
|
||||
$(MESSAGES_H) : $(MESSAGES_XML) generators
|
||||
$(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages.out $< telemetry > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_messages.out $< telemetry > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(MESSAGES2_H) : $(MESSAGES_XML) tools
|
||||
$(MESSAGES2_H) : $(MESSAGES_XML) generators
|
||||
$(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages2.out $< telemetry > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_messages2.out $< telemetry > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(UBX_PROTOCOL_H) : $(UBX_XML) tools
|
||||
$(UBX_PROTOCOL_H) : $(UBX_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_ubx.out $< > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_ubx.out $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(MTK_PROTOCOL_H) : $(MTK_XML) tools
|
||||
$(MTK_PROTOCOL_H) : $(MTK_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_mtk.out $< > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_mtk.out $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(XSENS_PROTOCOL_H) : $(XSENS_XML) tools
|
||||
$(XSENS_PROTOCOL_H) : $(XSENS_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_xsens.out $< > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_xsens.out $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(DL_PROTOCOL_H) : $(MESSAGES_XML) tools
|
||||
$(DL_PROTOCOL_H) : $(MESSAGES_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages.out $< datalink > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_messages.out $< datalink > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(DL_PROTOCOL2_H) : $(MESSAGES_XML) tools
|
||||
$(DL_PROTOCOL2_H) : $(MESSAGES_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages2.out $< datalink > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_messages2.out $< datalink > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(ABI_MESSAGES_H) : $(ABI_XML) tools
|
||||
$(ABI_MESSAGES_H) : $(ABI_XML) generators
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_abi.out $< airborne > $($@_TMP)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_abi.out $< airborne > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
|
||||
include Makefile.ac
|
||||
|
||||
ac_h ac fbw ap: static conf tools ext
|
||||
ac_h ac fbw ap: static conf generators ext
|
||||
|
||||
sim: sim_static
|
||||
|
||||
@@ -307,7 +307,7 @@ test: all replace_current_conf_xml run_tests restore_conf_xml
|
||||
|
||||
|
||||
.PHONY: all print_build_version update_google_version dox ground_segment ground_segment.opt \
|
||||
subdirs $(SUBDIRS) conf ext libpprz multimon cockpit cockpit.opt tmtc tmtc.opt tools\
|
||||
subdirs $(SUBDIRS) conf ext libpprz multimon cockpit cockpit.opt tmtc tmtc.opt generators\
|
||||
static sim_static lpctools commands \
|
||||
clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible \
|
||||
test replace_current_conf_xml run_tests restore_conf_xml
|
||||
|
||||
+17
-17
@@ -31,7 +31,7 @@ AIRBORNE=sw/airborne
|
||||
MESSAGES_XML = $(CONF)/messages.xml
|
||||
ACINCLUDE = $(PAPARAZZI_HOME)/var/$(AIRCRAFT)
|
||||
AIRCRAFT_CONF_DIR = $(ACINCLUDE)/conf
|
||||
AC_GENERATED = $(ACINCLUDE)/generated
|
||||
AC_GENERATED = $(ACINCLUDE)/$(TARGET)/generated
|
||||
|
||||
AIRFRAME_H=$(AC_GENERATED)/airframe.h
|
||||
PERIODIC_H=$(AC_GENERATED)/periodic_telemetry.h
|
||||
@@ -104,16 +104,16 @@ $(AIRFRAME_H) : $(CONF)/$(AIRFRAME_XML) $(CONF_XML) $(AIRCRAFT_MD5)
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_airframe.out $(AC_ID) $(AIRCRAFT) $(MD5SUM) $< > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_airframe.out $(AC_ID) $(AIRCRAFT) $(MD5SUM) $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $(CONF)/airframes/airframe.dtd $(AIRCRAFT_CONF_DIR)/airframes
|
||||
|
||||
$(RADIO_H) : $(CONF)/$(RADIO) $(CONF_XML) $(TOOLS)/gen_radio.out
|
||||
$(RADIO_H) : $(CONF)/$(RADIO) $(CONF_XML) $(GENERATORS)/gen_radio.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_radio.out $< > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_radio.out $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)/radios
|
||||
@@ -122,59 +122,59 @@ $(PERIODIC_H) : $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TE
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_periodic.out $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(TELEMETRY_FREQUENCY) $(SETTINGS_TELEMETRY) > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_periodic.out $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(TELEMETRY_FREQUENCY) $(SETTINGS_TELEMETRY) > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $(CONF)/$(TELEMETRY) $(AIRCRAFT_CONF_DIR)/telemetry
|
||||
|
||||
$(FLIGHT_PLAN_H) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(TOOLS)/gen_flight_plan.out
|
||||
$(FLIGHT_PLAN_H) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(GENERATORS)/gen_flight_plan.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_flight_plan.out $< > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_flight_plan.out $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)/flight_plans
|
||||
|
||||
$(FLIGHT_PLAN_XML) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(TOOLS)/gen_flight_plan.out
|
||||
$(FLIGHT_PLAN_XML) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(GENERATORS)/gen_flight_plan.out
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_flight_plan.out -dump $< > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_flight_plan.out -dump $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(SETTINGS_H) : $(SETTINGS_XMLS) $(CONF_XML) $(SETTINGS_MODULES) $(SETTINGS_TELEMETRY) $(TOOLS)/gen_settings.out
|
||||
$(SETTINGS_H) : $(SETTINGS_XMLS) $(CONF_XML) $(SETTINGS_MODULES) $(SETTINGS_TELEMETRY) $(GENERATORS)/gen_settings.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_settings.out $(SETTINGS_XML) $(SETTINGS_TELEMETRY) $(SETTINGS_XMLS) $(SETTINGS_MODULES) > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_settings.out $(SETTINGS_XML) $(SETTINGS_TELEMETRY) $(SETTINGS_XMLS) $(SETTINGS_MODULES) > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $(SETTINGS_XMLS) $(AIRCRAFT_CONF_DIR)/settings
|
||||
|
||||
$(MODULES_H) : $(CONF)/$(AIRFRAME_XML) $(TOOLS)/gen_modules.out $(CONF)/modules/*.xml
|
||||
$(MODULES_H) : $(CONF)/$(AIRFRAME_XML) $(GENERATORS)/gen_modules.out $(CONF)/modules/*.xml
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_modules.out $(SETTINGS_MODULES) $(DEFAULT_MODULES_FREQUENCY) $< > $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_modules.out $(SETTINGS_MODULES) $(DEFAULT_MODULES_FREQUENCY) $< > $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(AUTOPILOT_H) : $(CONF)/$(AIRFRAME_XML) $(TOOLS)/gen_autopilot.out $(CONF)/autopilot/*.xml
|
||||
$(AUTOPILOT_H) : $(CONF)/$(AIRFRAME_XML) $(GENERATORS)/gen_autopilot.out $(CONF)/autopilot/*.xml
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo GENERATE $@
|
||||
$(eval $@_TMP := $(shell $(MKTEMP)))
|
||||
$(Q)$(TOOLS)/gen_autopilot.out $(CONF)/$(AIRFRAME_XML) $($@_TMP)
|
||||
$(Q)$(GENERATORS)/gen_autopilot.out $(CONF)/$(AIRFRAME_XML) $($@_TMP)
|
||||
$(Q)mv $($@_TMP) $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(SETTINGS_MODULES) : $(MODULES_H)
|
||||
$(SETTINGS_TELEMETRY) : $(PERIODIC_H)
|
||||
|
||||
%.ac_h : $(TOOLS)/gen_aircraft.out
|
||||
%.ac_h : $(GENERATORS)/gen_aircraft.out
|
||||
$(Q)if (expr "$(AIRCRAFT)"); then : ; else echo "AIRCRAFT undefined: type 'make AIRCRAFT=AircraftName ...'"; exit 1; fi
|
||||
@echo BUILD $(AIRCRAFT), TARGET $*
|
||||
+$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) TARGET=$* Q=$(Q) $(TOOLS)/gen_aircraft.out $(AIRCRAFT)
|
||||
$(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) TARGET=$* Q=$(Q) $(GENERATORS)/gen_aircraft.out $(AIRCRAFT)
|
||||
|
||||
%.compile: %.ac_h print_version
|
||||
cd $(AIRBORNE); $(MAKE) TARGET=$* all
|
||||
|
||||
@@ -4,7 +4,7 @@ Paparazzi UAS
|
||||
Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System.
|
||||
As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles).
|
||||
|
||||
Up to date information is available in the wiki http://paparazzi.enac.fr
|
||||
Up to date information is available in the wiki http://wiki.paparazziuav.org
|
||||
|
||||
and from the mailing list [paparazzi-devel@nongnu.org] (http://savannah.nongnu.org/mail/?group=paparazzi)
|
||||
and the IRC channel (freenode, #paparazzi).
|
||||
@@ -13,10 +13,10 @@ and the IRC channel (freenode, #paparazzi).
|
||||
Required Software
|
||||
-----------------
|
||||
|
||||
Installation is described in the wiki (http://paparazzi.enac.fr/wiki/Installation).
|
||||
Installation is described in the wiki (http://wiki.paparazziuav.org/wiki/Installation).
|
||||
|
||||
For Ubuntu users, required packages are available in the [paparazzi-uav PPA] (https://launchpad.net/~paparazzi-uav/+archive/ppa),
|
||||
Debian users can use http://paparazzi.enac.fr/debian
|
||||
Debian users can use the [OpenSUSE Build Service repository] (http://download.opensuse.org/repositories/home:/flixr:/paparazzi-uav/Debian_7.0/)
|
||||
|
||||
Debian/Ubuntu packages:
|
||||
- **paparazzi-dev** is the meta-package that depends on everything needed to compile and run the ground segment and the simulator.
|
||||
|
||||
@@ -41,7 +41,7 @@ CHIBIOS_BOARD_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD)/chibios-libopen
|
||||
CHIBIOS_LIB_DIR = $(PAPARAZZI_SRC)/sw/airborne/subsystems/chibios-libopencm3
|
||||
CHIBIOS_EXT = $(PAPARAZZI_SRC)/sw/ext/chibios
|
||||
OPENCM3_EXT = $(PAPARAZZI_SRC)/sw/ext/libopencm3
|
||||
PPRZ_GENERATED = $(PAPARAZZI_SRC)/var/$(AIRCRAFT)/generated
|
||||
PPRZ_GENERATED = $(PAPARAZZI_SRC)/var/$(AIRCRAFT)/$(TARGET)/generated
|
||||
PPRZ_CHIBIOS_OCM3 = $(SRC_FIRMWARE)/chibios-libopencm3
|
||||
|
||||
# Launch with "make Q=''" to get full command display
|
||||
|
||||
+2
-2
@@ -7,8 +7,8 @@ PAPARAZZI_HOME=$(HOME)/paparazzi
|
||||
endif
|
||||
|
||||
ifeq ($(PAPARAZZI_SRC),)
|
||||
TOOLS=$(DESTDIR)/usr/share/paparazzi/bin
|
||||
GENERATORS=$(DESTDIR)/usr/share/paparazzi/bin
|
||||
else
|
||||
TOOLS=$(PAPARAZZI_SRC)/sw/tools
|
||||
GENERATORS=$(PAPARAZZI_SRC)/sw/tools/generators
|
||||
endif
|
||||
|
||||
|
||||
@@ -59,9 +59,14 @@ else ifeq ($(FLASH_MODE),DFU-UTIL)
|
||||
#
|
||||
# DFU flash mode using dfu-util
|
||||
DFU_ADDR ?= 0x08000000
|
||||
DFU_SIZE ?= $(shell stat --printf=%s $^)
|
||||
upload: $(OBJDIR)/$(TARGET).bin
|
||||
@echo "Using dfu-util at $(DFU_ADDR)"
|
||||
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^
|
||||
$(Q)rm -f $(OBJDIR)/verify.bla
|
||||
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR):$(DFU_SIZE) -U $(OBJDIR)/verify.bla
|
||||
$(Q)diff $^ $(OBJDIR)/verify.bla
|
||||
$(Q)rm -f $(OBJDIR)/verify.bla
|
||||
|
||||
#
|
||||
# serial flash mode
|
||||
|
||||
@@ -11,6 +11,11 @@
|
||||
<message name="BARO_DIFF" id="1">
|
||||
<field name="pressure" type="float" unit="Pa"/>
|
||||
</message>
|
||||
|
||||
<message name="AGL" id="2">
|
||||
<field name="distance" type="float" unit="m"/>
|
||||
</message>
|
||||
|
||||
</class>
|
||||
|
||||
|
||||
|
||||
@@ -218,7 +218,7 @@
|
||||
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12"/>
|
||||
</load>
|
||||
|
||||
<load name="nav_catapult.xml"/>
|
||||
|
||||
@@ -180,10 +180,6 @@
|
||||
<target name="ap" board="classix">
|
||||
<configure name="SYS_TIME_LED" value="2"/>
|
||||
|
||||
<define name="USE_LED_6" value="1"/>
|
||||
<define name="LED_6_BANK" value="0"/>
|
||||
<define name="LED_6_PIN" value="15"/>
|
||||
|
||||
<define name="USE_AD0"/>
|
||||
<define name="USE_AD0_3"/>
|
||||
<define name="ADC_6" value="AdcBank0\(3\)"/>
|
||||
@@ -230,7 +226,7 @@
|
||||
|
||||
<modules>
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="6"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOA,GPIO15"/>
|
||||
</load>
|
||||
<load name="adc_generic.xml">
|
||||
<define name="ADC_CHANNEL_GENERIC_NB_SAMPLES" value="32"/>
|
||||
|
||||
@@ -214,7 +214,7 @@
|
||||
|
||||
<!--
|
||||
<load name="digital_cam.xml" >
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO18"/>
|
||||
</load>
|
||||
-->
|
||||
</modules>
|
||||
|
||||
@@ -199,7 +199,7 @@
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
<!-- <load name="ins_ppzuavimu.xml"/> -->
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="2"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO16"/>
|
||||
</load>
|
||||
|
||||
</modules>
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
<modules main_freq="512">
|
||||
<load name="servo_switch.xml"/>
|
||||
<load name="rotorcraft_cam.xml"/>
|
||||
<!--load name="sonar_adc_ins.xml"/-->
|
||||
<!--load name="sonar_adc.xml"/-->
|
||||
<!--load name="adc_generic.xml">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_0"/>
|
||||
</load-->
|
||||
@@ -254,8 +254,6 @@
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="DEFAULT_MODE" value="MODE_MANUAL"/>
|
||||
<define name="ON" value="{}"/>
|
||||
<define name="OFF" value="{}"/>
|
||||
</section>
|
||||
|
||||
<section name="SERVO_SWITCH">
|
||||
|
||||
@@ -3,8 +3,9 @@
|
||||
<modules main_freq="512">
|
||||
<load name="servo_switch.xml"/>
|
||||
<load name="rotorcraft_cam.xml"/>
|
||||
<load name="sonar_adc_ins.xml">
|
||||
<load name="sonar_adc.xml">
|
||||
<configure name="ADC_SONAR" value="ADC_0"/>
|
||||
<define name="USE_SONAR"/>
|
||||
<!--define name="SENSOR_SYNC_SEND_SONAR"/-->
|
||||
</load>
|
||||
<!--load name="baro_mpl3115.xml">
|
||||
@@ -24,6 +25,7 @@
|
||||
</modules>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<define name="DEBUG_VFF_EXTENDED"/>
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--define name="GUIDANCE_H_USE_REF"/-->
|
||||
|
||||
@@ -177,13 +179,16 @@
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<!--define name="SONAR_SENS" value="0.00650498" integer="16"/--> <!-- XL-MaxSonar-EZ4 5V supply -->
|
||||
<define name="SONAR_SENS" value="0.016775" integer="16"/> <!-- XL-MaxSonar-EZ4 5V supply scaled to 3.3V -->
|
||||
<define name="SONAR_MAX_RANGE" value="5.0"/>
|
||||
<define name="SONAR_MIN_RANGE" value="0.25"/>
|
||||
<!--define name="SONAR_VARIANCE_THRESHOLD" value="0.01"/-->
|
||||
</section>
|
||||
|
||||
<section name="SONAR">
|
||||
<!--define name="SONAR_SENS" value="0.00650498" integer="16"/--> <!-- XL-MaxSonar-EZ4 5V supply -->
|
||||
<define name="SONAR_SENS" value="0.016775" integer="16"/> <!-- XL-MaxSonar-EZ4 5V supply scaled to 3.3V -->
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
@@ -228,8 +233,7 @@
|
||||
</section>
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="ON" value="LED_ON(CAM_SWITCH_LED)"/>
|
||||
<define name="OFF" value="LED_OFF(CAM_SWITCH_LED)"/>
|
||||
<define name="SWITCH_GPIO" value="CAM_SWITCH_GPIO"/>
|
||||
<define name="TILT_SERVO" value="CAM"/>
|
||||
<define name="TILT_ANGLE_MAX" value="-90." unit="deg"/>
|
||||
<define name="TILT_ANGLE_MIN" value=" 10." unit="deg"/>
|
||||
|
||||
@@ -185,29 +185,6 @@
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_QUARTERSEC_PERIOD" value="6" unit="quarter_second"/>
|
||||
<define name="AUTOSHOOT_METER_GRID" value="50" unit="meter"/>
|
||||
</section>
|
||||
|
||||
|
||||
<modules>
|
||||
<!--
|
||||
<load name="light.xml">
|
||||
<define name="LIGHT_LED_STROBE" value="3"/>
|
||||
<define name="LIGHT_LED_NAV" value="2"/>
|
||||
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
|
||||
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
|
||||
</load>
|
||||
-->
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
|
||||
<!--
|
||||
<load name="digital_cam.xml" >
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
</load>
|
||||
-->
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
|
||||
|
||||
@@ -0,0 +1,199 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Delfly (http://www.delfly.nl/home.html)
|
||||
Lisa/S v1.0 board (http://wiki.paparazziuav.org/wiki/Lisa/S)
|
||||
-->
|
||||
|
||||
<airframe name="Delfly Lisa/S 0.1">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="lisa_s_0.1">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="0"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="STRONG_WIND"/>
|
||||
|
||||
<define name="USE_BAROMETER" value="TRUE"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<subsystem name="telemetry" type="transparent">
|
||||
<!--<configure name="MODEM_BAUD" value="B57600"/>
|
||||
<configure name="MODEM_PORT" value="UART1"/>-->
|
||||
</subsystem>
|
||||
|
||||
<!-- Sensors -->
|
||||
<subsystem name="imu" type="lisa_s_v0.1"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="50"/>
|
||||
<define name="USE_SERVOS_1AND2"/>
|
||||
</subsystem>
|
||||
|
||||
<subsystem name="actuators" type="dualpwm">
|
||||
<define name="DUAL_PWM_ON"/>
|
||||
</subsystem>
|
||||
|
||||
<!--<subsystem name="ahrs" type="int_cmpl_quat"/>-->
|
||||
<subsystem name="control"/>
|
||||
<subsystem name="navigation"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
|
||||
<!--<configure name="SYS_TIME_LED" value="none"/>-->
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<load name="baro_sim.xml"/>
|
||||
<load name="servo_switch.xml"/>
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
</modules>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
|
||||
<!--<servo name="SWITCH" no="2" min="1100" neutral="1500" max="1900"/>
|
||||
<servo name="SWITCH2" no="3" min="1100" neutral="1500" max="1900"/>-->
|
||||
</servos>
|
||||
|
||||
<!-- comboPWM / mergedPWM / -->
|
||||
<servos driver="Dualpwm">
|
||||
<servo name="SWITCH" no="3" min="1100" neutral="1500" max="1900"/>
|
||||
<servo name="pitchator" no="2" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="4000"/>
|
||||
<axis name="PITCH" failsafe_value="-8000"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
</rc_commands>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="pitchator" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- ACCEL and GYRO calibration left out to take default datasheet values -->
|
||||
|
||||
<!-- replace this with your own mag calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="-45"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="334"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="7"/>
|
||||
<define name="MAG_X_SENS" value="4.47647816128" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.71085671542" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.41585354498" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<!-- replace this with your local magnetic field -->
|
||||
<define name="H_X" value="0.3770441"/>
|
||||
<define name="H_Y" value="0.0193986"/>
|
||||
<define name="H_Z" value="0.9259921"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="7.3" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="30" unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-30" unit="deg"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
<define name="ROLL_SLEW" value="0.1"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="2" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="40." unit="deg"/>
|
||||
<define name="MAX_PITCH" value="35." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="1000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="2.9" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="3.1" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="3.4" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="4.2" unit="V"/>
|
||||
<!--<define name="VoltageOfAdc(adc)" value ="8"/>-->
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
<!--<define name="RC_LOST_MODE" value="mode_auto2"/>-->
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -18,7 +18,7 @@
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="ardrone2"/>
|
||||
<subsystem name="imu" type="ardrone2"/>
|
||||
<subsystem name="gps" type="udp"/>
|
||||
<subsystem name="gps" type="datalink"/>
|
||||
<subsystem name="stabilization" type="int_quat"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="extended"/>
|
||||
@@ -26,6 +26,11 @@
|
||||
|
||||
<modules main_freq="512">
|
||||
<load name="send_imu_mag_current.xml"/>
|
||||
<load name="follow.xml">
|
||||
<define name="FOLLOW_AC_ID" value="101"/>
|
||||
<define name="FOLLOW_WAYPOINT_ID" value="WP_p1"/>
|
||||
<define name="FOLLOW_OFFSET_Z" value="2.0"/>
|
||||
</load>
|
||||
</modules>
|
||||
|
||||
<commands>
|
||||
@@ -102,6 +107,9 @@
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<!-- Use GPS altitude measurments and set the R gain -->
|
||||
<define name="USE_GPS_ALT" value="1"/>
|
||||
<define name="VFF_R_GPS" value="0.01"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
@@ -133,7 +141,7 @@
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45" unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45" unit="deg"/>
|
||||
<define name="SP_MAX_R" value="600" unit="deg/s"/>
|
||||
<define name="SP_MAX_R" value="200" unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
@@ -155,17 +163,17 @@
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(4000.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="592"/>
|
||||
<define name="PHI_PGAIN" value="1218"/>
|
||||
<define name="PHI_DGAIN" value="303"/>
|
||||
<define name="PHI_IGAIN" value="0"/>
|
||||
<define name="PHI_IGAIN" value="120"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="606"/>
|
||||
<define name="THETA_PGAIN" value="1218"/>
|
||||
<define name="THETA_DGAIN" value="303"/>
|
||||
<define name="THETA_IGAIN" value="0"/>
|
||||
<define name="THETA_IGAIN" value="120"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="529"/>
|
||||
<define name="PSI_DGAIN" value="353"/>
|
||||
<define name="PSI_IGAIN" value="0"/>
|
||||
<define name="PSI_IGAIN" value="10"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="0"/>
|
||||
@@ -191,8 +199,16 @@
|
||||
<define name="MAX_BANK" value="20" unit="deg"/>
|
||||
<!-- Bad weather -->
|
||||
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
|
||||
<define name="PGAIN" value="79"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
|
||||
<!-- reference model -->
|
||||
<define name="REF_OMEGA" value="RadOfDeg(190.)"/>
|
||||
<define name="REF_ZETA" value="0.9"/>
|
||||
<define name="REF_MAX_ACCEL" value="9.5"/>
|
||||
<define name="REF_MAX_SPEED" value="8.5"/>
|
||||
|
||||
<!-- gains -->
|
||||
<define name="PGAIN" value="150"/>
|
||||
<define name="DGAIN" value="60"/>
|
||||
<define name="IGAIN" value="60"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -79,7 +79,7 @@
|
||||
</load>
|
||||
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12"/>
|
||||
</load>
|
||||
|
||||
<load name="nav_catapult.xml"/>
|
||||
|
||||
@@ -58,7 +58,7 @@ twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
</load>
|
||||
<load name="baro_sim.xml"/>
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="5"/><!-- led4:aux led5:camsw-->
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO22"/><!-- 18:aux 22:camsw-->
|
||||
</load>
|
||||
<load name="nav_survey_polygon.xml"/>
|
||||
<load name="nav_line.xml"/>
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
<define name="SHOW_CAM_COORDINATES" value="1"/>
|
||||
</load>
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO23"/>
|
||||
</load>
|
||||
<load name="sys_mon.xml"/>
|
||||
<load name="infrared_adc.xml"/>
|
||||
|
||||
@@ -218,8 +218,6 @@
|
||||
</section>
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="ON" value="{}"/>
|
||||
<define name="OFF" value="{}"/>
|
||||
<define name="TILT_SERVO" value="CAM"/>
|
||||
<define name="TILT_ANGLE_MAX" value="-90." unit="deg"/>
|
||||
<define name="TILT_ANGLE_MIN" value=" 10." unit="deg"/>
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat">
|
||||
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30"/>
|
||||
</subsystem>
|
||||
<subsystem name="ins"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
|
||||
<!--define name="KILL_ON_GROUND_DETECT" value="TRUE"/-->
|
||||
</firmware>
|
||||
@@ -52,6 +52,8 @@
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_1"/>
|
||||
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_2"/>
|
||||
</load>
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="geo_mag.xml"/>
|
||||
</modules>
|
||||
|
||||
<servos driver="Pwm">
|
||||
|
||||
@@ -239,8 +239,6 @@
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="DEFAULT_MODE" value="MODE_MANUAL"/>
|
||||
<define name="ON" value="{}"/>
|
||||
<define name="OFF" value="{}"/>
|
||||
</section>
|
||||
|
||||
<section name="SERVO_SWITCH">
|
||||
|
||||
@@ -219,7 +219,7 @@
|
||||
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12"/>
|
||||
</load>
|
||||
|
||||
<load name="nav_catapult.xml"/>
|
||||
|
||||
@@ -1,34 +0,0 @@
|
||||
<airframe name="VOR">
|
||||
|
||||
<makefile>
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
|
||||
FLASH_MODE = IAP
|
||||
main.ARCHDIR = $(ARCH)
|
||||
|
||||
main.CFLAGS += -DBOARD_CONFIG=\"boards/olimex_lpc_h2148.h\"
|
||||
main.srcs = firmwares/vor/lpc_vor_main.c
|
||||
|
||||
main.CFLAGS += -DPERIODIC_FREQUENCY='29880.'
|
||||
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
|
||||
|
||||
main.CFLAGS += -DUSE_LED
|
||||
|
||||
main.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
main.srcs += firmwares/vor/lpc_vor_convertions.c
|
||||
|
||||
main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B9600
|
||||
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=UART0
|
||||
main.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c
|
||||
|
||||
main.srcs += firmwares/vor/vor_int_demod_decim.c
|
||||
|
||||
|
||||
</makefile>
|
||||
|
||||
</airframe>
|
||||
-241
@@ -1,241 +0,0 @@
|
||||
# Boa v0.94 configuration file
|
||||
# File format has not changed from 0.93
|
||||
# File format has changed little from 0.92
|
||||
# version changes are noted in the comments
|
||||
#
|
||||
# The Boa configuration file is parsed with a custom parser. If it
|
||||
# reports an error, the line number will be provided; it should be easy
|
||||
# to spot. The syntax of each of these rules is very simple, and they
|
||||
# can occur in any order. Where possible these directives mimic those
|
||||
# of NCSA httpd 1.3; I saw no reason to introduce gratuitous
|
||||
# differences.
|
||||
|
||||
# $Id$
|
||||
|
||||
# The "ServerRoot" is not in this configuration file. It can be
|
||||
# compiled into the server (see defines.h) or specified on the command
|
||||
# line with the -c option, for example:
|
||||
#
|
||||
# boa -c /usr/local/boa
|
||||
|
||||
|
||||
# Port: The port Boa runs on. The default port for http servers is 80.
|
||||
# If it is less than 1024, the server must be started as root.
|
||||
|
||||
Port 8889
|
||||
|
||||
# Listen: the Internet address to bind(2) to. If you leave it out,
|
||||
# it takes the behavior before 0.93.17.2, which is to bind to all
|
||||
# addresses (INADDR_ANY). You only get one "Listen" directive,
|
||||
# if you want service on multiple IP addresses, you have three choices:
|
||||
# 1. Run boa without a "Listen" directive
|
||||
# a. All addresses are treated the same; makes sense if the addresses
|
||||
# are localhost, ppp, and eth0.
|
||||
# b. Use the VirtualHost directive below to point requests to different
|
||||
# files. Should be good for a very large number of addresses (web
|
||||
# hosting clients).
|
||||
# 2. Run one copy of boa per IP address, each has its own configuration
|
||||
# with a "Listen" directive. No big deal up to a few tens of addresses.
|
||||
# Nice separation between clients.
|
||||
# The name you provide gets run through inet_aton(3), so you have to use dotted
|
||||
# quad notation. This configuration is too important to trust some DNS.
|
||||
|
||||
#Listen 192.68.0.5
|
||||
|
||||
# User: The name or UID the server should run as.
|
||||
# Group: The group name or GID the server should run as.
|
||||
|
||||
User www-data
|
||||
Group www-data
|
||||
|
||||
# ServerAdmin: The email address where server problems should be sent.
|
||||
# Note: this is not currently used, except as an environment variable
|
||||
# for CGIs.
|
||||
|
||||
#ServerAdmin root@localhost
|
||||
|
||||
# PidFile: where to put the pid of the process.
|
||||
# Comment out to write no pid file.
|
||||
# Note: Because Boa drops privileges at startup, and the
|
||||
# pid file is written by the UID/GID before doing so, Boa
|
||||
# does not attempt removal of the pid file.
|
||||
# PidFile /var/run/boa.pid
|
||||
|
||||
# ErrorLog: The location of the error log file. If this does not start
|
||||
# with /, it is considered relative to the server root.
|
||||
# Set to /dev/null if you don't want errors logged.
|
||||
# If unset, defaults to /dev/stderr
|
||||
# Please NOTE: Sending the logs to a pipe ('|'), as shown below,
|
||||
# is somewhat experimental and might fail under heavy load.
|
||||
# "Usual libc implementations of printf will stall the whole
|
||||
# process if the receiving end of a pipe stops reading."
|
||||
#ErrorLog "|/usr/sbin/cronolog --symlink=/var/log/boa/error_log /var/log/boa/error-%Y%m%d.log"
|
||||
|
||||
ErrorLog PAPARAZZI_HOME/var/logs/boa.log
|
||||
|
||||
# AccessLog: The location of the access log file. If this does not
|
||||
# start with /, it is considered relative to the server root.
|
||||
# Comment out or set to /dev/null (less effective) to disable.
|
||||
# Useful to set to /dev/stdout for use with daemontools.
|
||||
# Access logging.
|
||||
# Please NOTE: Sending the logs to a pipe ('|'), as shown below,
|
||||
# is somewhat experimental and might fail under heavy load.
|
||||
# "Usual libc implementations of printf will stall the whole
|
||||
# process if the receiving end of a pipe stops reading."
|
||||
#AccessLog "|/usr/sbin/cronolog --symlink=/var/log/boa/access_log /var/log/boa/access-%Y%m%d.log"
|
||||
|
||||
AccessLog PAPARAZZI_HOME/var/logs/boa_access.log
|
||||
|
||||
# CGILog /var/log/boa/cgi_log
|
||||
# CGILog: The location of the CGI stderr log file. If this does not
|
||||
# start with /, it is considered relative to the server root.
|
||||
# The log file would contain any contents send to /dev/stderr
|
||||
# by the CGI. If this is commented out, it defaults to whatever
|
||||
# ErrorLog points. Set to /dev/null to disable CGI stderr logging.
|
||||
# Please NOTE: Sending the logs to a pipe ('|'), as shown below,
|
||||
# is somewhat experimental and might fail under heavy load.
|
||||
# "Usual libc implementations of printf will stall the whole
|
||||
# process if the receiving end of a pipe stops reading."
|
||||
#CGILog "|/usr/sbin/cronolog --symlink=/var/log/boa/cgi_log /var/log/boa/cgi-%Y%m%d.log"
|
||||
|
||||
# CGIumask 027 (no mask for user, read-only for group, and nothing for user)
|
||||
# CGIumask 027
|
||||
# The CGIumask is set immediately before execution of the CGI.
|
||||
|
||||
# UseLocaltime: Logical switch. Uncomment to use localtime
|
||||
# instead of UTC time
|
||||
#UseLocaltime
|
||||
|
||||
# VerboseCGILogs: this is just a logical switch.
|
||||
# It simply notes the start and stop times of cgis in the error log
|
||||
# Comment out to disable.
|
||||
|
||||
#VerboseCGILogs
|
||||
|
||||
# ServerName: the name of this server that should be sent back to
|
||||
# clients if different than that returned by gethostname + gethostbyname
|
||||
|
||||
#ServerName www.your.org.here
|
||||
|
||||
# VirtualHost: a logical switch.
|
||||
# Comment out to disable.
|
||||
# Given DocumentRoot /var/www, requests on interface 'A' or IP 'IP-A'
|
||||
# become /var/www/IP-A.
|
||||
# Example: http://localhost/ becomes /var/www/127.0.0.1
|
||||
#
|
||||
# Not used until version 0.93.17.2. This "feature" also breaks commonlog
|
||||
# output rules, it prepends the interface number to each access_log line.
|
||||
# You are expected to fix that problem with a postprocessing script.
|
||||
|
||||
#VirtualHost
|
||||
|
||||
|
||||
# VHostRoot: the root location for all virtually hosted data
|
||||
# Comment out to disable.
|
||||
# Incompatible with 'Virtualhost' and 'DocumentRoot'!!
|
||||
# Given VHostRoot /var/www, requests to host foo.bar.com,
|
||||
# where foo.bar.com is ip a.b.c.d,
|
||||
# become /var/www/a.b.c.d/foo.bar.com
|
||||
# Hostnames are "cleaned", and must conform to the rules
|
||||
# specified in rfc1034, which are be summarized here:
|
||||
#
|
||||
# Hostnames must start with a letter, end with a letter or digit,
|
||||
# and have as interior characters only letters, digits, and hyphen.
|
||||
# Hostnames must not exceed 63 characters in length.
|
||||
|
||||
#VHostRoot /var/www
|
||||
|
||||
# DefaultVHost
|
||||
# Define this in order to have a default hostname when the client does not
|
||||
# specify one, if using VirtualHostName. If not specified, the word
|
||||
# "default" will be used for compatibility with older clients.
|
||||
|
||||
#DefaultVHost foo.bar.com
|
||||
|
||||
# DocumentRoot: The root directory of the HTML documents.
|
||||
# Comment out to disable server non user files.
|
||||
|
||||
DocumentRoot PAPARAZZI_HOME
|
||||
|
||||
# UserDir: The name of the directory which is appended onto a user's home
|
||||
# directory if a ~user request is received.
|
||||
|
||||
UserDir public_html
|
||||
|
||||
# DirectoryIndex: Name of the file to use as a pre-written HTML
|
||||
# directory index. Please MAKE AND USE THESE FILES. On the
|
||||
# fly creation of directory indexes can be _slow_.
|
||||
# Comment out to always use DirectoryMaker
|
||||
|
||||
DirectoryIndex index.html
|
||||
|
||||
# DirectoryMaker: Name of program used to create a directory listing.
|
||||
# Comment out to disable directory listings. If both this and
|
||||
# DirectoryIndex are commented out, accessing a directory will give
|
||||
# an error (though accessing files in the directory are still ok).
|
||||
|
||||
DirectoryMaker /usr/lib/boa/boa_indexer
|
||||
|
||||
# DirectoryCache: If DirectoryIndex doesn't exist, and DirectoryMaker
|
||||
# has been commented out, the the on-the-fly indexing of Boa can be used
|
||||
# to generate indexes of directories. Be warned that the output is
|
||||
# extremely minimal and can cause delays when slow disks are used.
|
||||
# Note: The DirectoryCache must be writable by the same user/group that
|
||||
# Boa runs as.
|
||||
|
||||
# DirectoryCache /var/spool/boa/dircache
|
||||
|
||||
# KeepAliveMax: Number of KeepAlive requests to allow per connection
|
||||
# Comment out, or set to 0 to disable keepalive processing
|
||||
|
||||
KeepAliveMax 1000
|
||||
|
||||
# KeepAliveTimeout: seconds to wait before keepalive connection times out
|
||||
|
||||
KeepAliveTimeout 10
|
||||
|
||||
# MimeTypes: This is the file that is used to generate mime type pairs
|
||||
# and Content-Type fields for boa.
|
||||
# Set to /dev/null if you do not want to load a mime types file.
|
||||
# Do *not* comment out (better use AddType!)
|
||||
|
||||
MimeTypes /etc/mime.types
|
||||
|
||||
# DefaultType: MIME type used if the file extension is unknown, or there
|
||||
# is no file extension.
|
||||
|
||||
DefaultType text/plain
|
||||
|
||||
# CGIPath: The value of the $PATH environment variable given to CGI progs.
|
||||
|
||||
CGIPath /bin:/usr/bin:/usr/local/bin
|
||||
|
||||
# SinglePostLimit: The maximum allowable number of bytes in
|
||||
# a single POST. Default is normally 1MB.
|
||||
|
||||
# AddType: adds types without editing mime.types
|
||||
# Example: AddType type extension [extension ...]
|
||||
|
||||
# Uncomment the next line if you want .cgi files to execute from anywhere
|
||||
AddType application/x-httpd-cgi cgi
|
||||
|
||||
# Redirect, Alias, and ScriptAlias all have the same semantics -- they
|
||||
# match the beginning of a request and take appropriate action. Use
|
||||
# Redirect for other servers, Alias for the same server, and ScriptAlias
|
||||
# to enable directories for script execution.
|
||||
|
||||
# Redirect allows you to tell clients about documents which used to exist in
|
||||
# your server's namespace, but do not anymore. This allows you to tell the
|
||||
# clients where to look for the relocated document.
|
||||
# Example: Redirect /bar http://elsewhere/feh/bar
|
||||
|
||||
# Aliases: Aliases one path to another.
|
||||
# Example: Alias /path1/bar /path2/foo
|
||||
|
||||
Alias /doc /usr/share/doc
|
||||
|
||||
# ScriptAlias: Maps a virtual path to a directory for serving scripts
|
||||
# Example: ScriptAlias /htbin/ /www/htbin/
|
||||
|
||||
ScriptAlias /cgi-bin/ PAPARAZZI_HOME/sw/cgi/
|
||||
|
||||
@@ -116,10 +116,10 @@ all: $(OBJS) $(OUTFILES) MAKE_ALL_RULE_HOOK
|
||||
|
||||
MAKE_ALL_RULE_HOOK:
|
||||
|
||||
$(OBJS): | $(BUILDDIR)
|
||||
$(OBJS): | $(OBJDIR)
|
||||
|
||||
$(BUILDDIR) $(OBJDIR) $(LSTDIR):
|
||||
ifneq ($(USE_VERBOSE_COMPILE),yes)
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo Compiler Options
|
||||
@echo $(CC) -c $(CFLAGS) -I. $(IINCDIR) main.c -o main.o
|
||||
@echo
|
||||
|
||||
@@ -41,11 +41,11 @@
|
||||
|
||||
<program name="Settings (Python)" command="sw/ground_segment/python/settings_app/settingsapp.py"/>
|
||||
|
||||
<program name="GPSd position display" command ="sw/ground_segment/tmtc/gpsd2ivy"/>
|
||||
<program name="GPSd position display" command="sw/ground_segment/tmtc/gpsd2ivy"/>
|
||||
|
||||
<program name="Log Plotter" command ="sw/logalizer/plot"/>
|
||||
<program name="Log Plotter" command="sw/logalizer/plot"/>
|
||||
|
||||
<program name="Real-time Plotter" command ="sw/logalizer/plotter"/>
|
||||
<program name="Real-time Plotter" command="sw/logalizer/plotter"/>
|
||||
|
||||
<program name="Log File Player" command="sw/logalizer/play">
|
||||
<arg flag="-b" variable="ivy_bus"/>
|
||||
@@ -68,8 +68,6 @@
|
||||
<arg flag="-b" variable="ivy_bus"/>
|
||||
</program>
|
||||
|
||||
<program name="Http Server" command="sw/ground_segment/tmtc/boa"/>
|
||||
|
||||
<program name="Plot Meteo Profile" command="sw/logalizer/plotprofile"/>
|
||||
|
||||
<program name="Weather Station" command="sw/ground_segment/misc/davis2ivy">
|
||||
@@ -78,7 +76,11 @@
|
||||
</program>
|
||||
|
||||
<program name="Attitude Visualizer" command="sw/tools/attitude_viz.py"/>
|
||||
</section>
|
||||
|
||||
<program name="App Server" command="sw/ground_segment/tmtc/app_server"/>
|
||||
|
||||
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
ins_srcs += $(SRC_SUBSYSTEMS)/ins.c
|
||||
ins_srcs += $(SRC_SUBSYSTEMS)/ins/ins_gps_passthrough.c
|
||||
ins_srcs += $(SRC_SUBSYSTEMS)/ins/ins_gps_passthrough_utm.c
|
||||
|
||||
|
||||
ap.CFLAGS += $(ins_CFLAGS)
|
||||
|
||||
@@ -0,0 +1,18 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
GPS_LED ?= none
|
||||
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_datalink.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_datalink.c
|
||||
|
||||
ap.CFLAGS += -DUSE_GPS -DGPS_DATALINK
|
||||
|
||||
ifneq ($(GPS_LED),none)
|
||||
ap.CFLAGS += -DGPS_LED=$(GPS_LED)
|
||||
endif
|
||||
|
||||
nps.CFLAGS += -DUSE_GPS
|
||||
nps.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\"
|
||||
nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c
|
||||
@@ -0,0 +1,15 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_hitl.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_hitl.c
|
||||
ap.CFLAGS += -DUSE_GPS -DHITL
|
||||
|
||||
ifneq ($(GPS_LED),none)
|
||||
ap.CFLAGS += -DGPS_LED=$(GPS_LED)
|
||||
endif
|
||||
|
||||
nps.CFLAGS += -DUSE_GPS
|
||||
nps.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\"
|
||||
nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c
|
||||
@@ -0,0 +1,11 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
ins_srcs += $(SRC_SUBSYSTEMS)/ins.c
|
||||
ins_srcs += $(SRC_SUBSYSTEMS)/ins/ins_gps_passthrough.c
|
||||
|
||||
|
||||
ap.CFLAGS += $(ins_CFLAGS)
|
||||
ap.srcs += $(ins_srcs)
|
||||
|
||||
nps.CFLAGS += $(ins_CFLAGS)
|
||||
nps.srcs += $(ins_srcs)
|
||||
@@ -0,0 +1,10 @@
|
||||
ifeq ($(ARCH), lpc21)
|
||||
$(error Error: dualpwm actuators only implemented for stm32)
|
||||
endif
|
||||
|
||||
$(TARGET).CFLAGS += -DACTUATORS
|
||||
$(TARGET).srcs += $(SRC_ARCH)/subsystems/actuators/actuators_dualpwm_arch.c
|
||||
ifeq ($(ARCH), stm32)
|
||||
$(TARGET).srcs += $(SRC_ARCH)/subsystems/actuators/actuators_shared_arch.c
|
||||
endif
|
||||
|
||||
@@ -2,3 +2,6 @@
|
||||
|
||||
$(TARGET).CFLAGS += -DACTUATORS
|
||||
$(TARGET).srcs += $(SRC_ARCH)/subsystems/actuators/actuators_pwm_arch.c
|
||||
ifeq ($(ARCH), stm32)
|
||||
$(TARGET).srcs += $(SRC_ARCH)/subsystems/actuators/actuators_shared_arch.c
|
||||
endif
|
||||
|
||||
@@ -19,6 +19,8 @@ ap.srcs += $(imu_srcs)
|
||||
# Set the AHRS propegation frequencies
|
||||
AHRS_PROPAGATE_FREQUENCY ?= 200
|
||||
AHRS_CORRECT_FREQUENCY ?= 200
|
||||
ap.CFLAGS += -DAHRS_PROPAGATE_FREQUENCY=$(AHRS_PROPAGATE_FREQUENCY)
|
||||
ap.CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY)
|
||||
|
||||
#
|
||||
# Simulator
|
||||
|
||||
@@ -40,7 +40,7 @@
|
||||
<set value="0" var="autopilot_flight_time"/>
|
||||
<go from="HOME" throttle="1.0" vmode="throttle" wp="CLIMB" pitch="15"/>
|
||||
</block>
|
||||
<block key="<Control>a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
|
||||
<block key="Ctrl+a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
|
||||
<circle radius="nav_radius" wp="STDBY"/>
|
||||
</block>
|
||||
<block key="F8" name="Figure 8 around wp 1" strip_button="Figure 8 (wp 1-2)" strip_icon="eight.png" group="base_pattern">
|
||||
|
||||
@@ -141,6 +141,7 @@ pitch CDATA #IMPLIED
|
||||
alt CDATA #IMPLIED
|
||||
height CDATA #IMPLIED
|
||||
approaching_time CDATA #IMPLIED
|
||||
exceeding_time CDATA #IMPLIED
|
||||
throttle CDATA #IMPLIED
|
||||
climb CDATA #IMPLIED
|
||||
until CDATA #IMPLIED>
|
||||
@@ -151,6 +152,7 @@ vmode CDATA #IMPLIED
|
||||
pitch CDATA #IMPLIED
|
||||
alt CDATA #IMPLIED
|
||||
approaching_time CDATA #IMPLIED
|
||||
exceeding_time CDATA #IMPLIED
|
||||
throttle CDATA #IMPLIED
|
||||
climb CDATA #IMPLIED>
|
||||
|
||||
|
||||
@@ -31,7 +31,7 @@
|
||||
<set value="0" var="autopilot_flight_time"/>
|
||||
<go from="HOME" throttle="1.0" vmode="throttle" wp="CLIMB" pitch="15"/>
|
||||
</block>
|
||||
<block key="<Control>a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
|
||||
<block key="Ctrl+a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
|
||||
<circle radius="nav_radius" wp="STDBY"/>
|
||||
</block>
|
||||
<block name="Mission" strip_button="Mission">
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
<set value="0" var="autopilot_flight_time"/>
|
||||
<go from="HOME" pitch="15" throttle="1.0" vmode="throttle" wp="CLIMB"/>
|
||||
</block>
|
||||
<block key="<Control>a" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<block key="Ctrl+a" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<circle radius="nav_radius" wp="STDBY"/>
|
||||
</block>
|
||||
<block name="Poles 1" strip_button="Line (wp 1-2)" strip_icon="line.png">
|
||||
|
||||
@@ -75,7 +75,7 @@
|
||||
<go approaching_time="0" from="AF" hmode="route" throttle="0.0" vmode="throttle" wp="TD"/>
|
||||
<attitude roll="0.0" throttle="0.0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
<block group="home" key="<Control>a" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<block group="home" key="Ctrl+a" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<circle radius="nav_radius" wp="STDBY"/>
|
||||
</block>
|
||||
</blocks>
|
||||
|
||||
+38
-33
@@ -1498,8 +1498,7 @@
|
||||
</message>
|
||||
|
||||
<message name="INS_SONAR" id="167">
|
||||
<field name="raw" type="int32" unit="adc" alt_unit="m" alt_unit_coef="0.0039063"/>
|
||||
<field name="scaled" type="float" unit="m"/>
|
||||
<field name="distance" type="float" unit="m"/>
|
||||
<field name="var" type="float"/>
|
||||
</message>
|
||||
|
||||
@@ -1889,7 +1888,27 @@
|
||||
<field name="ref_zd" type="int32" alt_unit="m/s" alt_unit_coef="0.0000019"/>
|
||||
</message>
|
||||
|
||||
<!--214 is free -->
|
||||
<message name="MF_DAQ_STATE" id="214">
|
||||
<field name="flight_time" type="uint16" unit="s"/>
|
||||
<field name="p" type="float"/>
|
||||
<field name="q" type="float"/>
|
||||
<field name="r" type="float"/>
|
||||
<field name="phi" type="float"/>
|
||||
<field name="theta" type="float"/>
|
||||
<field name="psi" type="float"/>
|
||||
<field name="ax" type="float"/>
|
||||
<field name="ay" type="float"/>
|
||||
<field name="az" type="float"/>
|
||||
<field name="ve" type="float"/>
|
||||
<field name="vn" type="float"/>
|
||||
<field name="vu" type="float"/>
|
||||
<field name="lat" type="float"/>
|
||||
<field name="lon" type="float"/>
|
||||
<field name="alt" type="float"/>
|
||||
<field name="we" type="float"/>
|
||||
<field name="wn" type="float"/>
|
||||
</message>
|
||||
|
||||
<!--215 is free -->
|
||||
<!--216 is free -->
|
||||
<!--217 is free -->
|
||||
@@ -1947,7 +1966,7 @@
|
||||
|
||||
<message name="ROTORCRAFT_STATUS" id="231">
|
||||
<field name="link_imu_nb_err" type="uint32"/>
|
||||
<field name="blmc_nb_err" type="uint8"/>
|
||||
<field name="motor_nb_err" type="uint8"/>
|
||||
<field name="rc_status" type="uint8" values="OK|LOST|REALLY_LOST"/>
|
||||
<field name="frame_rate" type="uint8" unit="Hz"/>
|
||||
<field name="gps_status" type="uint8" values="NO_FIX|NA|NA|3Dfix"/>
|
||||
@@ -2430,35 +2449,21 @@
|
||||
<field name="yaw" type="int8"/>
|
||||
</message>
|
||||
|
||||
<message name="MF_DAQ" id="53" link="forwarded">
|
||||
<field name="pad" type="uint16"/>
|
||||
<field name="timestamp" type="float"/>
|
||||
<field name="pressure" type="float"/>
|
||||
<field name="temp" type="float"/>
|
||||
<field name="humidity" type="float"/>
|
||||
<field name="Pdiff" type="float"/>
|
||||
<field name="Thw" type="float"/>
|
||||
</message>
|
||||
|
||||
<message name="MF_DAQ_STATE" id="54" link="forwarded">
|
||||
<field name="flight_time" type="uint16" unit="s"/>
|
||||
<field name="p" type="float"/>
|
||||
<field name="q" type="float"/>
|
||||
<field name="r" type="float"/>
|
||||
<field name="phi" type="float"/>
|
||||
<field name="theta" type="float"/>
|
||||
<field name="psi" type="float"/>
|
||||
<field name="ax" type="float"/>
|
||||
<field name="ay" type="float"/>
|
||||
<field name="az" type="float"/>
|
||||
<field name="ve" type="float"/>
|
||||
<field name="vn" type="float"/>
|
||||
<field name="vu" type="float"/>
|
||||
<field name="lat" type="float"/>
|
||||
<field name="lon" type="float"/>
|
||||
<field name="alt" type="float"/>
|
||||
<field name="we" type="float"/>
|
||||
<field name="wn" type="float"/>
|
||||
<message name="REMOTE_GPS" id="55" link="broadcasted">
|
||||
<field name="ac_id" type="uint8"/>
|
||||
<field name="numsv" type="uint8"/>
|
||||
<field name="ecef_x" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="ecef_y" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="ecef_z" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="lat" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="lon" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="alt" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="hmsl" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="ecef_xd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="ecef_yd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="ecef_zd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="tow" type="uint32"/>
|
||||
<field name="course" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
</message>
|
||||
|
||||
<message name="KITE_COMMAND" id="96">
|
||||
|
||||
@@ -1,44 +1,34 @@
|
||||
<!DOCTYPE module SYSTEM "./module.dtd">
|
||||
|
||||
<!--
|
||||
|
||||
// Use (parts of) the following section in airframe file to change
|
||||
|
||||
# ap.CFLAGS += -DGPS_TRIGGERED_FUNCTION="dc_shoot_on_gps"
|
||||
# ap.CFLAGS += -DDC_GPS_TRIGGER_START=1
|
||||
# ap.CFLAGS += -DDC_GPS_TRIGGER_STOP=3
|
||||
|
||||
-->
|
||||
|
||||
<module name="digital_cam">
|
||||
<doc>
|
||||
<description>Digital camera control (trigger using led)</description>
|
||||
<define name="DC_SHOOT_ON_BUTTON_RELEASE" />
|
||||
<define name="SENSOR_SYNC_SEND" value="1" />
|
||||
|
||||
<define name="DC_PUSH" value="LED_ON" />
|
||||
<define name="DC_RELEASE" value="LED_OFF" />
|
||||
<description>Digital camera control (trigger using GPIO)</description>
|
||||
<define name="DC_SHOOT_ON_BUTTON_RELEASE" description="if defined, call dc_send_shot_postion on button release instead of on push"/>
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12" description="mandatory, gpio to control shutter"/>
|
||||
<define name="DC_ZOOM_IN_GPIO" value="GPIOC,GPIO2" description="optional, gpio to activate zoom in"/>
|
||||
<define name="DC_ZOOM_OUT_GPIO" value="GPIOC,GPIO5" description="optional, gpio to activate zoom out"/>
|
||||
<define name="DC_POWER_GPIO" value="GPIOB,GPIO1" description="optional, gpio to turn power on"/>
|
||||
<define name="DC_POWER_OFF_GPIO" value="GPIOC,GPIO1" description="optional, gpio to turn power off"/>
|
||||
<define name="DC_PUSH" value="gpio_set|gpio_clear" description="specifies whether to set or clear gpio to push the shutter (default: gpio_set)"/>
|
||||
<define name="DC_RELEASE" value="gpio_clear|gpio_set" description="specifies whether to set or clear gpio to release the shutter (default: gpio_clear)"/>
|
||||
|
||||
<define name="DC_AUTOSHOOT_QUARTERSEC_PERIOD" value="6" description="quarter_second"/>
|
||||
<define name="DC_AUTOSHOOT_METER_GRID" value="50" description="grid in meters"/>
|
||||
</doc>
|
||||
|
||||
<header>
|
||||
<file name="led_cam_ctrl.h"/>
|
||||
<file name="gpio_cam_ctrl.h"/>
|
||||
</header>
|
||||
|
||||
<init fun="led_cam_ctrl_init()"/>
|
||||
<init fun="gpio_cam_ctrl_init()"/>
|
||||
|
||||
<periodic fun="led_cam_ctrl_periodic()" freq="4" autorun="TRUE"/>
|
||||
<periodic fun="gpio_cam_ctrl_periodic()" freq="4" autorun="TRUE"/>
|
||||
|
||||
<makefile >
|
||||
|
||||
<define name="DIGITAL_CAM" />
|
||||
<file name="led_cam_ctrl.c"/>
|
||||
<file name="gpio_cam_ctrl.c"/>
|
||||
<file name="dc.c"/>
|
||||
<define name="SENSOR_SYNC_SEND" value="1" />
|
||||
|
||||
<define name="SENSOR_SYNC_SEND" value="1"/>
|
||||
</makefile>
|
||||
|
||||
|
||||
</module>
|
||||
|
||||
@@ -1,29 +1,15 @@
|
||||
<!DOCTYPE module SYSTEM "./module.dtd">
|
||||
|
||||
<!--
|
||||
|
||||
// Use (parts of) the following section in airframe file to change
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
|
||||
<configure name="PUSH" value"LED_ON" />
|
||||
<configure name="RELEASE" value"LED_OFF" />
|
||||
|
||||
<configure name="AUTOSHOOT_QUARTERSEC_PERIOD" value="6" unit="quarter_second"/>
|
||||
<configure name="AUTOSHOOT_METER_GRID" value="50" unit="meter"/>
|
||||
</section>
|
||||
|
||||
# ap.CFLAGS += -DGPS_TRIGGERED_FUNCTION="dc_shoot_on_gps"
|
||||
# ap.CFLAGS += -DDC_GPS_TRIGGER_START=1
|
||||
# ap.CFLAGS += -DDC_GPS_TRIGGER_STOP=3
|
||||
|
||||
-->
|
||||
|
||||
<module name="digital_cam_servo" dir="digital_cam">
|
||||
<doc>
|
||||
<description>Digital camera control (trigger using servo)</description>
|
||||
<define name="DC_SHOOT_ON_BUTTON_RELEASE" />
|
||||
<define name="SENSOR_SYNC_SEND" value="1" />
|
||||
<define name="DC_SHOOT_ON_BUTTON_RELEASE" description="if defined, call dc_send_shot_postion on button release instead of on push"/>
|
||||
<define name="DC_SHUTTER_SERVO" value="servo" description="mandatory, Servo to control shutter"/>
|
||||
<define name="DC_ZOOM_IN_SERVO" value="servo" description="optional, Servo to activate zoom in"/>
|
||||
<define name="DC_ZOOM_OUT_SERVO" value="servo" description="optional, Servo to activate zoom out"/>
|
||||
<define name="DC_POWER_SERVO" value="servo" description="optional, Servo to control power"/>
|
||||
<define name="DC_AUTOSHOOT_QUARTERSEC_PERIOD" value="6" description="quarter_second"/>
|
||||
<define name="DC_AUTOSHOOT_METER_GRID" value="50" description="grid in meters"/>
|
||||
</doc>
|
||||
|
||||
<header>
|
||||
@@ -35,14 +21,10 @@
|
||||
<periodic fun="servo_cam_ctrl_periodic()" freq="4" autorun="TRUE"/>
|
||||
|
||||
<makefile >
|
||||
|
||||
<define name="DIGITAL_CAM" />
|
||||
<define name="DIGITAL_CAM"/>
|
||||
<file name="servo_cam_ctrl.c"/>
|
||||
<file name="dc.c"/>
|
||||
<define name="SENSOR_SYNC_SEND" value="1" />
|
||||
|
||||
<define name="SENSOR_SYNC_SEND" value="1"/>
|
||||
</makefile>
|
||||
|
||||
|
||||
</module>
|
||||
|
||||
|
||||
@@ -0,0 +1,23 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="follow" dir="multi">
|
||||
<doc>
|
||||
<description>Follow a certain AC_ID trough remote GPS</description>
|
||||
<define name="FOLLOW_AC_ID" description="the aircraft ID which it has to follow"/>
|
||||
<define name="FOLLOW_WAYPOINT_ID" description="the waypoint ID which it has to change"/>
|
||||
<define name="FOLLOW_OFFSET_X" value="0" description="the x offset in ENU (meters) from the plane"/>
|
||||
<define name="FOLLOW_OFFSET_Y" value="0" description="the y offset in ENU (meters) from the plane"/>
|
||||
<define name="FOLLOW_OFFSET_Z" value="0" description="the z offset in ENU (meters) from the plane"/>
|
||||
</doc>
|
||||
|
||||
<header>
|
||||
<file name="follow.h"/>
|
||||
</header>
|
||||
|
||||
<init fun="follow_init()"/>
|
||||
<datalink message="REMOTE_GPS" fun="ParseRemoteGps()"/>
|
||||
|
||||
<makefile>
|
||||
<file name="follow.c"/>
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -10,7 +10,7 @@
|
||||
<init fun="init_mf_daq()"/>
|
||||
<periodic fun="mf_daq_send_state()" freq="10."/>
|
||||
<periodic fun="mf_daq_send_report()" freq="1." autorun="TRUE"/>
|
||||
<datalink message="MF_DAQ" fun="parse_mf_daq_msg()"/>
|
||||
<datalink message="PAYLOAD_FLOAT" fun="parse_mf_daq_msg()"/>
|
||||
<makefile>
|
||||
<file name="meteo_france_DAQ.c"/>
|
||||
</makefile>
|
||||
|
||||
@@ -12,12 +12,16 @@ Four modes:
|
||||
- HEADING: the servo position and the heading of the rotorcraft are set with angles
|
||||
- WP: the camera is tracking a waypoint (Default: CAM)
|
||||
|
||||
The CAM_SWITCH can be used to power the camera in normal modes and disable it when in NONE mode.
|
||||
If ROTORCRAFT_CAM_SWITCH_GPIO is defined, this gpio is set/cleared to switch the power
|
||||
of the camera on in normal modes and disable it when in NONE mode.
|
||||
On boards with CAM_SWITCH, ROTORCRAFT_CAM_SWITCH_GPIO can be defined to CAM_SWITCH_GPIO.
|
||||
|
||||
</description>
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="DEFAULT_MODE" value="MODE_NONE|MODE_MANUAL|MODE_HEADING|MODE_WP" description="Select default mode (default: MODE_NONE)"/>
|
||||
<define name="CAM_ON" value="handler" description="Handler to power on the camera ({} to disable)"/>
|
||||
<define name="CAM_OFF" value="handler" description="Handler to power off the camera ({} to disable)"/>
|
||||
<define name="SWITCH_GPIO" value="gpio" description="GPIO used to turn on/off the camer power, e.g. CAM_SWITCH_GPIO or GPIOB,GPIO22. Nothing set by default."/>
|
||||
<define name="CAM_ON" value="gpio_set|gpio_clear" description="Gpio output level to turn camera power power on. gpio_set (default) or gpio_clear"/>
|
||||
<define name="CAM_OFF" value="gpio_set|gpio_clear" description="Gpio output level to turn camera power power off. gpio_set or gpio_clear (default) "/>
|
||||
<define name="TILT_SERVO" value="name" description="Servo name for tilt control (no tilt control if not defined)"/>
|
||||
<define name="TILT_ANGLE_MIN" value="angle" description="Tilt angle corresponding to the servo min position"/>
|
||||
<define name="TILT_ANGLE_MAX" value="angle" description="Tilt angle corresponding to the servo max position"/>
|
||||
|
||||
@@ -7,8 +7,9 @@
|
||||
Reads an anlog sonar sensor and outputs sonar distance in [m]
|
||||
</description>
|
||||
<configure name="ADC_SONAR" value="ADC_X" description="select ADC to use with the sonar"/>
|
||||
<define name="SONAR_OFFSET" value="0.0" description="sensor offset in [m] - default is 0.0"/>
|
||||
<define name="SONAR_OFFSET" value="0" description="sensor offset in [adc] - default is 0"/>
|
||||
<define name="SONAR_SCALE" value="0.0166" description="sensor scale factor [m/adc] - default is 0.0166"/>
|
||||
<define name="USE_SONAR" value="" description="activate use of sonar in INS extended filter (only rotorcraft)"/>
|
||||
</doc>
|
||||
|
||||
<header>
|
||||
@@ -24,7 +25,6 @@
|
||||
<makefile target="ap">
|
||||
<define name="ADC_CHANNEL_SONAR" value="$(ADC_SONAR)"/>
|
||||
<define name="USE_$(ADC_SONAR)"/>
|
||||
<define name="USE_SONAR"/>
|
||||
</makefile>
|
||||
|
||||
</module>
|
||||
|
||||
@@ -1,28 +0,0 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="sonar">
|
||||
<doc>
|
||||
<description>
|
||||
Sonar ADC (INS bindings).
|
||||
Sonar ADC driver with INS binding, wich oes the same than sonar_adc module with an event function to feed INS subsystem.
|
||||
Even if SONAR_OFFSET and _SCALE can be set, currently only the raw value and the INS_SONAR_SENS will be used in ins filters.
|
||||
</description>
|
||||
<configure name="ADC_SONAR" value="ADC_X" description="select ADC to use with the sonar"/>
|
||||
</doc>
|
||||
<header>
|
||||
<file name="sonar_adc.h"/>
|
||||
<file name="ins.h" dir="subsystems"/>
|
||||
</header>
|
||||
<init fun="sonar_adc_init()"/>
|
||||
<periodic fun="sonar_adc_read()" freq="10"/>
|
||||
<event fun="SonarEvent(ins_update_sonar)"/>
|
||||
<makefile>
|
||||
<file name="sonar_adc.c"/>
|
||||
</makefile>
|
||||
<makefile target="ap">
|
||||
<define name="ADC_CHANNEL_SONAR" value="$(ADC_SONAR)"/>
|
||||
<define name="USE_$(ADC_SONAR)"/>
|
||||
<define name="USE_SONAR"/>
|
||||
</makefile>
|
||||
|
||||
</module>
|
||||
@@ -45,11 +45,11 @@
|
||||
|
||||
<!DOCTYPE radio SYSTEM "radio.dtd">
|
||||
<radio name="Futaba T10CG with SBUS" data_min="900" data_max="2100" sync_min ="5000" sync_max ="15000" pulse_type="POSITIVE">
|
||||
<channel ctl="A" function="ROLL" min="363" neutral="1024" max="1683" average="0"/>
|
||||
<channel ctl="B" function="PITCH" min="363" neutral="1024" max="1683" average="0"/>
|
||||
<channel ctl="C" function="THROTTLE" min="1683" neutral="1683" max="363" average="0"/>
|
||||
<channel ctl="D" function="YAW" min="363" neutral="1024" max="1683" average="0"/>
|
||||
<channel ctl="E" function="MODE" max="137" neutral="1024" min="1908" average="1"/>
|
||||
<channel ctl="F" function="GAIN1" min="137" neutral="1024" max="1908" average="0"/>
|
||||
<channel ctl="G" function="GAIN2" min="137" neutral="1024" max="1908" average="0"/>
|
||||
<channel ctl="A" function="ROLL" min="1107" neutral="1520" max="1932" average="0"/>
|
||||
<channel ctl="B" function="PITCH" min="1107" neutral="1520" max="1932" average="0"/>
|
||||
<channel ctl="C" function="THROTTLE" min="1932" neutral="1932" max="1107" average="0"/>
|
||||
<channel ctl="D" function="YAW" min="1107" neutral="1520" max="1932" average="0"/>
|
||||
<channel ctl="E" function="MODE" max="966" neutral="1520" min="2072" average="1"/>
|
||||
<channel ctl="F" function="GAIN1" min="966" neutral="1520" max="2072" average="0"/>
|
||||
<channel ctl="G" function="GAIN2" min="966" neutral="1520" max="2072" average="0"/>
|
||||
</radio>
|
||||
|
||||
@@ -14,6 +14,7 @@
|
||||
|
||||
<dl_settings NAME="Horiz Loop">
|
||||
<dl_setting var="guidance_h_use_ref" min="0" step="1" max="1" module="guidance/guidance_h" shortname="use_ref" values="FALSE|TRUE" handler="SetUseRef" param="GUIDANCE_H_USE_REF"/>
|
||||
<dl_setting var="gh_max_speed" min="0.1" step="0.1" max="15.0" module="guidance/guidance_h" shortname="max_speed" handler="SetMaxSpeed" param="GUIDANCE_H_REF_MAX_SPEED"/>
|
||||
<dl_setting var="guidance_h_approx_force_by_thrust" min="0" step="1" max="1" module="guidance/guidance_h" shortname="approx_force" values="FALSE|TRUE" param="GUIDANCE_H_APPROX_FORCE_BY_THRUST"/>
|
||||
<dl_setting var="guidance_h_pgain" min="0" step="1" max="400" module="guidance/guidance_h" shortname="kp" param="GUIDANCE_H_PGAIN"/>
|
||||
<dl_setting var="guidance_h_dgain" min="0" step="1" max="400" module="guidance/guidance_h" shortname="kd" param="GUIDANCE_H_DGAIN"/>
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user