Merge branch 'master' into dev

This commit is contained in:
Felix Ruess
2011-11-19 14:02:48 +01:00
24 changed files with 218 additions and 116 deletions
+16 -8
View File
@@ -233,11 +233,11 @@ fast_deb:
$(MAKE) deb OCAMLC=ocamlc.opt DEBFLAGS=-b
clean:
rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-arm7 debian/paparazzi-avr debian/paparazzi-base debian/paparazzi-bin debian/paparazzi-dev
rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(DL_PROTOCOL_H)
find . -mindepth 2 -name Makefile -exec sh -c '$(MAKE) -C `dirname {}` $@' \;
find . -name '*~' -exec rm -f {} \;
rm -f paparazzi sw/simulator/launchsitl
$(Q)rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-base debian/paparazzi-bin
$(Q)rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(DL_PROTOCOL_H)
$(Q)find . -mindepth 2 -name Makefile -exec sh -c 'echo "Cleaning {}"; $(MAKE) -C `dirname {}` $@' \;
$(Q)find . -name '*~' -exec rm -f {} \;
$(Q)rm -f paparazzi sw/simulator/launchsitl
cleanspaces:
find ./sw/airborne -name '*.[ch]' -exec sed -i {} -e 's/[ \t]*$$//' \;
@@ -247,9 +247,14 @@ cleanspaces:
find ./conf -name '*.xml' -exec sed -i {} -e 's/[ \t]*$$//' ';'
distclean : dist_clean
dist_clean : clean
rm -r conf/srtm_data
rm -r conf/maps_data conf/maps.xml
dist_clean :
@echo "Warning: This removes all non-repository files. This means you will loose your aircraft list, your maps, your logfiles, ... if you want this, then run: make dist_clean_irreversible"
dist_clean_irreversible: clean
rm -rf conf/srtm_data
rm -rf conf/maps_data conf/maps.xml
rm -rf conf/conf.xml conf/controlpanel.xml
rm -rf var
ab_clean:
find sw/airborne -name '*~' -exec rm -f {} \;
@@ -260,6 +265,9 @@ test_all_example_airframes:
$(MAKE) AIRCRAFT=Tiny_IMU clean_ac ap
$(MAKE) AIRCRAFT=EasyStar_ETS clean_ac ap sim
test_all_example_airframes2:
for ap in `grep name conf/conf.xml.example | sed -e 's/.*name=\"//' | sed -e 's/"//'`; do echo "Making $$ap"; make -C ./ AIRCRAFT=$$ap clean_ac ap.compile; done
commands: paparazzi sw/simulator/launchsitl
paparazzi:
+5 -5
View File
@@ -221,18 +221,17 @@ printcommands:
@echo "Using DMP = $(OBJDUMP)"
@echo "Using NM = $(NM)"
@echo "Using SIZE = $(SIZE)"
@echo "Using OOCD = $(OOCD)"
@echo "GCC version:"
@$(CC) --version | head -1
ifeq ("$(MULTILIB)","yes")
printmultilib:
@echo "*** Using multilib ***"
@echo "--------------------------"
@echo "--------------------------------------"
else
printmultilib:
@echo "*** NOT using multilib ***"
@echo "--------------------------"
@echo "--------------------------------------"
endif
build: elf hex lss sym
@@ -247,10 +246,10 @@ sym: $(OBJDIR)/$(TARGET).sym
HEXSIZE = $(SIZE) --target=$(FORMAT) $(OBJDIR)/$(TARGET).hex
ELFSIZE = $(SIZE) -A $(OBJDIR)/$(TARGET).elf
sizebefore:
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; $(ELFSIZE); echo; fi
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Previous size:"; $(ELFSIZE); fi
sizeafter:
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; $(ELFSIZE); echo; fi
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Current size:"; $(ELFSIZE); fi
# Program the device.
@@ -258,6 +257,7 @@ load upload program: $(OBJDIR)/$(TARGET).hex
ifeq ($(FLASH_MODE),IAP)
$(SUDO) $(LPC21IAP) $(OBJDIR)/$(TARGET).elf
else ifeq ($(FLASH_MODE),JTAG)
@echo "Using OOCD = $(OOCD)"
@echo -e " OOCD\t$<"
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_TARGET).cfg \
+11 -6
View File
@@ -44,6 +44,10 @@ TOOLCHAIN_DIR=$(shell dirname $(TOOLCHAIN))
GCC_BIN_DIR=$(TOOLCHAIN_DIR)/bin
GCC_LIB_DIR=$(TOOLCHAIN_DIR)/arm-none-eabi/lib
# Detect if we are using the new libopencm3 or the old libopenstm32
LIBOPENCM3_LIB=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "opencm3_stm32f1"; else echo "opencm3_stm32"; fi)
LIBOPENCM3_DEFS=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "-DSTM32F1"; fi)
# Define programs and commands.
GCC_BIN_PREFIX=$(GCC_BIN_DIR)/arm-none-eabi
CC = $(GCC_BIN_PREFIX)-gcc
@@ -133,6 +137,7 @@ CFLAGS += -Wmissing-prototypes
CFLAGS += -Wstrict-prototypes
CFLAGS += -Wmissing-declarations
CFLAGS += -Wswitch-default
CFLAGS += $(LIBOPENCM3_DEFS)
CFLAGS += $($(TARGET).CFLAGS)
@@ -148,7 +153,7 @@ else
LDFLAGS = -D__thumb2__ -T$(LDSCRIPT) -nostartfiles -L$(GCC_LIB_DIR) -O$(OPT) --gc-sections
endif
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(TARGET).map,--cref,--gc-sections
LDLIBS += -lc -lm -lgcc -lcmsis -lstm32 -lopencm3_stm32
LDLIBS += -lc -lm -lgcc -lcmsis -lstm32 -l$(LIBOPENCM3_LIB)
CPFLAGS = -j .isr_vector -j .text -j .data
CPFLAGS_BIN = -Obinary
@@ -168,18 +173,17 @@ printcommands:
@echo "Using DMP = $(DMP)"
@echo "Using NM = $(NM)"
@echo "Using SIZE = $(SIZE)"
@echo "Using OOCD = $(OOCD)"
@echo "GCC version:"
@$(CC) --version | head -1
@echo "OOCD version:"
@$(OOCD) --version | head -1
ifeq ("$(MULTILIB)","yes")
printmultilib:
@echo "*** Using multilib ***"
@echo "--------------------------------------"
else
printmultilib:
@echo "*** NOT using multilib ***"
@echo "--------------------------------------"
endif
build: elf bin hex
@@ -194,10 +198,10 @@ sym: $(OBJDIR)/$(TARGET).sym
# Display size of file.
ELFSIZE = $(SIZE) -A $(OBJDIR)/$(TARGET).elf
sizebefore:
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; $(ELFSIZE); echo; fi
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Previous size:"; $(ELFSIZE); fi
sizeafter:
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; $(ELFSIZE); echo; fi
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Current size:"; $(ELFSIZE); fi
@@ -246,6 +250,7 @@ upload: $(OBJDIR)/$(TARGET).bin
$(LOADER) -p /dev/ttyUSB0 -b 115200 -e -w -v $^
else ifeq ($(FLASH_MODE),JTAG)
upload: $(OBJDIR)/$(TARGET).elf
@echo "Using OOCD = $(OOCD)"
@echo " OOCD\t$<"
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
+7 -4
View File
@@ -7,7 +7,7 @@
<airframe name="Yapa v1">
<servos>
<servo name="THROTTLE" no="0" min="1100" neutral="1100" max="1900"/>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILERON_LEFT" no="2" min="900" neutral="1500" max="2100"/>
<servo name="AILERON_RIGHT" no="6" min="900" neutral="1500" max="2100"/>
<servo name="ELEVATOR" no="7" min="1900" neutral="1500" max="1100"/>
@@ -17,8 +17,8 @@
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="9600"/> <!-- both elerons up as butterfly brake ? -->
</commands>
@@ -103,8 +103,8 @@
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="-0.205" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="-0.232" unit="rad"/>
<define name="ROLL_NEUTRAL_DEFAULT" value="0.0" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="-0.075" unit="rad"/>
</section>
<section name="MISC">
@@ -120,6 +120,9 @@
<define name="GLIDE_AIRSPEED" value="10"/>
<define name="GLIDE_VSPEED" value="3."/>
<define name="GLIDE_PITCH" value="45" unit="deg"/>
<define name="COMMAND_ROLL_TRIM" value="-2300" />
<define name="COMMAND_PITCH_TRIM" value="1800" />
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
+109 -73
View File
@@ -1,25 +1,91 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
YAPA + XSens + XBee
Skywalker Fiberglass "GraySky" FPV 168 (http://www..com/)
YAPA v2 (http://paparazzi.enac.fr/wiki/Yapa#Yapa_v2)
With modified power routing
* Aspiring
* XBee 2.4Ghz
* uBlox LEA5H and Sarantel helix GPS antenna
Notes:
The two aileron servos are separately connected and have an additional spoileron function
-->
<airframe name="Yapa v2">
<airframe name="Graysky">
<!-- **************************** FIRMWARE ********************************* -->
<firmware name="fixedwing">
<target name="ap" board="tiny_2.11">
<configure name="PERIODIC_FREQUENCY" value="120"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<configure name="AHRS_ALIGNER_LED" value="3"/>
</target>
<target name="sim" board="pc"/>
<define name="LOITER_TRIM"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<!-- Radio Control -->
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>
<!-- Actuators -->
<subsystem name="control"/>
<!-- Navigation -->
<subsystem name="navigation"/>
<!-- Sensors -->
<subsystem name="imu" type="aspirin_i2c"/>
<subsystem name="ahrs" type="float_dcm"/>
<subsystem name="gps" type="ublox"/>
</firmware>
<!-- **************************** MODULES ********************************** -->
<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="ins_ppzuavimu.xml"/> -->
<load name="digital_cam.xml">
<define name="DC_SHUTTER_LED" value="3"/>
</load>
</modules>
<!-- ***************************** SERVOS ********************************** -->
<servos>
<servo name="THROTTLE" no="9" min="1100" neutral="1100" max="1900"/>
<!-- Define here to which CONNECTOR NUMBER the servo is connected to, on the autopilot cicuit board -->
<servo name="THROTTLE" no="9" min="1000" neutral="1000" max="2000"/>
<servo name="AILERON_LEFT" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="AILERON_RIGHT" no="8" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVATOR" no="5" min="1900" neutral="1500" max="1100"/>
<servo name="RUDDER" no="1" min="1100" neutral="1500" max="1900"/>
</servos>
<!-- commands section -->
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="9600"/> <!-- both elerons up as butterfly brake ? -->
<!-- both ailerons up as braking spoilerons -->
<axis name="BRAKE" failsafe_value="9600"/>
</commands>
<rc_commands>
@@ -30,6 +96,15 @@
<set command="BRAKE" value="@FLAPS"/>
</rc_commands>
<!-- To still be able to use rudder in autonomous fight YAW can come in handy while tuning -->
<!--
<auto_rc_commands>
<set command="YAW" value="@YAW"/>
<set command="GAIN1" value="@GAIN1"/>
<set command="CALIB" value="@CALIB"/>
</auto_rc_commands>
-->
<section name="SERVO_MIXER_GAINS">
<define name="AILERON_NEUTRAL" value="0.3f"/>
@@ -41,7 +116,7 @@
<define name="PITCH_GAIN" value="0.9f"/>
<define name="BRAKE_AILEVON" value="-0.7f"/>
<define name="BRAKE_SPOILERON" value="-0.7f"/>
<define name="BRAKE_PITCH" value="0.1f"/>
<define name="MAX_BRAKE_RATE" value="130"/>
@@ -66,8 +141,8 @@
<let var="aileron_down" value="(@ROLL * (((float)$aileron_down_rate) / ((float)MAX_PPRZ)))"/>
<let var="leftturn" value="(@ROLL >= 0? 1 : 0)"/>
<let var="rightturn" value="(1 - $leftturn)"/>
<set servo="AILERON_LEFT" value="($aileron_up * $leftturn) + ($aileron_down * $rightturn) - $brake_value*(BRAKE_AILEVON) - (MAX_PPRZ * AILERON_NEUTRAL)"/>
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_AILEVON) + (MAX_PPRZ *AILERON_NEUTRAL)"/>
<set servo="AILERON_LEFT" value="($aileron_up * $leftturn) + ($aileron_down * $rightturn) - $brake_value*(BRAKE_SPOILERON) - (MAX_PPRZ * AILERON_NEUTRAL)"/>
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_SPOILERON) + (MAX_PPRZ *AILERON_NEUTRAL)"/>
<set servo="RUDDER" value="@YAW + @ROLL * RUDDER_OF_AILERON"/>
<set servo="THROTTLE" value="@THROTTLE"/>
@@ -91,9 +166,11 @@
<section name="BAT">
<!-- <define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/> -->
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
<!-- Note that 3S lipo 3.1*3=9.3 most of the time the cutof for the motor part of the ESC -->
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
</section>
<section name="IMU" prefix="IMU_">
@@ -102,10 +179,11 @@
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 14.375 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
<define name="GYRO_P_SENS" value="4.947" integer="16"/>
<define name="GYRO_Q_SENS" value="4.947" integer="16"/>
<define name="GYRO_R_SENS" value="4.947" integer="16"/>
<!-- ITG3200: SENS = 14.375 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
<!-- IMU3000: SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
<define name="GYRO_P_SENS" value="4.336" integer="16"/>
<define name="GYRO_Q_SENS" value="4.336" integer="16"/>
<define name="GYRO_R_SENS" value="4.336" integer="16"/>
<define name="GYRO_P_Q" value="0."/>
<define name="GYRO_P_R" value="0"/>
@@ -115,12 +193,12 @@
<define name="GYRO_R_Q" value="0."/>
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="1"/>
<define name="GYRO_R_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<define name="ACCEL_X_NEUTRAL" value="-14"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<define name="ACCEL_X_NEUTRAL" value="-12"/>
<define name="ACCEL_Y_NEUTRAL" value="+3"/>
<define name="ACCEL_Z_NEUTRAL" value="-30"/>
<!-- SENS = 256 LSB/g @ 2.5V [X&Y: 265 LSB/g @ 3.3V] / 9.81 ms2/g = 26.095 LSB/ms2 / 10bit FRAC: 1024 / 26.095 for z and 1024 / 27.01 for X&Y -->
<define name="ACCEL_X_SENS" value="37.9" integer="16"/>
@@ -128,8 +206,8 @@
<define name="ACCEL_Z_SENS" value="39.24" integer="16"/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="1"/>
<define name="ACCEL_Z_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
@@ -154,6 +232,10 @@
</section>
<section name="MISC">
<define name="COMMAND_ROLL_TRIM" value="1" />
<define name="COMMAND_PITCH_TRIM" value="-1" />
<define name="NOMINAL_AIRSPEED" value="17." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
@@ -162,11 +244,13 @@
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<!-- The Glide definitions are used for calculating the touch down point during auto landing -->
<define name="GLIDE_AIRSPEED" value="10"/>
<define name="GLIDE_VSPEED" value="3."/>
<define name="GLIDE_PITCH" value="45" unit="deg"/>
</section>
<!-- ******************* VERTICAL CONTROL ********************************** -->
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
@@ -188,6 +272,8 @@
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
</section>
<!-- ******************* HORIZONTAL CONTROL ******************************** -->
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="-1.16799998283"/>
<define name="COURSE_DGAIN" value="0.280999988317"/>
@@ -208,6 +294,7 @@
<define name="ROLL_RATE_GAIN" value="-820.312011719"/>
</section>
<!-- ***************************** AGGRESIVE ******************************* -->
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="30"/>
<define name="BLEND_END" value="15"/>
@@ -219,6 +306,7 @@
<define name="DESCENT_NAV_RATIO" value="0.834999978542"/>
</section>
<!-- ****************************** FAILSAFE ******************************* -->
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
@@ -229,62 +317,10 @@
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
</section>
<!-- ******************************* CAMERA ******************************** -->
<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="ins_ppzuavimu.xml"/> -->
<load name="digital_cam.xml">
<define name="DC_SHUTTER_LED" value="2"/>
</load>
</modules>
<firmware name="fixedwing">
<target name="ap" board="tiny_2.11">
<configure name="PERIODIC_FREQUENCY" value="120"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<configure name="AHRS_ALIGNER_LED" value="3"/>
</target>
<target name="sim" board="pc"/>
<define name="LOITER_TRIM"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>
<!-- Actuators -->
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="navigation"/>
<subsystem name="imu" type="aspirin_i2c"/>
<subsystem name="ahrs" type="float_dcm"/>
<subsystem name="gps" type="ublox"/>
</firmware>
</airframe>
+6 -1
View File
@@ -19,6 +19,7 @@
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="SHUTTER" failsafe_value="0"/>
</commands>
<rc_commands>
@@ -120,7 +121,8 @@
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="-1.4"/>
<define name="COURSE_PGAIN" value="-1.0"/>
<define name="COURSE_DGAIN" value="0.3"/>
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
@@ -195,6 +197,9 @@
<modules>
<load name="infrared_adc.xml"/>
<load name="digital_cam_servo.xml">
<define name="DC_SHUTTER_SERVO" value="COMMAND_SHUTTER" />
</load>
</modules>
+5 -1
View File
@@ -3,11 +3,15 @@ Q=@
all: $(DATADIR)/maps.google.com $(PAPARAZZI_HOME)/conf/maps.xml
clean:
$(DATADIR):
mkdir $(DATADIR)
$(DATADIR)/maps.google.com: $(DATADIR) FORCE
wget -O $(@) http://maps.google.com/
@echo "DOWNLOAD: google maps version code";
$(Q)wget -q -O $(@) http://maps.google.com/
$(PAPARAZZI_HOME)/conf/maps.xml: $(DATADIR)/maps.google.com
$(Q)echo "<!DOCTYPE maps SYSTEM \"maps.dtd\">" > $(@)
+4
View File
@@ -3,6 +3,9 @@ Q=@
SRTMData: $(DATADIR)/Africa $(DATADIR)/Australia $(DATADIR)/Eurasia $(DATADIR)/Islands $(DATADIR)/North_America $(DATADIR)/South_America
clean:
$(DATADIR):
mkdir $(DATADIR)
@@ -29,3 +32,4 @@ $(DATADIR)/South_America: $(DATADIR)
%.hgt.zip: SRTMData
$(Q)wget -c -nv -N http://dds.cr.usgs.gov/srtm/version2_1/SRTM3/$(shell grep -l $(@F) $(DATADIR)/* | sed -e s#$(DATADIR)/##)/$(@F)
+1 -1
View File
@@ -95,7 +95,7 @@ case "$choice" in
echo -e "-Now use one of your tags: \033[1mgit checkout TAG_NAME\033[0m (find the available TAG_NAMEs using \033[1mgit tag\033[0m ) (note that after this command you will be in detached head state which means that you are using a older revision and you can not commit changes here. If you want to make changes you have to make a branch from your tag)"
exit;
;;
4 ) clear; exit 1 ;;
5 ) clear; exit 1 ;;
esac
done
+4
View File
@@ -32,8 +32,12 @@
#include <stm32/flash.h>
#include <stm32/misc.h>
#ifdef USE_OPENCM3
# if defined(STM32F1) || defined(STM32F2) || defined(STM32F4)
# include <libopencm3/stm32/f1/rcc.h>
# else
# include <libopencm3/stm32/rcc.h>
# endif
#endif
void mcu_arch_init(void) {
@@ -287,6 +287,8 @@ static inline void autopilot_check_motors_on( void ) {
if (!(THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED())) // wait until stick released
autopilot_check_motor_status = STATUS_MOTORS_OFF;
break;
default:
break;
};
}
+1 -1
View File
@@ -145,7 +145,7 @@ uint8_t dc_survey(float interval, float x, float y) {
dc_gps_x = x;
dc_gps_y = y;
}
dc_gps_next_dist = interval;
dc_gps_next_dist = 0;
dc_info();
return 0;
}
+1 -1
View File
@@ -10,7 +10,7 @@ endif
all: davis2ivy kestrel2ivy
clean:
rm *.o davis2ivy kestrel2ivy
rm -f *.o davis2ivy kestrel2ivy
davis2ivy: davis2ivy.o
g++ -o davis2ivy davis2ivy.o $(LIBRARYS) -livy
+1 -1
View File
@@ -4,4 +4,4 @@ SMS_GS: SMS_Ground_UDtest_final.c
gcc -g -O2 -Wall `pkg-config --cflags glib-2.0 gtk+-2.0` -L/usr/lib -lglibivy -o SMS_GS SMS_Ground_UDtest_final.c `pkg-config --libs glib-2.0 gtk+-2.0` -lglibivy
clean:
rm SMS_GS
rm -f SMS_GS
+3 -3
View File
@@ -110,6 +110,7 @@ static void on_Estimator(IvyClientPtr app, void *user_data, int argc, char *argv
</message>
*/
local_uav.utm_z = (( atof(argv[0]) ) * 1000.0f);
local_uav.climb = atof(argv[1]);
}
@@ -168,7 +169,6 @@ static void on_Gps(IvyClientPtr app, void *user_data, int argc, char *argv[])
local_uav.utm_east = atoi(argv[1]);
local_uav.utm_north = atoi(argv[2]);
local_uav.utm_z = atoi(argv[4]);
local_uav.utm_zone = atoi(argv[9]);
local_uav.speed = atoi(argv[5]);
@@ -268,7 +268,7 @@ void send_ivy(void)
</message>
*/
IvySendMsg("%d NAVIGATION %d 0 0 0 0 0 0 0 \n", remote_uav.ac_id, remote_uav.block);
// IvySendMsg("%d NAVIGATION %d 0 0 0 0 0 0 0 \n", remote_uav.ac_id, remote_uav.block);
/*
<message name="BAT" id="12">
@@ -310,7 +310,7 @@ void send_ivy(void)
delayer++;
if (delayer > 5)
{
IvySendMsg("%d NAVIGATION_REF %d %d %d\n", remote_uav.ac_id, remote_uav.utm_east, remote_uav.utm_north, remote_uav.utm_zone);
// IvySendMsg("%d NAVIGATION_REF %d %d %d\n", remote_uav.ac_id, remote_uav.utm_east, remote_uav.utm_north, remote_uav.utm_zone);
delayer = 0;
}
+12
View File
@@ -446,6 +446,18 @@ let check_md5sum = fun ac_name alive_md5sum aircraft_conf_dir ->
assert (x = Pprz.int_of_value array.(i))
done
| _ -> failwith "Array expected here"
with _ ->
try
match alive_md5sum with
Pprz.Array array ->
let n = Array.length array in
assert(n = String.length md5sum / 2);
for i = 0 to n - 1 do
let x = 0 in
assert (x = Pprz.int_of_value array.(i))
done;
fprintf stderr "MD5 is ZERO, be carefull with configurations\n%!"
| _ -> failwith "Array expected here"
with _ ->
let error_message = sprintf "WARNING: live md5 signature for %s does not match current configuration, please reload your code (disable check with -no_md5_check option)" ac_name in
if !no_md5_check then
+1 -1
View File
@@ -6,7 +6,7 @@
#include <gtkdatabox_bars.h>
#include <gtkdatabox_grid.h>
#include <gtkdatabox_cross_simple.h>
#include <gtkdatabox_marker.h>
#include <gtkdatabox_markers.h>
#define NB_POINTS 121
+1 -1
View File
@@ -10,4 +10,4 @@ tcp2ivy_generic: tcp2ivy_generic.c
gcc -g -O2 -Wall `pkg-config glib-2.0 --cflags` -I../../../var/${AIRCRAFT} -o $@ $^ `pkg-config glib-2.0 --libs` -lglibivy -lm
clean:
rm email2udp udp2tcp tcp2ivy
rm -f email2udp udp2tcp tcp2ivy
@@ -5,6 +5,9 @@ obj-m += go7007.o go7007-usb.o snd-go7007.o wis-saa7115.o wis-tw9903.o \
wis-tw2804.o
go7007-objs := go7007-v4l2.o go7007-driver.o go7007-i2c.o go7007-fw.o
clean:
rm -f $(obj-m)
ifneq ($(SAA7134_BUILD),)
obj-m += saa7134-go7007.o
endif
+2
View File
@@ -122,4 +122,6 @@ clean:
.depend:
$(OCAMLDEP) $(INCLUDES) *.mli *.ml > .depend
ifneq ($(MAKECMDGOALS),clean)
include .depend
endif
+2
View File
@@ -26,4 +26,6 @@ clean:
.depend:
$(OCAMLDEP) $(INCLUDES) *.mli *.ml > .depend
ifneq ($(MAKECMDGOALS),clean)
include .depend
endif
+3
View File
@@ -68,3 +68,6 @@ TEST_SENSORS_SRCS = test_sensors.c \
test_sensors : $(TEST_SENSORS_SRCS)
gcc $(CFLAGS) -o $@ $^ $(LDFLAGS)
clean:
+4
View File
@@ -4,3 +4,7 @@ GLIB_LDFLAGS = `pkg-config glib-2.0 --libs` -lglibivy -lpcre
ttx2scilab: ttx2scilab.c
$(CC) -Wall $(GLIB_CFLAGS) -o $@ $< $(GLIB_LDFLAGS)
clean:
rm -f ttx2scilab
+6 -1
View File
@@ -232,7 +232,12 @@ let parse_firmware = fun makefile_ac firmware ->
(* print makefile for this target *)
fprintf makefile_ac "\n###########\n# -target: '%s'\n" (Xml.attrib target "name");
fprintf makefile_ac "ifeq ($(TARGET), %s)\n" (Xml.attrib target "name");
try fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor") with _ -> ();
let has_processor =
try
not (String.compare (Xml.attrib target "processor") "" = 0)
with _ -> false in
if has_processor then
fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor");
List.iter (print_firmware_configure makefile_ac) config;
List.iter (print_firmware_configure makefile_ac) t_config;
List.iter (print_firmware_define makefile_ac) defines;