Merge remote branch 'paparazzi/master' into uart

Conflicts:
	conf/autopilot/rotorcraft.makefile
This commit is contained in:
Gautier Hattenberger
2011-01-27 17:16:56 +01:00
132 changed files with 2016 additions and 1083 deletions
+2
View File
@@ -19,6 +19,7 @@
/var
/dox
/paparazzi
# /conf/
/conf/conf.xml
@@ -77,6 +78,7 @@
# /sw/simulator/
/sw/simulator/gaia
/sw/simulator/simhitl
/sw/simulator/launchsitl
# /sw/supervision/
/sw/supervision/gtk_process.ml
+880 -544
View File
File diff suppressed because it is too large Load Diff
+19 -10
View File
@@ -60,14 +60,14 @@ XSENS_XML = $(CONF)/xsens_MTi-G.xml
TOOLS=$(PAPARAZZI_SRC)/sw/tools
HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc)
ifeq ($(strip $(HAVE_ARM_NONE_EABI_GCC)),)
#ARMGCC=/opt/paparazzi/bin/arm-elf-gcc
ARMGCC=/usr/bin/arm-elf-gcc
ARMGCC=$(shell which arm-elf-gcc)
else
ARMGCC=$(HAVE_ARM_NONE_EABI_GCC)
endif
OCAML=$(shell which ocaml)
OCAMLRUN=$(shell which ocamlrun)
all: static conf
all: commands static conf
static : lib center tools cockpit multimon tmtc logalizer lpc21iap sim_static static_h usb_lib
@@ -211,6 +211,7 @@ clean:
rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_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
cleanspaces:
find ./sw/airborne -name '*.[ch]' -exec sed -i {} -e 's/[ \t]*$$//' \;
@@ -226,9 +227,17 @@ ab_clean:
find sw/airborne -name '*~' -exec rm -f {} \;
test_all_example_airframes:
$(MAKE) AIRCRAFT=BOOZ2_A2 clean_ac ap
$(MAKE) AIRCRAFT=MJ5 clean_ac ap sim
$(MAKE) AIRCRAFT=TJ1 clean_ac ap sim
$(MAKE) AIRCRAFT=HITL clean_ac ap
$(MAKE) AIRCRAFT=DM clean_ac ap sim
$(MAKE) AIRCRAFT=CSC clean_ac ap
$(MAKE) AIRCRAFT=BOOZ2_A1 clean_ac ap sim
$(MAKE) AIRCRAFT=Microjet clean_ac ap sim
$(MAKE) AIRCRAFT=Tiny_IMU clean_ac ap
$(MAKE) AIRCRAFT=EasyStar_ETS clean_ac ap sim
commands: paparazzi sw/simulator/launchsitl
paparazzi:
cat src/paparazzi | sed s#OCAMLRUN#$(OCAMLRUN)# | sed s#OCAML#$(OCAML)# > $@
chmod a+x $@
sw/simulator/launchsitl:
cat src/$(@F) | sed s#OCAMLRUN#$(OCAMLRUN)# | sed s#OCAML#$(OCAML)# > $@
chmod a+x $@
+1 -1
View File
@@ -59,7 +59,7 @@ AIRCRAFT_MD5=$(AIRCRAFT_CONF_DIR)/aircraft.md5
Q=@
init:
@[ -d $(PAPARAZZI_HOME) ] || (echo "Copying config example in your $(PAPARAZZI_HOME) directory"; mkdir -p $(PAPARAZZI_HOME); cp -a conf $(PAPARAZZI_HOME); cp -a data $(PAPARAZZI_HOME); mkdir -p $(PAPARAZZI_HOME)/var/maps; mv $(PAPARAZZI_HOME)/data/maps/trtqtttqtsrrt*.jpg $(PAPARAZZI_HOME)/var/maps; mkdir -p $(PAPARAZZI_HOME)/var/include)
@[ -d $(PAPARAZZI_HOME) ] || (echo "Copying config example in your $(PAPARAZZI_HOME) directory"; mkdir -p $(PAPARAZZI_HOME); cp -a conf $(PAPARAZZI_HOME); cp -a data $(PAPARAZZI_HOME); mkdir -p $(PAPARAZZI_HOME)/var/maps; mkdir -p $(PAPARAZZI_HOME)/var/include)
demo:
$(SUPERVISION)
-3
View File
@@ -19,13 +19,11 @@ install_data:
$(INSTALL) -d $(DESTDIR)/data/maps
$(INSTALLDATA) data/maps/muret_UTM.xml data/maps/muret_UTM.gif $(DESTDIR)/data/maps
$(INSTALL) -d $(DESTDIR)/data/pictures/gcs_icons
$(INSTALLDATA) var/maps/trtqtttqtsrrtstq*.jpg var/maps/trtqtttqtsrrttsr*.jpg $(DESTDIR)/data/maps
$(INSTALLDATA) data/pictures/*.gif data/pictures/*.svg data/pictures/*.jpg data/pictures/*.png $(DESTDIR)/data/pictures
$(INSTALLDATA) data/pictures/gcs_icons/*.png $(DESTDIR)/data/pictures/gcs_icons
$(INSTALL) -d $(PREFIX)/usr/share/pixmaps
$(INSTALLDATA) data/pictures/penguin_icon.png $(PREFIX)/usr/share/pixmaps/paparazzi.png
$(INSTALL) -d $(DESTDIR)/data/srtm
$(INSTALLDATA) data/srtm/N43E001.hgt.bz2 $(DESTDIR)/data/srtm
install_conf:
@@ -40,7 +38,6 @@ install_conf:
$(INSTALLDATA) conf/airframes/microjet_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinstar_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinjet_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/tiny_hitl.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/example_twog_analogimu.xml $(DESTDIR)/conf/airframes
$(INSTALL) -d $(DESTDIR)/conf/autopilot
$(INSTALLDATA) conf/autopilot/*.makefile $(DESTDIR)/conf/autopilot
+1 -1
View File
@@ -35,7 +35,7 @@ CC = g++
endif
OCAMLC = ocamlc
SIMDIR = $(PAPARAZZI_SRC)/sw/simulator
CAMLINCLUDES = -I +lablgtk2 -I $(PAPARAZZI_SRC)/sw/lib/ocaml -I $(SIMDIR) -I +xml-light
CAMLINCLUDES = $(shell ocamlfind query -r -i-format lablgtk2) -I $(PAPARAZZI_SRC)/sw/lib/ocaml -I $(SIMDIR) $(shell ocamlfind query -r -i-format xml-light)
SIMSITLML = $(OBJDIR)/simsitl.ml
MYGTKINITCMO = myGtkInit.cmo
SITLCMA = $(SIMDIR)/sitl.cma
+23 -1
View File
@@ -53,6 +53,18 @@ SIZE = $(GCC_BIN_PREFIX)-size
RM = rm
OOCD = $(TOOLCHAIN_DIR)/bin/openocd
# If we can't find the toolchain then try picking up the compilers from the path
ifeq ($(TOOLCHAIN_DIR),)
CC = $(shell which arm-none-eabi-gcc)
LD = $(shell which arm-none-eabi-gcc)
CP = $(shell which arm-none-eabi-objcopy)
DMP = $(shell which arm-none-eabi-objdump)
NM = $(shell which arm-none-eabi-nm)
SIZE = $(shell which arm-none-eabi-size)
OOCD = $(shell which openocd)
GCC_LIB_DIR=$(shell dirname `which arm-none-eabi-gcc`)/../arm-none-eabi/lib
endif
LOADER=/home/poine/work/stm32/stm32loader-a3c51c26ad6c/stm32loader.py
ifndef $(TARGET).OOCD_INTERFACE
@@ -123,7 +135,17 @@ ODFLAGS = -S
# Default target.
all: sizebefore build sizeafter
all: printcommands sizebefore build sizeafter
printcommands:
$(Q)echo "Using CC = $(CC)"
$(Q)echo "Using LD = $(LD)"
$(Q)echo "Using CP = $(CP)"
$(Q)echo "Using DMP = $(DMP)"
$(Q)echo "Using NM = $(NM)"
$(Q)echo "Using SIZE = $(SIZE)"
$(Q)echo "Using RM = $(RM)"
$(Q)echo "Using OOCD = $(OOCD)"
build: elf bin hex
# lss sym
+2 -2
View File
@@ -106,8 +106,8 @@
<section name="INFRARED" prefix="IR_">
<define name="IR1_NEUTRAL" value="-15"/>
<define name="IR2_NEUTRAL" value="0"/>
<define name="TOP_NEUTRAL" value="-20"/>
<define name="IR2_NEUTRAL" value="10"/>
<define name="TOP_NEUTRAL" value="-15"/>
<define name="I2C_DEFAULT_CONF" value="1"/>
<define name="LATERAL_CORRECTION" value="1"/>
+46 -66
View File
@@ -1,19 +1,54 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<airframe name="MiniMag Tiny 0.99">
<airframe name="MiniMag Tiny 2.11">
<firmware name="fixedwing">
<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />
<target name="sim" board="pc" />
<target name="ap" board="tiny_2.11">
<define name="SPI_MASTER"/>
<define name="USE_SPI_SLAVE0"/>
</target>
<subsystem name="spi"/>
<!--subsystem name="i2c">
<define name="USE_I2C0"/>
</subsystem-->
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600" />
</subsystem>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="navigation" />
<!-- <subsystem name="attitude" type="infrared"/>-->
<subsystem name="control"/>
<subsystem name="gps" type="ublox_lea5h"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="tiny_2.11" />
<target name="setup_actuators" board="tiny_2.11" />
</firmware>
<modules>
<load name="ins_vn100.xml" />
</modules>
<!-- commands section -->
<servos>
<servo name="THROTTLE" no="0" min="1200" neutral="1200" max="2000"/>
<!-- Servo aileron gauche = couleur blanche -->
<!-- Aileron gauche oppose de l'aileron droit -->
<servo name="AILERON_LEFT" no="1" min="1775" neutral="1500" max="1050"/>
<servo name="AILERON_LEFT" no="4" min="1775" neutral="1500" max="1050"/>
<!-- max = valeur aileron vers le bas-->
<servo name="AILERON_RIGHT" no="3" min="1875" neutral="1475" max="1225"/>
<!-- Rudder = Couleur rouge droite gauche -->
<servo name="RUDDER" no="4" min="1875" neutral="1500" max="1250"/>
<servo name="ELEVATOR" no="5" min="1850" neutral="1586" max="1150"/>
<servo name="RUDDER" no="6" min="1875" neutral="1500" max="1250"/>
<servo name="ELEVATOR" no="7" min="1850" neutral="1586" max="1150"/>
</servos>
<commands>
@@ -51,11 +86,9 @@
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="adc" prefix="ADC_CHANNEL_">
<define name="IR1" value="ADC_0"/>
<define name="IR2" value="ADC_1"/>
<define name="IR_TOP" value="ADC_4"/>
<define name="IR_NB_SAMPLES" value="16"/>
<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="INFRARED" prefix="IR_">
@@ -98,7 +131,6 @@
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="-0.07"/>
@@ -123,7 +155,6 @@
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
<define name="THROTTLE_SLEW" value="0.05"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
@@ -138,7 +169,6 @@
<define name="PITCH_PGAIN" value="-9000."/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1250"/>
</section>
<section name="NAV">
@@ -155,64 +185,14 @@
<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>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="1" 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="DATALINK" prefix="DATALINK_">
<define name="DEVICE_TYPE" value="XBEE"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<makefile>
include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
ap.CFLAGS += -DACTUATORS=\"servos_4015_MAT_hw.h\" -DSERVOS_4015_MAT
ap.srcs += $(SRC_ARCH)/servos_4015_MAT_hw.c actuators.c
ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DXBEE_UART=Uart0 -DDATALINK=XBEE -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
#TRANSPARENT ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_4
ap.srcs += $(SRC_ARCH)/adc_hw.c
ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B19200
ap.srcs += gps_ubx.c gps.c latlong.c
ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN
ap.srcs += infrared.c estimator.c
ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM
ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/nav_line.c
# Config for SITL simulation
include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
sim.srcs += subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/nav_line.c
</makefile>
</airframe>
@@ -28,6 +28,7 @@
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
@@ -26,6 +26,7 @@
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+1
View File
@@ -12,6 +12,7 @@
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+1
View File
@@ -11,6 +11,7 @@
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
+1
View File
@@ -202,6 +202,7 @@
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.0"/>
<subsystem name="gps" type="ublox"/>
+1 -1
View File
@@ -181,7 +181,7 @@
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="telemetry" type="transparent"/>
<!-- <subsystem name="imu" type="b2_v1.1"/> -->
<subsystem name="imu" type="aspirin"/>
<subsystem name="gps" type="ublox"/>
+1 -1
View File
@@ -199,7 +199,7 @@
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ahrs" type="cmpl"/>
@@ -289,6 +289,7 @@ second attempt
<target name="sim" board="pc"/>
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="crista"/>
<subsystem name="gps" type="ublox"/>
@@ -198,6 +198,7 @@
<define name = "OVERRIDE_UART5_IRQ_HANDLER"/> -->
</target>
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="heli"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
@@ -248,6 +248,7 @@
<target name="sim" board="pc"/>
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+4 -5
View File
@@ -16,6 +16,7 @@
<define name="GUIDANCE_H_USE_REF"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk">
<configure name="MKK_I2C_SCL_TIME" value="150"/><!-- this is optional, 150 is default, e.g. use 50 for 8 motors-->
</subsystem>
@@ -35,6 +36,9 @@
</firmware>
<modules main_freq="512">
<load name="booz_pwm.xml">
<define name="USE_PWM1"/>
</load>
<load name="booz_drop.xml"/>
<load name="sys_mon.xml"/>
<!--load name="booz_cam.xml"/-->
@@ -233,9 +237,4 @@
<define name="AUTO2" value="AP_MODE_HOVER_Z_HOLD" />
</section>
<makefile location="after">
ap.srcs += $(SRC_BOOZ_ARCH)/booz2_pwm_hw.c
sim.srcs += $(SRC_BOOZ_SIM)/booz2_pwm_hw.c
</makefile>
</airframe>
+1
View File
@@ -204,6 +204,7 @@
<configure name="FLASH_MODE" value="IAP"/> <!-- default for the board but putting it here as example-->
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+113 -80
View File
@@ -16,6 +16,12 @@
<axis name="THRUST" failsafe_value="0"/>
</commands>
<!-- for the sim -->
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="3"/>
@@ -32,42 +38,46 @@
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32685"/>
<define name="GYRO_Q_NEUTRAL" value="33261"/>
<define name="GYRO_R_NEUTRAL" value="32707"/>
<define name="GYRO_P_SENS" value="1.096691894" integer="16"/>
<define name="GYRO_Q_SENS" value="1.066804199" integer="16"/>
<define name="GYRO_R_SENS" value="1.117463379" integer="16"/>
<define name="ACCEL_X_SENS" value="2.58358915626" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.58164052066" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.59655739465" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="32731"/>
<define name="ACCEL_Y_NEUTRAL" value="32101"/>
<define name="ACCEL_Z_NEUTRAL" value="32660"/>
<define name="MAG_X_SENS" value="5.32718104135" integer="16"/>
<define name="MAG_Y_SENS" value="4.87857821202" integer="16"/>
<define name="MAG_Z_SENS" value="3.11986612709" integer="16"/>
<define name="MAG_X_NEUTRAL" value="-43"/>
<define name="MAG_Y_NEUTRAL" value=" 49"/>
<define name="MAG_Z_NEUTRAL" value="-66"/>
<define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0.)"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0.)"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg( 45.)"/>
<define name="GYRO_P_NEUTRAL" value="32276"/>
<define name="GYRO_Q_NEUTRAL" value="33987"/>
<define name="GYRO_R_NEUTRAL" value="32801"/>
<define name="GYRO_P_SENS" value="0.92466" integer="16"/>
<define name="GYRO_Q_SENS" value="0.93226" integer="16"/>
<define name="GYRO_R_SENS" value="0.92943" integer="16"/>
<define name="GYRO_PQ_SENS" value="0.0" integer="16"/>
<define name="GYRO_PR_SENS" value="0.0" integer="16"/>
<define name="GYRO_QR_SENS" value="0.0" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="25875"/>
<define name="ACCEL_Y_NEUTRAL" value="26273"/>
<define name="ACCEL_Z_NEUTRAL" value="26152"/>
<define name="ACCEL_X_SENS" value="1.8788156268" integer="16"/>
<define name="ACCEL_Y_SENS" value="1.88941543145" integer="16"/>
<define name="ACCEL_Z_SENS" value="1.90349115464" integer="16"/>
<define name="ACCEL_XY_SENS" value="0.0" integer="16"/>
<define name="ACCEL_XZ_SENS" value="0.0" integer="16"/>
<define name="ACCEL_YZ_SENS" value="0.0" integer="16"/>
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="1." integer="16"/>
<define name="MAG_Y_SENS" value="1." integer="16"/>
<define name="MAG_Z_SENS" value="1." integer="16"/>
<define name="MAG_XY_SENS" value="0.0" integer="16"/>
<define name="MAG_XZ_SENS" value="0.0" integer="16"/>
<define name="MAG_YZ_SENS" value="0.0" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0. )"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg( 45. )"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_HOVER_Z_HOLD"/>
</section>
<section name="BAT">
@@ -114,27 +124,27 @@
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="-2000"/>
<define name="PHI_DGAIN" value="-400"/>
<define name="PHI_PGAIN" value="-900"/>
<define name="PHI_DGAIN" value="-200"/>
<define name="PHI_IGAIN" value="-200"/>
<define name="THETA_PGAIN" value="-2000"/>
<define name="THETA_DGAIN" value="-400"/>
<define name="THETA_IGAIN" value="-400"/>
<define name="THETA_PGAIN" value="-900"/>
<define name="THETA_DGAIN" value="-200"/>
<define name="THETA_IGAIN" value="-200"/>
<define name="PSI_PGAIN" value="-1000"/>
<define name="PSI_DGAIN" value="-350"/>
<define name="PSI_PGAIN" value="-900"/>
<define name="PSI_DGAIN" value="-200"/>
<define name="PSI_IGAIN" value="-10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 300"/>
<define name="THETA_DDGAIN" value=" 300"/>
<define name="PSI_DDGAIN" value=" 300"/>
<define name="PHI_DDGAIN" value=" 200"/>
<define name="THETA_DDGAIN" value=" 200"/>
<define name="PSI_DDGAIN" value=" 200"/>
</section>
<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="15." integer="16"/>
<define name="BARO_SENS" value="10." integer="16"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
@@ -164,49 +174,72 @@
<define name="FACE_REINJ_1" value="1024"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="INITIAL_CONDITITONS" value="&quot;reset00&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<makefile>
<!-- -->
<modules main_freq="512">
<load name="vehicle_interface_overo_link.xml"/>
</modules>
<!-- -->
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<!-- <define name="BOOZ_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="actuators" type="asctec_v2"/>
<subsystem name="telemetry" type="transparent"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ahrs" type="cmpl"/>
</firmware>
USER = root
HOST = 192.168.1.3
#HOST = overo
#HOST = beth
#HOST = asctec_lisa
TARGET_DIR = ~
<firmware name="lisa_l_test_progs">
<target name="test_led" board="lisa_l_1.1"/>
<target name="test_uart" board="lisa_l_1.1"/>
<target name="test_servos" board="lisa_l_1.1"/>
<target name="test_telemetry" board="lisa_l_1.1"/>
<target name="test_baro" board="lisa_l_1.1"/>
<target name="test_imu_b2" board="lisa_l_1.1"/>
<target name="test_imu_b2_2" board="lisa_l_1.1"/>
<target name="test_imu_aspirin" board="lisa_l_1.1"/>
<target name="test_rc_spektrum" board="lisa_l_1.1"/>
<target name="test_rc_ppm" board="lisa_l_1.1"/>
<target name="test_adc" board="lisa_l_1.1"/>
<target name="test_hmc5843" board="lisa_l_1.1"/>
<target name="test_itg3200" board="lisa_l_1.1"/>
<target name="test_adxl345" board="lisa_l_1.1"/>
<target name="test_esc_mkk_simple" board="lisa_l_1.1"/>
<target name="test_esc_asctecv1_simple" board="lisa_l_1.1"/>
<target name="test_actuators_mkk" board="lisa_l_1.1"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/>
</firmware>
SRC_FMS=fms
<firmware name="lisa_passthrough">
<target name="overo_test_passthrough" board="lisa_l_1.1" >
<param name="HOST" value="A7"/>
<param name="USER" value=""/>
<param name="TARGET_DIR" value="~"/>
<param name="PERIODIC_FREQ" value="512"/>
</target>
<target name="stm_passthrough" board="lisa_l_1.1">
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="imu" type="b2_v1.1"/>
</target>
</firmware>
ARCH=stm32
BOARD_CFG=\"boards/lisa_0.99.h\"
FLASH_MODE = JTAG
ap.CFLAGS += -DMODEM_BAUD=B57600
ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=\"subsystems/radio_control/spektrum_dx7se_joby.h\"
include $(PAPARAZZI_SRC)/conf/autopilot/booz2_common.makefile
include $(CFG_BOOZ)/booz2_autopilot.makefile
include $(CFG_BOOZ)/subsystems/booz2_radio_control_spektrum.makefile
include $(CFG_BOOZ)/subsystems/booz2_actuators_asctec_v2.makefile
include $(CFG_BOOZ)/subsystems/booz2_imu_b2v1_1.makefile
#include $(CFG_BOOZ)/subsystems/booz2_gps.makefile
include $(CFG_BOOZ)/subsystems/booz2_ahrs_cmpl.makefile
include $(PAPARAZZI_SRC)/conf/autopilot/lisa_test_progs.makefile
CONFIG_PASSTHROUGH = $(PAPARAZZI_SRC)/conf/autopilot/subsystems/lisa_passthrough
SERVOS_REFRESH_FREQ=200
include $(PAPARAZZI_SRC)/conf/autopilot/lisa_passthrough.makefile
RADIO_CONTROL_SPEKTRUM_MODEL=\"booz/radio_control/booz_radio_control_joby.h\"
include $(CONFIG_PASSTHROUGH)/radio_control_joby.makefile
</makefile>
</airframe>
@@ -0,0 +1,245 @@
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
<airframe name="lisa_asctec">
<servos min="0" neutral="0" max="0xff">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/>
<servo name="LEFT" no="2" min="0" neutral="0" max="255"/>
<servo name="RIGHT" no="3" min="0" neutral="0" max="255"/>
</servos>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<!-- for the sim -->
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="3"/>
<define name="MAX_MOTOR" value="200"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
<define name="TRIM_R" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="-227"/>
<define name="GYRO_Q_NEUTRAL" value="48"/>
<define name="GYRO_R_NEUTRAL" value="21"/>
<define name="GYRO_P_SENS" value="5.0" integer="16"/>
<define name="GYRO_Q_SENS" value="5.0" integer="16"/>
<define name="GYRO_R_SENS" value="5.0" integer="16"/>
<define name="GYRO_PQ_SENS" value="0.0" integer="16"/>
<define name="GYRO_PR_SENS" value="0.0" integer="16"/>
<define name="GYRO_QR_SENS" value="0.0" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="4"/>
<define name="ACCEL_Y_NEUTRAL" value="-14"/>
<define name="ACCEL_Z_NEUTRAL" value="-5"/>
<define name="ACCEL_X_SENS" value="39" integer="16"/>
<define name="ACCEL_Y_SENS" value="39" integer="16"/>
<define name="ACCEL_Z_SENS" value="39" integer="16"/>
<define name="ACCEL_XY_SENS" value="0.0" integer="16"/>
<define name="ACCEL_XZ_SENS" value="0.0" integer="16"/>
<define name="ACCEL_YZ_SENS" value="0.0" integer="16"/>
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="1." integer="16"/>
<define name="MAG_Y_SENS" value="1." integer="16"/>
<define name="MAG_Z_SENS" value="1." integer="16"/>
<define name="MAG_XY_SENS" value="0.0" integer="16"/>
<define name="MAG_XZ_SENS" value="0.0" integer="16"/>
<define name="MAG_YZ_SENS" value="0.0" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0. )"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg( 45. )"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_HOVER_Z_HOLD"/>
</section>
<section name="BAT">
<define name="MILLIAMP_PER_PERCENT" value="0.86"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="BATTERY_SENS" value="0.48" integer="16"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="GAIN_P" value="-400"/>
<define name="GAIN_Q" value="-400"/>
<define name="GAIN_R" value="-350"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="RadOfDeg(300.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="RadOfDeg(300.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="RadOfDeg(500)"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="RadOfDeg(180.)"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="-900"/>
<define name="PHI_DGAIN" value="-200"/>
<define name="PHI_IGAIN" value="-200"/>
<define name="THETA_PGAIN" value="-900"/>
<define name="THETA_DGAIN" value="-200"/>
<define name="THETA_IGAIN" value="-200"/>
<define name="PSI_PGAIN" value="-900"/>
<define name="PSI_DGAIN" value="-200"/>
<define name="PSI_IGAIN" value="-10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 200"/>
<define name="THETA_DDGAIN" value=" 200"/>
<define name="PSI_DDGAIN" value=" 200"/>
</section>
<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="10." integer="16"/>
</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.)"/>
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
<define name="MAX_SUM_ERR" value="2000000"/>
<define name="HOVER_KP" value="-500"/>
<define name="HOVER_KD" value="-200"/>
<define name="HOVER_KI" value="-100"/>
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
<define name="RC_CLIMB_COEF" value ="163"/>
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
<define name="INV_M" value ="0.2"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="-100"/>
<define name="DGAIN" value="-100"/>
<define name="IGAIN" value="-0"/>
</section>
<section name="MISC">
<define name="FACE_REINJ_1" value="1024"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="INITIAL_CONDITITONS" value="&quot;reset00&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<!-- -->
<modules main_freq="512">
<load name="vehicle_interface_overo_link.xml"/>
</modules>
<!-- -->
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<!-- <define name="BOOZ_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="actuators" type="asctec_v2"/>
<subsystem name="telemetry" type="transparent"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="imu" type="aspirin"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ahrs" type="cmpl"/>
</firmware>
<firmware name="lisa_l_test_progs">
<target name="test_led" board="lisa_l_1.1"/>
<target name="test_uart" board="lisa_l_1.1"/>
<target name="test_servos" board="lisa_l_1.1"/>
<target name="test_telemetry" board="lisa_l_1.1"/>
<target name="test_baro" board="lisa_l_1.1"/>
<target name="test_imu_b2" board="lisa_l_1.1"/>
<target name="test_imu_b2_2" board="lisa_l_1.1"/>
<target name="test_imu_aspirin" board="lisa_l_1.1"/>
<target name="test_rc_spektrum" board="lisa_l_1.1"/>
<target name="test_rc_ppm" board="lisa_l_1.1"/>
<target name="test_adc" board="lisa_l_1.1"/>
<target name="test_hmc5843" board="lisa_l_1.1"/>
<target name="test_itg3200" board="lisa_l_1.1"/>
<target name="test_adxl345" board="lisa_l_1.1"/>
<target name="test_esc_mkk_simple" board="lisa_l_1.1"/>
<target name="test_esc_asctecv1_simple" board="lisa_l_1.1"/>
<target name="test_actuators_mkk" board="lisa_l_1.1"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/>
</firmware>
<firmware name="lisa_passthrough">
<target name="overo_test_passthrough" board="lisa_l_1.1" >
<param name="HOST" value="A7"/>
<param name="USER" value=""/>
<param name="TARGET_DIR" value="~"/>
<param name="PERIODIC_FREQ" value="512"/>
</target>
<target name="stm_passthrough" board="lisa_l_1.1">
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="imu" type="b2_v1.1"/>
</target>
</firmware>
</airframe>
+10 -10
View File
@@ -34,7 +34,7 @@
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/>
@@ -52,7 +52,7 @@
<define name="IR_NB_SAMPLES" value="16"/>
<define name="GYRO_ROLL" value="ADC_3"/>
<define name="GYRO_NB_SAMPLES" value="16"/>
<define name="GYRO_NB_SAMPLES" value="16"/>
</section>
@@ -80,13 +80,13 @@
<section name="GYRO" prefix="GYRO_">
<define name="ADC_ROLL_NEUTRAL" value="520"/>
<define name="ADC_TEMP_NEUTRAL" value="476"/>
<define name="ADC_TEMP_SLOPE" value="0"/>
<define name="ADC_TEMP_NEUTRAL" value="476"/>
<define name="ADC_TEMP_SLOPE" value="0"/>
<define name="DYNAMIC_RANGE" value="300" unit="deg/s"/>
<define name="ADXRS300_RESISTOR_BRIDGE" value="(3.3/(3.3+1.8))"/>
<define name="ADXRS300_SENSITIVITY" value="5" unit="mV/(deg/s)"/>
<define name="ROLL_SCALE" value="3.3*1000./1024./(GYRO_ADXRS300_SENSITIVITY*GYRO_ADXRS300_RESISTOR_BRIDGE)" unit="deg/s/adc_unit"/>
<define name="ROLL_DIRECTION" value="-1."/>
<define name="ROLL_DIRECTION" value="-1."/>
</section>
<section name="BAT">
@@ -94,7 +94,7 @@
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="17." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
@@ -107,7 +107,7 @@
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
@@ -188,7 +188,7 @@
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
<section name="SIMU">
<define name="JSBSIM_MODEL" value="&quot;Malolo1&quot;"/>
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="RadOfDeg(0.)"/>
@@ -199,7 +199,7 @@
#### Config for SITL simulation
include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.CFLAGS += -DBOARD_CONFIG=\"tiny_sim.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
sim.CFLAGS += -DBOARD_CONFIG=\"boards/tiny_sim.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c
@@ -207,7 +207,7 @@ sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_re
SRC_FIRMWARE = firmwares/fixedwing
include $(PAPARAZZI_SRC)/conf/autopilot/sitl_jsbsim.makefile
jsbsim.CFLAGS += -DBOARD_CONFIG=\"tiny_sim.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
jsbsim.CFLAGS += -DBOARD_CONFIG=\"boards/tiny_sim.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
jsbsim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c
jsbsim.srcs += $(SIMDIR)/sim_ac_fw.c
+1 -1
View File
@@ -198,7 +198,7 @@
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART3"/>
Executable → Regular
View File
+1 -15
View File
@@ -33,27 +33,13 @@ endif
ifeq ($(TARGET),$(ACTUATOR_TARGET))
ifeq ($(ACTUATORS),)
ifeq ($(BOARD),tiny)
ifeq ($(BOARD_VERSION),1.1)
include $(CFG_SHARED)/actuators_4015.makefile
else
ifeq ($(BOARD_VERSION),0.99)
include $(CFG_SHARED)/actuators_4015.makefile
else
include $(CFG_SHARED)/actuators_4017.makefile
endif
endif
endif
ifeq ($(BOARD),twog)
include $(CFG_SHARED)/actuators_4017.makefile
endif
ifeq ($(BOARD),lisa_l)
include $(CFG_SHARED)/actuators_direct.makefile
endif
else
include $(CFG_FIXEDWING)/$(ACTUATORS).makefile
include $(CFG_SHARED)/$(ACTUATORS).makefile
endif
endif
+1 -1
View File
@@ -387,7 +387,7 @@ test_imu_b2_2.srcs += $(SRC_SUBSYSTEMS)/imu/imu_b2.c $(SRC_ARCH)/subsystems/imu/
test_imu_b2_2.srcs += peripherals/max1168.c $(SRC_ARCH)/peripherals/max1168_arch.c
test_imu_b2_2.CFLAGS += -DUSE_I2C2
test_imu_b2_2.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
test_imu_b2_2.srcs += peripherals/hmc5843.c $(SRC_BOOZ_ARCH)/peripherals/hmc5843_arch.c
test_imu_b2_2.srcs += peripherals/hmc5843.c $(SRC_ARCH)/peripherals/hmc5843_arch.c
test_imu_b2_2.CFLAGS += -DUSE_EXTI9_5_IRQ # Mag Int on PB5
+10 -22
View File
@@ -23,13 +23,6 @@
#
#
#
# Expected from board file or overriden as xml param :
#
# MODEM_PORT
# MODEM_BAUD
#
CFG_SHARED=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/shared
CFG_ROTORCRAFT=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/rotorcraft
@@ -79,12 +72,16 @@ ifeq ($(ARCH), stm32)
ap.srcs += $(SRC_ARCH)/led_hw.c
endif
# frequency of main periodic
ifndef PERIODIC_FREQUENCY
PERIODIC_FREQUENCY = 512
endif
$(TARGET).CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./$(PERIODIC_FREQUENCY).))' -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY)
#
# Systime
#
ap.CFLAGS += -DUSE_SYS_TIME
ap.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
ap.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))'
ifeq ($(ARCH), stm32)
ap.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED)
endif
@@ -92,21 +89,12 @@ endif
#
# Telemetry/Datalink
#
# include subsystems/rotorcraft/telemetry_transparent.makefile
# or
# include subsystems/rotorcraft/telemetry_xbee_api.makefile
#
ap.srcs += mcu_periph/uart.c
ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
ap.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport
ap.CFLAGS += -DDOWNLINK_DEVICE=$(MODEM_PORT)
ap.srcs += $(SRC_FIRMWARE)/telemetry.c
ap.srcs += downlink.c
ap.srcs += pprz_transport.c
ap.CFLAGS += -DDATALINK=PPRZ
ap.CFLAGS += -DPPRZ_UART=$(MODEM_PORT)
ap.srcs += $(SRC_FIRMWARE)/datalink.c
ap.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD)
ifeq ($(ARCH), lpc21)
ap.CFLAGS += -D$(MODEM_PORT)_VIC_SLOT=6
endif
ap.srcs += $(SRC_BOOZ)/booz2_commands.c
@@ -213,7 +201,7 @@ ap.srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodeti
# vertical filter float version
ap.srcs += $(SRC_SUBSYSTEMS)/ins/vf_float.c
ap.CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./512.)'
ap.CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./$(PERIODIC_FREQUENCY).)'
ap.srcs += $(SRC_FIRMWARE)/navigation.c
+2 -2
View File
@@ -23,7 +23,7 @@ tunnel.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c
# for the usb_tunnel we need to set PCLK higher with the flag USE_USB_HIGH_PCLK
# a configuration program to access both uart through usb
usb_tunnel_0.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200
usb_tunnel_0.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200 -DPERIPHERALS_AUTO_INIT
usb_tunnel_0.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -DUSE_USB_HIGH_PCLK
usb_tunnel_0.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c
usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c
@@ -31,7 +31,7 @@ usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdre
usb_tunnel_0.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c
usb_tunnel_0.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c
usb_tunnel_1.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B115200
usb_tunnel_1.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B115200 -DPERIPHERALS_AUTO_INIT
usb_tunnel_1.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -DUSE_USB_HIGH_PCLK
usb_tunnel_1.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c
usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c

Some files were not shown because too many files have changed in this diff Show More