Merge remote-tracking branch 'origin/master' into spi_driver

This commit is contained in:
Piotr Esden-Tempski
2012-10-26 18:07:43 -07:00
234 changed files with 6589 additions and 2639 deletions
+1 -1
View File
@@ -1,5 +1,5 @@
# ignore html dir for github pages # ignore html dir for github pages
/doc/html /doc/generated
*.so *.so
*.[oa] *.[oa]
+1 -4
View File
@@ -1,9 +1,6 @@
[submodule "sw/ext/libopencm3"] [submodule "sw/ext/libopencm3"]
path = sw/ext/libopencm3 path = sw/ext/libopencm3
url = git://libopencm3.git.sourceforge.net/gitroot/libopencm3/libopencm3 url = https://github.com/libopencm3/libopencm3.git
[submodule "sw/ext/stm32loader"]
path = sw/ext/stm32loader
url = https://github.com/jsnyder/stm32loader.git
[submodule "sw/ext/luftboot"] [submodule "sw/ext/luftboot"]
path = sw/ext/luftboot path = sw/ext/luftboot
url = https://github.com/paparazzi/luftboot.git url = https://github.com/paparazzi/luftboot.git
+2 -2
View File
@@ -51,7 +51,7 @@ PROJECT_LOGO = data/pictures/penguin_icon.png
# If a relative path is entered, it will be relative to the location # If a relative path is entered, it will be relative to the location
# where doxygen was started. If left blank the current directory will be used. # where doxygen was started. If left blank the current directory will be used.
OUTPUT_DIRECTORY = doc/html OUTPUT_DIRECTORY = doc/generated
# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create
# 4096 sub-directories (in 2 levels) under the output directory of each output # 4096 sub-directories (in 2 levels) under the output directory of each output
@@ -828,7 +828,7 @@ GENERATE_HTML = YES
# If a relative path is entered the value of OUTPUT_DIRECTORY will be # If a relative path is entered the value of OUTPUT_DIRECTORY will be
# put in front of it. If left blank `html' will be used as the default path. # put in front of it. If left blank `html' will be used as the default path.
HTML_OUTPUT = docs HTML_OUTPUT =
# The HTML_FILE_EXTENSION tag can be used to specify the file extension for # The HTML_FILE_EXTENSION tag can be used to specify the file extension for
# each generated HTML page (for example: .htm,.php,.asp). If it is left blank # each generated HTML page (for example: .htm,.php,.asp). If it is left blank
+1 -5
View File
@@ -210,10 +210,6 @@ upload_ms ms.upload: ms
##### #####
##### #####
doxygen:
mkdir -p dox
doxygen Doxyfile
run_sitl : run_sitl :
$(PAPARAZZI_HOME)/var/$(AIRCRAFT)/sim/simsitl $(PAPARAZZI_HOME)/var/$(AIRCRAFT)/sim/simsitl
@@ -282,4 +278,4 @@ run_tests:
test: all replace_current_conf_xml run_tests restore_conf_xml test: all replace_current_conf_xml run_tests restore_conf_xml
.PHONY: all print_build_version clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible doxygen run_sitl install uninstall test replace_current_conf_xml run_tests restore_conf_xml .PHONY: all print_build_version clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible run_sitl install uninstall test replace_current_conf_xml run_tests restore_conf_xml
+2 -2
View File
@@ -51,7 +51,7 @@ ifneq ($(BOARD_SERIAL),)
OOCD_OPTIONS = -c "ft2232_serial $(BOARD_SERIAL)" OOCD_OPTIONS = -c "ft2232_serial $(BOARD_SERIAL)"
endif endif
LOADER= $(PAPARAZZI_SRC)/sw/ext/stm32loader/stm32loader.py LOADER ?= $(PAPARAZZI_SRC)/sw/tools/stm32loader/stm32loader.py
ifndef $(TARGET).OOCD_INTERFACE ifndef $(TARGET).OOCD_INTERFACE
OOCD_INTERFACE = lisa-l OOCD_INTERFACE = lisa-l
@@ -130,7 +130,7 @@ AFLAGS += -mcpu=$(MCU) -mthumb
endif endif
AFLAGS += -x assembler-with-cpp -Wa,-adhlns=$(OBJDIR)/$(<:.S=.lst),--g$(DEBUG) AFLAGS += -x assembler-with-cpp -Wa,-adhlns=$(OBJDIR)/$(<:.S=.lst),--g$(DEBUG)
LDFLAGS = -L../ext/libopencm3/lib/stm32/f1 LDFLAGS = -L../ext/libopencm3/lib
ifeq ("$(MULTILIB)","yes") ifeq ("$(MULTILIB)","yes")
LDFLAGS += -T$(LDSCRIPT) -nostartfiles -O$(OPT) -mthumb -march=armv7 -mfix-cortex-m3-ldrd -msoft-float LDFLAGS += -T$(LDSCRIPT) -nostartfiles -O$(OPT) -mthumb -march=armv7 -mfix-cortex-m3-ldrd -msoft-float
else else
+308
View File
@@ -0,0 +1,308 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
Lisa + Aspirin v2 using SPI only
-->
<airframe name="LisaAspirin2">
<servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="1" min="1200" neutral="1500" max="1800"/>
<servo name="ELEVATOR" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
<servo name="AILEVON_RIGHT" no="4" min="1800" neutral="1500" max="1200"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="FORCECRASH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
<!-- <set command="FORCECRASH" value="@FLAPS"/> -->
</rc_commands>
<command_laws>
<set servo="AILEVON_LEFT" value="@ROLL"/>
<set servo="AILEVON_RIGHT" value="-@ROLL"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW"/>
</command_laws>
<!-- Local magnetic field -->
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value="0.85490967783446"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 939.650 LSB/rad/sec / 12bit FRAC: 4096 / 939.65 -->
<define name="GYRO_P_SENS" value="4.359" integer="16"/>
<define name="GYRO_Q_SENS" value="4.359" integer="16"/>
<define name="GYRO_R_SENS" value="4.359" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- SENS = 2048 LSB/g / 9.81 ms2/g = 208.766564729 LSB/ms2 / 10bit FRAC: 1024 / 208.7665 -->
<define name="ACCEL_X_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Y_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Z_SENS" value="9.81" 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="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="-0.0" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0.103000000119" unit="rad"/>
</section>
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0"/>
<define name="PITCH_TRIM" value="788."/>
</section>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.8"/>
<define name="MAX_PITCH" value="0.8"/>
</section>
<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"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0."/>
</section>
<section name="CATAPULT" prefix="NAV_CATAPULT_" >
<define name="MOTOR_DELAY" value="45" />
<define name="HEADING_DELAY" value="(60*3)" />
<define name="ACCELERATION_THRESHOLD" value="1.75" />
<define name="INITIAL_PITCH" value="(15.0/57.0)" />
<define name="INITIAL_THROTTLE" value="1.0" />
</section>
<section name="GLS_APPROACH" prefix="APP_" >
<define name="ANGLE" value="5" />
<define name="INTERCEPT_AF_TOD" value="10" />
<define name="TARGET_SPEED" value="13" />
</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.104999996722"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
<define name="ALTITUDE_PRE_CLIMB_CORRECTION" value="0.0960000008345"/>
<!--
<define name="AUTO_PITCH_PGAIN" value="-0.00"/>
<define name="AUTO_PITCH_IGAIN" value="-0.00"/>
-->
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.36700001359"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.626999974251"/>
<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.518000006676" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.00"/>
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.307000011206"/>
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.16600000858"/>
<define name="COURSE_DGAIN" value="0.324999988079"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.889999985695"/>
<define name="ROLL_MAX_SETPOINT" value="0.586000025272" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="PITCH_PGAIN" value="12587.4130859"/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1273.88500977"/>
<define name="ROLL_SLEW" value="1."/>
<define name="ROLL_ATTITUDE_GAIN" value="7972.02783203"/>
<define name="ROLL_RATE_GAIN" value="500."/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="70"/>
<define name="BLEND_END" value="60"/>
<define name="CLIMB_THROTTLE" value="0.949999988079"/>
<define name="CLIMB_PITCH" value="0.352999985218"/>
<define name="DESCENT_THROTTLE" value="0."/>
<define name="DESCENT_PITCH" value="-0.252000004053"/>
<define name="CLIMB_NAV_RATIO" value="0.8"/>
<define name="DESCENT_NAV_RATIO" value="1.0"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<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="gps_ubx_ucenter.xml"/>
<!--
<load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="0" />
<configure name="ADC_CHANNEL_GENERIC2" value="1" />
</load>
-->
<load name="light.xml">
<define name="LIGHT_LED_STROBE" value="2"/>
<define name="LIGHT_LED_NAV" value="3"/>
<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>
<load name="nav_catapult.xml"/>
</modules>
<firmware name="fixedwing">
<target name="ap" board="lisa_m_2.0">
<!-- this define is not available in paparazzi v4.1 -->
<!--define name="LISA_M_LONGITUDINAL_X"/-->
<configure name="SEPARATE_FBW" value="1"/>
<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="1"/>
<configure name="CPU_LED" value="1"/>
<define name="LINK_MCU_LED" value="4"/>
<!-- split of ap/fbw specific subsystems for ap -->
<subsystem name="actuators" type="dummy"/>
<subsystem name="intermcu" type="uart">
<configure name="INTERMCU_PORT_NR" value="5"/>
</subsystem>
<subsystem name="control"/>
<subsystem name="navigation" type="extra"/>
</target>
<target name="fbw" board="lisa_m_2.0">
<configure name="SYS_TIME_LED" value="2"/>
<define name="RADIO_CONTROL_LED" value="4"/>
<define name="LINK_MCU_LED" value="3"/>
<define name="OUTBACK_CHALLENGE_DANGEROUS_RULE_RC_LOST_NO_AP" value="1"/>
<define name="OUTBACK_CHALLENGE_VERY_DANGEROUS_RULE_AP_CAN_FORCE_FAILSAFE" value="1"/>
<subsystem name="radio_control" type="ppm"/>
<!-- split of ap/fbw specific subsystems for fbw -->
<subsystem name="actuators" type="pwm"/>
<subsystem name="intermcu" type="uart">
<configure name="INTERMCU_PORT_NR" value="2"/>
</subsystem>
</target>
<target name="sim" board="pc">
<subsystem name="radio_control" type="ppm"/>
<subsystem name="control"/>
<subsystem name="navigation" type="extra"/>
</target>
<configure name="FLASH_MODE" value="JTAG"/>
<configure name="NO_LUFTBOOT" value="1"/>
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="RADIO_CONTROL_AUTO1"/>
<!-- Communication -->
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_PORT" value="UART2"/>
</subsystem>
<!-- Sensors -->
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART1"/>
</subsystem>
<subsystem name="ahrs" type="float_dcm"/>
<subsystem name="ins" type="alt_float"/>
</firmware>
</airframe>
-248
View File
@@ -1,248 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
Lisa + Aspirin v2 using SPI only
-->
<airframe name="LisaAspirin2">
<servos>
<servo name="THROTTLE" no="2" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="1" min="1000" neutral="1500" max="2000"/>
<servo name="AILEVON_RIGHT" no="0" min="2000" neutral="1500" max="1000"/>
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="0"/> <!-- both elerons up as butterfly brake ? -->
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="BRAKE" value="@YAW"/>
</rc_commands>
<command_laws>
<set servo="AILEVON_LEFT" value="@ROLL + @PITCH"/>
<set servo="AILEVON_RIGHT" value="@ROLL - @PITCH"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
</command_laws>
<!-- Local magnetic field -->
<section name="AHRS" prefix="AHRS_" >
<define name="H_X" value="0.51562740288882" />
<define name="H_Y" value="-0.05707735220832" />
<define name="H_Z" value="0.85490967783446" />
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 939.650 LSB/rad/sec / 12bit FRAC: 4096 / 939.65 -->
<define name="GYRO_P_SENS" value="4.359" integer="16"/>
<define name="GYRO_Q_SENS" value="4.359" integer="16"/>
<define name="GYRO_R_SENS" value="4.359" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- SENS = 2048 LSB/g / 9.81 ms2/g = 208.766564729 LSB/ms2 / 10bit FRAC: 1024 / 208.7665 -->
<define name="ACCEL_X_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Y_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Z_SENS" value="9.81" 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="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</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="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.7"/>
<define name="MAX_PITCH" value="0.7"/>
</section>
<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"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="XBEE_INIT" value="&quot;ATPL2\rATRN5\rATTT80\r&quot;"/>
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="GLIDE_AIRSPEED" value="10"/>
<define name="GLIDE_VSPEED" value="3."/>
<define name="GLIDE_PITCH" value="45" unit="deg"/>
</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.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.20000004768"/>
<define name="COURSE_DGAIN" value="0.3"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
<define name="ROLL_MAX_SETPOINT" value="0.75" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="PITCH_PGAIN" value="-12000."/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1000."/>
<define name="ROLL_SLEW" value="1."/>
<define name="ROLL_ATTITUDE_GAIN" value="-7500"/>
<define name="ROLL_RATE_GAIN" value="0."/>
</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="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<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="2"/>
<define name="LIGHT_LED_NAV" value="3"/>
<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>
<firmware name="fixedwing">
<target name="ap" board="lisa_l_1.0">
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<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="1"/>
</target>
<target name="sim" board="pc"/>
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<!-- Sensors -->
<!--
<subsystem name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" />
</subsystem>
-->
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="ahrs" type="float_dcm">
<configure name="USE_MAGNETOMETER" value="0"/>
</subsystem>
<subsystem name="ins" type="alt_float"/>
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<!-- Actuators -->
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="navigation"/>
<subsystem name="gps" type="ublox"/>
</firmware>
</airframe>
+260
View File
@@ -0,0 +1,260 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="TwinStarXSens">
<servos driver="Ppm">
<servo name="THROTTLE_LEFT" no="1" min="1100" neutral="1100" max="1900"/>
<servo name="THROTTLE_RIGHT" no="0" min="1100" neutral="1100" max="1900"/>
<servo name="AILERON_RIGHT" no="2" min="2300" neutral="1550" max="700"/>
<servo name="AILERON_LEFT" no="3" min="2300" neutral="1550" max="700"/>
<servo name="ELEVATOR" no="4" min="1100" neutral="1500" max="1900"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="BRAKE" value="@YAW"/>
</rc_commands>
<section name="SERVO_MIXER_GAINS">
<define name="AILERON_RATE_UP" value="0.50f"/>
<define name="AILERON_RATE_DOWN" value="0.25f"/>
<define name="AILERON_RATE_UP_BRAKE" value="0.5f"/>
<define name="AILERON_RATE_DOWN_BRAKE" value="0.9f"/>
<define name="PITCH_GAIN" value="0.9f"/>
<define name="YAW_THRUST" value="0.0f"/>
<define name="BRAKE_AILEVON" value="-0.68f"/>
<define name="BRAKE_PITCH" value="0.0f"/>
<define name="MAX_BRAKE_RATE" value="130"/>
</section>
<command_laws>
<!-- Brake Rate Limiter -->
<let var="brake_value_nofilt" value="Chop(-@BRAKE, 0, MAX_PPRZ)"/>
<ratelimit var="brake_value" value="$brake_value_nofilt" rate_min="-MAX_BRAKE_RATE" rate_max="MAX_BRAKE_RATE" />
<!-- Differential Aileron Depending on Brake Value -->
<let var="aileron_up_rate" value="(AILERON_RATE_UP * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_UP_BRAKE * $brake_value)"/>
<let var="aileron_down_rate" value="(AILERON_RATE_DOWN * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_DOWN_BRAKE * $brake_value)"/>
<let var="aileron_up" value="((-@ROLL) * (((float)$aileron_up_rate) / ((float)MAX_PPRZ)))"/>
<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)"/>
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_AILEVON)"/>
<!-- Differential Thurst -->
<set servo="THROTTLE_LEFT" value="@THROTTLE - @ROLL * (YAW_THRUST)"/>
<set servo="THROTTLE_RIGHT" value="@THROTTLE + @ROLL * (YAW_THRUST)"/>
<!-- Pitch with Brake-Trim Function -->
<set servo="ELEVATOR" value="-@PITCH * PITCH_GAIN + BRAKE_PITCH * $brake_value"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.7"/>
<define name="MAX_PITCH" value="0.7"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0"/>
</section>
<!-- Local magnetic field -->
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value="0.85490967783446"/>
</section>
<section name="XSENS">
<define name="GPS_IMU_LEVER_ARM_X" value="0.0f"/>
<define name="GPS_IMU_LEVER_ARM_Y" value="0.0f"/>
<define name="GPS_IMU_LEVER_ARM_Z" value="0.0f"/>
</section>
<section name="ADC" prefix="ADC_CHANNEL_">
<define name="CURRENT" value="AdcBank1(5)"/>
</section>
<section name="BAT">
<define name="VoltageOfAdc(adc)" value="(0.01688000f*(adc)+2)"/>
<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"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.45" unit="%"/>
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.75"/>
<define name="COURSE_DGAIN" value="0.45"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.935"/>
<define name="ROLL_MAX_SETPOINT" value="0.8" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.4" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.275" unit="radians"/>
<define name="PITCH_PGAIN" value="11000"/>
<define name="PITCH_DGAIN" value="0."/>
<define name="ELEVATOR_OF_ROLL" value="1000."/>
<!-- roll rate loop -->
<define name="ROLL_ATTITUDE_GAIN" value="7000."/>
<define name="ROLL_RATE_GAIN" value="1100"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.1"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3.0"/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value=".38"/>
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.62"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000."/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1500"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0."/>
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.175"/>
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
</section>
<section name="NAV">
<define name="AGR_CLIMB_PITCH" value="0."/> <!-- Needed For OSAMNav -->
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="75."/>
<define name="GLIDE_AIRSPEED" value="10"/>
<define name="GLIDE_PITCH" value="45" unit="deg"/>
<define name="COMMAND_ROLL_TRIM" value="180"/>
<define name="COMMAND_PITCH_TRIM" value="-194."/>
</section>
<section name="DIGITAL_CAMERA" prefix="DC_">
<define name="AUTOSHOOT_QUARTERSEC_PERIOD" value="8" unit="quarter_second"/>
<define name="AUTOSHOOT_METER_GRID" value="50" unit="meter"/>
</section>
<firmware name="fixedwing">
<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\)"/>
<subsystem name="control"/>
<subsystem name="navigation" type="extra"/>
</target>
<target name="fbw" board="classix">
<configure name="SYS_TIME_LED" value="2"/>
<define name="RADIO_CONTROL_LED" value="1"/>
<define name="USE_AD1_5" value="1"/>
<define name="USE_AD1" value="1"/>
<configure name="ACTUATORS" value="actuators_ppm"/>
<define name="ADC_CHANNEL_VSUPPLY" value="AdcBank0\(6\)"/>
<subsystem name="radio_control" type="ppm"/>
</target>
<target name="sim" board="pc">
<subsystem name="radio_control" type="ppm"/>
<subsystem name="control"/>
<subsystem name="navigation" type="extra"/>
</target>
<define name="DC_IMAGE_BUFFER" value="65000" />
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="LOITER_TRIM"/>
<define name="RADIO_CONTROL_AUTO1"/>
<subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_PORT" value="UART0"/>
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>
<subsystem name="ins" type="xsens">
<configure name="XSENS_UART_NR" value="1"/>
</subsystem>
</firmware>
<modules>
<load name="digital_cam.xml">
<define name="DC_SHUTTER_LED" value="6"/>
</load>
<load name="adc_generic.xml">
<define name="ADC_GENERIC_NB_SAMPLES" value="32"/>
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_6"/> <!-- e.g. current sensor -->
</load>
<load name="photogrammetry_calculator.xml" />
</modules>
<!-- --------------------------------------------------------------------------- -->
<section name="Photogrammetry" prefix="PHOTOGRAMMETRY_">
<!-- Camera Parameters -->
<define name="FOCAL_LENGTH" value="20" unit="mm"/>
<define name="SENSOR_WIDTH" value="24" unit="mm"/>
<define name="SENSOR_HEIGHT" value="13.5" unit="mm"/>
<define name="PIXELS_WIDTH" value="1280" unit=""/>
<!-- Flight Safety Parameters -->
<define name="HEIGHT_MIN" value="40" unit="m"/>
<define name="HEIGHT_MAX" value="300" unit="m"/>
<define name="RADIUS_MIN" value="70" unit="m"/>
</section>
</airframe>
-276
View File
@@ -1,276 +0,0 @@
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
<airframe name="booz2_a7">
<servos>
<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="32858"/>
<define name="GYRO_Q_NEUTRAL" value="33152"/>
<define name="GYRO_R_NEUTRAL" value="31779"/>
<define name="GYRO_P_SENS" value=" 1.101357422" integer="16"/>
<define name="GYRO_Q_SENS" value=" 1.122670898" integer="16"/>
<define name="GYRO_R_SENS" value=" 1.104890137" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="32899"/>
<define name="ACCEL_Y_NEUTRAL" value="33281"/>
<define name="ACCEL_Z_NEUTRAL" value="32569"/>
<define name="ACCEL_X_SENS" value="2.57702956051" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.57835230627" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.54311399868" integer="16"/>
<define name="MAG_X_NEUTRAL" value="58"/>
<define name="MAG_Y_NEUTRAL" value="92"/>
<define name="MAG_Z_NEUTRAL" value="-3"/>
<define name="MAG_X_SENS" value="4.70018395734" integer="16"/>
<define name="MAG_Y_SENS" value="4.884119848" integer="16"/>
<define name="MAG_Z_SENS" value="2.59926404993" 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="135." unit="deg"/>
</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_ATTITUDE_Z_HOLD"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</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="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- gaui props
<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"/>
<define name="PHI_DDGAIN" value=" 200"/>
<define name="THETA_DDGAIN" value=" 200"/>
<define name="PSI_DDGAIN" value=" 200"/>
-->
<!-- feedback -->
<define name="PHI_PGAIN" value="2000"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="2000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="PSI_PGAIN" value="2000"/>
<define name="PSI_DGAIN" value="400"/>
<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"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="PROPAGATE_FREQUENCY" value="512"/>
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
</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="0"/>
-->
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="0"/>
<!-- 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="50"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="15"/>
<define name="NGAIN" 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="i2c_abuse_test.xml"/>
</modules>
<firmware name="rotorcraft">
<!-- <define name="USE_PERSISTENT_SETTINGS"/> -->
<!-- <define name="USE_INS_NAV_INIT"/> -->
<define name="FAILSAFE_GROUND_DETECT"/>
<define name="USE_GPS_ACC4R"/>
<target name="ap" board="lisa_l_1.0">
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="asctec"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<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_BAUD" value="B57600"/>
</subsystem>
<!--subsystem name="ahrs" type="int_cmpl_euler"/-->
<subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
<subsystem name="ins" type="hff"/>
</firmware>
<firmware name="lisa_test_progs">
<target name="test_led" board="lisa_l_1.0"/>
<target name="test_uart" board="lisa_l_1.0"/>
<target name="test_servos" board="lisa_l_1.0"/>
<target name="test_telemetry" board="lisa_l_1.0"/>
<target name="test_baro" board="lisa_l_1.0"/>
<target name="test_imu_b2" board="lisa_l_1.0"/>
<target name="test_imu_b2_2" board="lisa_l_1.0"/>
<target name="test_imu_aspirin" board="lisa_l_1.0"/>
<target name="test_rc_spektrum" board="lisa_l_1.0"/>
<target name="test_rc_ppm" board="lisa_l_1.0"/>
<target name="test_adc" board="lisa_l_1.0"/>
<target name="test_hmc5843" board="lisa_l_1.0"/>
<target name="test_itg3200" board="lisa_l_1.0"/>
<target name="test_adxl345" board="lisa_l_1.0"/>
<target name="test_esc_mkk_simple" board="lisa_l_1.0"/>
<target name="test_esc_asctecv1_simple" board="lisa_l_1.0"/>
<target name="test_actuators_mkk" board="lisa_l_1.0"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.0"/>
<target name="tunnel_sw" board="lisa_l_1.0"/>
<target name="tunnel_hw" board="lisa_l_1.0"/>
</firmware>
<firmware name="lisa_passthrough">
<target name="overo_test_passthrough" board="lisa_l_1.0" >
<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.0">
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="imu" type="b2_v1.1"/>
</target>
</firmware>
</airframe>
@@ -1,5 +1,6 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd"> <!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Yapa v1"> <airframe name="Yapa v1">
<servos> <servos>
@@ -81,15 +82,12 @@
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/> <define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="GLIDE_AIRSPEED" value="10"/>
<define name="GLIDE_VSPEED" value="3."/>
<define name="GLIDE_PITCH" value="45" unit="deg"/>
</section> </section>
<section name="VERTICAL CONTROL" prefix="V_CTL_"> <section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/> <define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain --> <!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="-0.03"/> <define name="ALTITUDE_PGAIN" value="0.03"/>
<!-- outer loop saturation --> <!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/> <define name="ALTITUDE_MAX_CLIMB" value="2."/>
@@ -100,7 +98,7 @@
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/> <define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/> <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_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="-0.01"/> <define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/> <define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/> <define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
@@ -108,21 +106,21 @@
</section> </section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_"> <section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="-1.20000004768"/> <define name="COURSE_PGAIN" value="1.20000004768"/>
<define name="COURSE_DGAIN" value="0.3"/> <define name="COURSE_DGAIN" value="0.3"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/> <define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
<define name="ROLL_MAX_SETPOINT" value="0.9" unit="radians"/> <define name="ROLL_MAX_SETPOINT" value="0.9" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/> <define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/> <define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="PITCH_PGAIN" value="-12000."/> <define name="PITCH_PGAIN" value="12000."/>
<define name="PITCH_DGAIN" value="0"/> <define name="PITCH_DGAIN" value="0"/>
<define name="ELEVATOR_OF_ROLL" value="1000."/> <define name="ELEVATOR_OF_ROLL" value="1000."/>
<define name="ROLL_ATTITUDE_GAIN" value="-11500"/> <define name="ROLL_ATTITUDE_GAIN" value="11500"/>
<define name="ROLL_RATE_GAIN" value="-600."/> <define name="ROLL_RATE_GAIN" value="600."/>
</section> </section>
<section name="AGGRESSIVE" prefix="AGR_"> <section name="AGGRESSIVE" prefix="AGR_">
@@ -1,13 +1,14 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd"> <!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Yapa v1"> <airframe name="Yapa v1">
<servos> <servos>
<servo name="THROTTLE" no="8" min="1000" neutral="1000" max="2000"/> <servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILERON_LEFT" no="9" min="1000" neutral="1500" max="2000"/> <servo name="AILERON_LEFT" no="1" min="1000" neutral="1500" max="2000"/>
<servo name="AILERON_RIGHT" no="4" min="2000" neutral="1500" max="1000"/> <servo name="AILERON_RIGHT" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="ELEVATOR" no="5" min="2000" neutral="1500" max="1000"/> <servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/> <servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
</servos> </servos>
<commands> <commands>
@@ -109,7 +110,7 @@
<define name="COURSE_DGAIN" value="0.3"/> <define name="COURSE_DGAIN" value="0.3"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/> <define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
<define name="ROLL_MAX_SETPOINT" value="0.75" unit="rad"/> <define name="ROLL_MAX_SETPOINT" value="0.9" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/> <define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/> <define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
@@ -222,7 +222,7 @@
<firmware name="fixedwing"> <firmware name="fixedwing">
<target name="ap" board="tiny_2.11"> <target name="ap" board="yapa_2.0">
<define name="STRONG_WIND"/> <define name="STRONG_WIND"/>
<define name="WIND_INFO"/> <define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/> <define name="WIND_INFO_RET"/>
@@ -1,95 +1,86 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd"> <!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- <!--
Tiny + XSens + XBee YAPA + XSens + XBee
--> -->
<airframe name="Yapa v1"> <airframe name="Yapa v1">
<servos> <servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/> <servo name="THROTTLE" no="0" min="1100" neutral="1000" max="1900"/>
<servo name="AILERON_LEFT" no="2" min="1000" neutral="1500" max="2000"/> <servo name="RUDDER" no="2" min="1100" neutral="1500" max="1900"/>
<servo name="AILERON_RIGHT" no="6" min="2000" neutral="1500" max="1000"/> <servo name="ELEVATOR" no="6" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/> <servo name="CAM_TILT" no="7" min="700" neutral="1600" max="2500"/>
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/> <servo name="CAM_PAN" no="3" min="800" neutral="1650" max="2500"/>
</servos> </servos>
<commands> <commands>
<axis name="THROTTLE" failsafe_value="0"/> <axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/> <axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/> <axis name="PITCH" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="0"/> <!-- both elerons up as butterfly brake ? --> <axis name="CAM_PAN" failsafe_value="0"/>
<axis name="CAM_TILT" failsafe_value="0"/>
</commands> </commands>
<ap_only_commands>
<copy command="CAM_PAN"/>
<copy command="CAM_TILT"/>
</ap_only_commands>
<rc_commands> <rc_commands>
<set command="THROTTLE" value="@THROTTLE"/> <set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/> <set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/> <set command="PITCH" value="@PITCH"/>
<set command="BRAKE" value="@YAW"/>
</rc_commands> </rc_commands>
<section name="SERVO_MIXER_GAINS">
<define name="AILERON_RATE_UP" value="0.50f"/>
<define name="AILERON_RATE_DOWN" value="0.25f"/>
<define name="AILERON_RATE_UP_BRAKE" value="0.5f"/>
<define name="AILERON_RATE_DOWN_BRAKE" value="0.9f"/>
<define name="PITCH_GAIN" value="0.9f"/>
<define name="YAW_THRUST" value="0.0f"/>
<define name="BRAKE_AILEVON" value="-0.68f"/>
<define name="BRAKE_PITCH" value="0.0f"/>
<define name="MAX_BRAKE_RATE" value="150"/>
</section>
<command_laws> <command_laws>
<!-- Brake Rate Limiter --> <set servo="CAM_PAN" value="@CAM_PAN"/>
<let var="brake_value_nofilt" value="Chop(-@BRAKE, 0, MAX_PPRZ)"/> <set servo="CAM_TILT" value="@CAM_TILT"/>
<ratelimit var="brake_value" value="$brake_value_nofilt" rate_min="-MAX_BRAKE_RATE" rate_max="MAX_BRAKE_RATE" />
<!-- Differential Aileron Depending on Brake Value --> <!-- Differential Aileron Depending on Brake Value -->
<let var="aileron_up_rate" value="(AILERON_RATE_UP * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_UP_BRAKE * $brake_value)"/> <set servo="RUDDER" value="@ROLL"/>
<let var="aileron_down_rate" value="(AILERON_RATE_DOWN * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_DOWN_BRAKE * $brake_value)"/>
<let var="aileron_up" value="(@ROLL * (((float)$aileron_up_rate) / ((float)MAX_PPRZ)))"/>
<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)"/>
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_AILEVON)"/>
<!-- Differential Thurst --> <!-- Differential Thurst -->
<set servo="THROTTLE" value="@THROTTLE"/> <set servo="THROTTLE" value="@THROTTLE"/>
<!-- Pitch with Brake-Trim Function --> <!-- Pitch with Brake-Trim Function -->
<set servo="ELEVATOR" value="-@PITCH * PITCH_GAIN + BRAKE_PITCH * $brake_value"/> <set servo="ELEVATOR" value="@PITCH"/>
</command_laws> </command_laws>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="rad"/>
</section>
<section name="AUTO1" prefix="AUTO1_"> <section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.7"/> <define name="MAX_ROLL" value="0.7"/>
<define name="MAX_PITCH" value="0.7"/> <define name="MAX_PITCH" value="0.7"/>
</section> </section>
<section name="BAT"> <section name="PANTILT" prefix="CAM_">
<define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/> <define name="PAN_MIN" value="-45"/>
<define name="PAN_NEUTRAL" value="33"/>
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/> <define name="PAN_MAX" value="156"/>
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/> <define name="PAN0" value="0"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/> <define name="TILT_MIN" value="-62"/>
<define name="TILT_NEUTRAL" value="47"/>
<define name="TILT_MAX" value="122"/>
<define name="TILT0" value="90"/>
<define name="MODE0" value="1"/>
</section> </section>
<section name="INS" prefix="INS_"> <section name="BAT">
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/> <define name="LOW_BAT_LEVEL" value="7" unit="V"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/> <define name="CRITIC_BAT_LEVEL" value="6.5" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/>
</section> </section>
<section name="MISC"> <section name="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/> <define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/> <define name="CARROT" value="5." unit="s"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/> <!-- <define name="XBEE_INIT" value="&quot;ATPL2\rATRN5\rATTT80\r&quot;"/>
<define name="XBEE_INIT" value="&quot;ATPL2\rATRN5\rATTT80\r&quot;"/> <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="TRUE"/> <define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/> <define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
@@ -102,7 +93,7 @@
<section name="VERTICAL CONTROL" prefix="V_CTL_"> <section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/> <define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain --> <!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="-0.03"/> <define name="ALTITUDE_PGAIN" value="0.03"/>
<!-- outer loop saturation --> <!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/> <define name="ALTITUDE_MAX_CLIMB" value="2."/>
@@ -113,7 +104,7 @@
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/> <define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/> <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_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="-0.01"/> <define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/> <define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/> <define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
@@ -121,23 +112,21 @@
</section> </section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_"> <section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="-1.20000004768"/> <define name="COURSE_PGAIN" value="1.20000004768"/>
<define name="COURSE_DGAIN" value="0.3"/> <define name="COURSE_DGAIN" value="0.3"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/> <define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
<define name="ROLL_MAX_SETPOINT" value="0.75" unit="radians"/> <define name="ROLL_MAX_SETPOINT" value="0.9" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/> <define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/> <define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="PITCH_PGAIN" value="-12000."/> <define name="PITCH_PGAIN" value="12000."/>
<define name="PITCH_DGAIN" value="1.5"/> <define name="PITCH_DGAIN" value="0"/>
<define name="ELEVATOR_OF_ROLL" value="1000."/> <define name="ELEVATOR_OF_ROLL" value="1000."/>
<define name="ROLL_SLEW" value="1."/> <define name="ROLL_ATTITUDE_GAIN" value="11500"/>
<define name="ROLL_RATE_GAIN" value="600."/>
<define name="ROLL_ATTITUDE_GAIN" value="-7500"/>
<define name="ROLL_RATE_GAIN" value="0."/>
</section> </section>
<section name="AGGRESSIVE" prefix="AGR_"> <section name="AGGRESSIVE" prefix="AGR_">
@@ -168,33 +157,44 @@
<modules> <modules>
<load name="i2c_abuse_test.xml"/> <load name="ins_chimu_spi.xml" >
<define name="CHIMU_BIG_ENDIAN" />
</load>
<load name="cam_point.xml" />
<load name="gps_ubx_ucenter.xml">
<define name="GPS_PORT_ID" value="GPS_PORT_UART2" />
</load>
</modules> </modules>
<firmware name="fixedwing"> <firmware name="fixedwing">
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="POINT_CAM_PITCH_ROLL" />
<target name="ap" board="tiny_2.11"> <target name="ap" board="tiny_2.11">
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="LOITER_TRIM"/>
</target> </target>
<target name="sim" board="pc"/> <!-- <target name="sim" board="pc"/> -->
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="gps" type="ublox" />
<!-- Communication --> <!-- Communication -->
<subsystem name="telemetry" type="xbee_api"> <subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B57600"/> <configure name="MODEM_BAUD" value="B9600"/>
</subsystem> </subsystem>
<!-- Actuators --> <!-- Actuators -->
<subsystem name="control"/> <subsystem name="control"/>
<!-- Sensors --> <!-- Sensors -->
<subsystem name="navigation"/> <subsystem name="navigation"/>
<subsystem name="ins" type="xsens">
<configure name="XSENS_UART_NR" value="0"/> <subsystem name="spi_slave_hs"/>
</subsystem>
</firmware> </firmware>
</airframe> </airframe>
+2 -2
View File
@@ -43,7 +43,7 @@
<define name="BRAKE_AILEVON" value="-0.7f"/> <define name="BRAKE_AILEVON" value="-0.7f"/>
<define name="BRAKE_PITCH" value="0.1f"/> <define name="BRAKE_PITCH" value="0.1f"/>
<define name="MAX_BRAKE_RATE" value="130"/> <define name="MAX_BRAKE_RATE" value="80"/>
<define name="RUDDER_OF_AILERON" value="0.3"/> <define name="RUDDER_OF_AILERON" value="0.3"/>
@@ -207,7 +207,7 @@
<firmware name="fixedwing"> <firmware name="fixedwing">
<target name="ap" board="tiny_2.11"/> <target name="ap" board="yapa_2.0"/>
<target name="sim" board="pc"/> <target name="sim" board="pc"/>
<define name="STRONG_WIND"/> <define name="STRONG_WIND"/>
@@ -0,0 +1,195 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!--
Eternity 1
designed by Murat Bronz
Umarim-Lite
Radiotronix modem
LEA 6H GPS
-->
<airframe name="Eternity 1">
<modules>
</modules>
<firmware name="fixedwing">
<target name="ap" board="umarim_lite_2.0"/>
<target name="sim" board="pc"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="AGR_CLIMB"/>
<define name="USE_I2C0"/>
<define name="USE_I2C1"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="umarim"/>
<subsystem name="ahrs" type="float_dcm">
<define name="USE_HIGH_ACCEL_FLAG"/>
</subsystem>
<subsystem name="ins" type="alt_float"/>
<subsystem name="control"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_0"/>
</subsystem>
</firmware>
<!-- commands section -->
<servos>
<servo name="MOTOR" no="5" min="1100" neutral="1100" max="1900"/>
<servo name="ELEVATOR" no="0" min="1200" neutral="1430" max="1800"/>
<servo name="RUDDER" no="1" min="1200" neutral="1619" max="2000"/>
<servo name="AILERON_RIGHT" no="3" max="1800" neutral="1521" min="1200"/>
<servo name="AILERON_LEFT" no="2" max="1800" neutral="1480" min="1200"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</rc_commands>
<section name="MIXER">
<define name="AILERON_DIFF" value="0.3"/>
</section>
<command_laws>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<let var="roll" value="@ROLL"/>
<set servo="AILERON_LEFT" value="($roll < 0 ? 1 : AILERON_DIFF) * $roll"/>
<set servo="AILERON_RIGHT" value="($roll < 0 ? AILERON_DIFF : 1) * $roll"/>
<set servo="RUDDER" value="@YAW"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="21"/>
<define name="GYRO_Q_NEUTRAL" value="21"/>
<define name="GYRO_R_NEUTRAL" value="5"/>
<define name="GYRO_P_SENS" value="5.072800" integer="16"/>
<define name="GYRO_Q_SENS" value="5.080519" integer="16"/>
<define name="GYRO_R_SENS" value="4.993218" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="-1"/>
<define name="ACCEL_Y_NEUTRAL" value="-6"/>
<define name="ACCEL_Z_NEUTRAL" value="-18"/>
<define name="ACCEL_X_SENS" value="38.8426913974" integer="16"/>
<define name="ACCEL_Y_SENS" value="38.743860704" integer="16"/>
<define name="ACCEL_Z_SENS" value="39.5046247859" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0.0959929972887" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="rad"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-156)*18.2"/>
</section>
<section name="MISC">
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="19." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
</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.06"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1200"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.116999998689" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.0109999999404"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.119000002742"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.082999996841"/>
<!-- auto pitch inner loop -->
<!--define name="AUTO_PITCH_PGAIN" value="-0.06"/>
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/-->
<define name="THROTTLE_SLEW" value="0.1"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.878000020981"/>
<define name="ROLL_MAX_SETPOINT" value="0.60" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="ROLL_ATTITUDE_GAIN" value="11359.2226562"/>
<define name="ROLL_RATE_GAIN" value="2000."/>
<define name="PITCH_PGAIN" value="9587.37890625"/>
<define name="PITCH_DGAIN" value="0.4"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<define name="ELEVATOR_OF_ROLL" value="1500"/>
</section>
<section name="NAV">
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.35"/><!-- 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.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
</airframe>
+4 -2
View File
@@ -9,7 +9,6 @@
<modules> <modules>
<load name="poles.xml"/> <load name="poles.xml"/>
<load name="baro_board.xml"/>
</modules> </modules>
<firmware name="fixedwing"> <firmware name="fixedwing">
@@ -36,7 +35,9 @@
<subsystem name="ahrs" type="float_dcm"> <subsystem name="ahrs" type="float_dcm">
<define name="USE_HIGH_ACCEL_FLAG"/> <define name="USE_HIGH_ACCEL_FLAG"/>
</subsystem> </subsystem>
<subsystem name="ins" type="alt_float"/> <subsystem name="ins" type="alt_float">
<!--define name="USE_BAROMETER"/-->
</subsystem>
<subsystem name="control" type="adaptive"/> <subsystem name="control" type="adaptive"/>
<subsystem name="navigation"/> <subsystem name="navigation"/>
<!-- Sensors --> <!-- Sensors -->
@@ -125,6 +126,7 @@
<section name="INS" prefix="INS_"> <section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="-0.0640000030398" unit="rad"/> <define name="ROLL_NEUTRAL_DEFAULT" value="-0.0640000030398" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0.0670000016689" unit="rad"/> <define name="PITCH_NEUTRAL_DEFAULT" value="0.0670000016689" unit="rad"/>
<define name="BARO_SENS" value="1.0"/> <!-- TODO calibration -->
</section> </section>
<section name="BAT"> <section name="BAT">
+227
View File
@@ -0,0 +1,227 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Funjet Multiplex (http://www.multiplex-rc.de/)
Umarim Lite
Radiotronix modem
UBX GPS
Airspeed sensor
Digital camera
-->
<airframe name="Funjet II">
<modules>
<!--load name="light.xml">
<define name="LIGHT_LED_STROBE" value="5"/>
<define name="LIGHT_LED_NAV" value="3"/>
</load-->
<!--load name="baro_board.xml">
<define name="BARO_ABS_EVENT" value="BaroPbnUpdate"/>
</load-->
<load name="pbn.xml"/>
</modules>
<firmware name="fixedwing">
<define name="USE_I2C0"/>
<define name="USE_I2C1"/>
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<define name="LOITER_TRIM"/>
<define name="USE_AIRSPEED"/>
<target name="sim" board="pc"/>
<target name="ap" board="umarim_lite_2.0"/>
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="transparent"/>
<!-- Actuators are automatically chosen according to board-->
<subsystem name="imu" type="umarim"/>
<subsystem name="ahrs" type="float_dcm">
<define name="USE_HIGH_ACCEL_FLAG"/>
</subsystem>
<subsystem name="ins" type="alt_float"/>
<subsystem name="control" type="new">
<define name="USE_GYRO_PITCH_RATE"/>
</subsystem>
<!-- Sensors -->
<subsystem name="gps" type="ublox"/>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_0"/>
</subsystem>
<subsystem name="navigation"/>
</firmware>
<servos>
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1500" max="1050"/>
<servo name="AILEVON_RIGHT" no="1" min="1120" neutral="1540" max="1980"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_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"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="5"/>
<define name="GYRO_Q_NEUTRAL" value="17"/>
<define name="GYRO_R_NEUTRAL" value="-5 "/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="ACCEL_X_NEUTRAL" value="6"/>
<define name="ACCEL_Y_NEUTRAL" value="-3"/>
<define name="ACCEL_Z_NEUTRAL" value="-8"/>
<define name="ACCEL_X_SENS" value="38.273044006" integer="16"/>
<define name="ACCEL_Y_SENS" value="39.3799642589" integer="16"/>
<define name="ACCEL_Z_SENS" value="39.6142126316" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="8." unit="deg"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-100)*26.9"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.1"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="4."/>
<!-- disable climb rate limiter -->
<define name="AUTO_CLIMB_LIMIT" value="2*V_CTL_ALTITUDE_MAX_CLIMB"/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<!--define name="AUTO_THROTTLE_LOITER_TRIM" value="1000"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000"/-->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.005"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.003"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.02"/>
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="0.03"/>
<define name="AUTO_PITCH_DGAIN" value="0.03"/>
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
<!--define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/-->
<define name="AUTO_PITCH_MAX_PITCH" value="20" unit="deg"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-20" unit="deg"/>
<!-- airspeed control -->
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.1"/>
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.12"/>
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
<define name="AIRSPEED_MAX" value="30"/>
<define name="AIRSPEED_MIN" value="10"/>
<!-- groundspeed control -->
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
<!-- pitch trim -->
<define name="PITCH_LOITER_TRIM" value="0." unit="deg"/>
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/>
<define name="THROTTLE_SLEW" value="0.1"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.6"/>
<define name="ROLL_MAX_SETPOINT" value="0.8" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="ROLL_ATTITUDE_GAIN" value="9000."/>
<define name="ROLL_RATE_GAIN" value="1000."/>
<define name="ROLL_IGAIN" value="150."/>
<define name="PITCH_PGAIN" value="18000."/>
<define name="PITCH_DGAIN" value="500"/>
<define name="PITCH_IGAIN" value="250."/>
<define name="PITCH_OF_ROLL" value="1." unit="deg"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<!--define name="ELEVATOR_OF_ROLL" value="1400"/-->
</section>
<section name="NAV">
<define name="NAV_GLIDE_PITCH_TRIM" value="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"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
<section name="SIMU">
<define name="YAW_RESPONSE_FACTOR" value="0.6"/>
</section>
</airframe>
+200
View File
@@ -0,0 +1,200 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Merlin
Tiny 2.11
Tilted infrared sensor
XBee modem
LEA 5H
-->
<airframe name="Merlin">
<firmware name="fixedwing">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<target name="ap" board="tiny_2.11"/>
<target name="sim" board="pc"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="control"/>
<subsystem name="ahrs" type="infrared"/>
<subsystem name="ins" type="alt_float"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="tiny_2.11" />
<target name="setup_actuators" board="tiny_2.11" />
</firmware>
<modules>
<load name="infrared_adc.xml"/>
</modules>
<!-- commands section -->
<servos>
<servo name="AILERON_RIGHT" no="0" min="1900" neutral="1500" max="1100"/>
<servo name="AILERON_LEFT" no="2" min="1900" neutral="1500" max="1100"/>
<servo name="ELEVATOR" no="6" min="1100" neutral="1500" max="1900"/>
<servo name="RUDDER" no="7" min="1100" neutral="1500" max="1900"/>
<servo name="MOTOR" no="3" min="1000" neutral="1000" max="2000"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</rc_commands>
<section name="MIXER">
<define name="AILERON_DIFF" value="0.8"/>
</section>
<command_laws>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW"/>
<let var="roll" value="@ROLL"/>
<set servo="AILERON_LEFT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll"/>
<set servo="AILERON_RIGHT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="INFRARED" prefix="IR_">
<define name="ADC_IR1_NEUTRAL" value="512"/>
<define name="ADC_IR2_NEUTRAL" value="512"/>
<define name="ADC_TOP_NEUTRAL" value="512"/>
<define name="LATERAL_CORRECTION" value="1"/>
<define name="LONGITUDINAL_CORRECTION" value="1"/>
<define name="VERTICAL_CORRECTION" value="1"/>
<define name="HORIZ_SENSOR_TILTED" value="1"/>
<define name="IR1_SIGN" value="1"/>
<define name="IR2_SIGN" value="1"/>
<define name="TOP_SIGN" value="1"/>
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<!-- 0.0247311828 -->
<!-- 0.02432905 -->
<define name="VoltageOfAdc(adc)" value="(0.02454*adc)"/>
</section>
<section name="MISC">
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="18." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<!-- <define name="XBEE_INIT" value="&quot;ATPL2\rATRN1\rATTT80\r&quot;"/> -->
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="FALSE"/>
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
</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.06"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1200"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.023"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="0.06"/>
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
<define name="AUTO_PITCH_DGAIN" value="0.0"/>
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
<!-- pitch trim -->
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>
<define name="THROTTLE_SLEW" value="0.1"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.0"/>
<define name="ROLL_MAX_SETPOINT" value="0.60" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="ROLL_ATTITUDE_GAIN" value="5900"/>
<define name="ROLL_RATE_GAIN" value="2900"/>
<define name="ROLL_IGAIN" value="500"/>
<define name="ROLL_KFFA" value="500"/>
<define name="ROLL_KFFD" value="500"/>
<define name="PITCH_PGAIN" value="9000."/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="PITCH_IGAIN" value="500"/>
<define name="PITCH_KFFA" value="0."/>
<define name="PITCH_KFFD" value="0."/>
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.2)"/>
<define name="ELEVATOR_OF_ROLL" value="0"/>
</section>
<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.35"/><!-- 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.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
</airframe>
+265
View File
@@ -0,0 +1,265 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Mythe
Umarim
XBee modem
LEA 5H GPS
-->
<airframe name="Funjet">
<modules>
<!--load name="baro_board.xml"/-->
<load name="airspeed_adc.xml">
<configure name="ADC_AIRSPEED" value="ADC_0"/>
<define name="AIRSPEED_QUADRATIC_SCALE" value="1.09378"/>
<define name="AIRSPEED_BIAS" value="110"/>
</load>
<!--load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_2"/>
</load-->
<!--load name="baro_hca.xml">
<define name="I2C0_SCLL" value="25"/>
<define name="I2C0_SCLH" value="25"/>
</load-->
<load name="baro_bmp.xml">
<define name="BMP_I2C_DEV" value="i2c1"/>
</load>
<load name="baro_ms5611_i2c.xml">
<define name="MS5611_I2C_DEV" value="i2c0"/>
</load>
<!-- load name="airspeed_ads1114.xml"/-->
<!--load name="mcp355x.xml"/-->
<!--load name="sys_mon.xml"/-->
</modules>
<firmware name="fixedwing">
<define name="USE_I2C0"/>
<define name="USE_I2C1"/>
<!--define name="AGR_CLIMB"/-->
<define name="ALT_KALMAN"/>
<define name="USE_AIRSPEED"/>
<!--define name="LOITER_TRIM"/-->
<!--define name="PITCH_TRIM"/-->
<define name="USE_GYRO_PITCH_RATE"/>
<define name="SENSOR_SYNC_SEND"/>
<target name="sim" board="pc"/>
<target name="ap" board="umarim_1.0"/>
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api"/>
<!-- Actuators are automatically chosen according to board-->
<subsystem name="imu" type="umarim"/>
<subsystem name="ahrs" type="float_dcm">
<define name="USE_HIGH_ACCEL_FLAG"/>
</subsystem>
<subsystem name="ins" type="alt_float"/>
<subsystem name="control" type="new"/>
<subsystem name="navigation"/>
<!-- Sensors -->
<subsystem name="gps" type="ublox"/>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_1"/>
</subsystem>
<!--subsystem name="spi"/-->
</firmware>
<!-- commands section -->
<servos>
<servo name="MOTOR" no="7" min="1040" neutral="1040" max="2000"/>
<servo name="AILEVON_LEFT" no="6" min="1900" neutral="1543" max="1100"/>
<servo name="AILEVON_RIGHT" no="3" min="1100" neutral="1561" max="1900"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_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"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_SIGN" value="-1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="1"/>
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="-83"/>
<define name="GYRO_Q_NEUTRAL" value="81"/>
<define name="GYRO_R_NEUTRAL" value="77 "/>
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
<define name="GYRO_R_SENS" value="4.97312" 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_X_NEUTRAL" value="1"/>
<define name="ACCEL_Y_NEUTRAL" value="6"/>
<define name="ACCEL_Z_NEUTRAL" value="-18"/>
<define name="ACCEL_X_SENS" value="38.2761110243" integer="16"/>
<define name="ACCEL_Y_SENS" value="38.9101161196" integer="16"/>
<define name="ACCEL_Z_SENS" value="39.8204157329" integer="16"/>
<!-- Just to compile -->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0.144" unit="rad"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-158)*16.5698"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
</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.18"/> <!-- 0.024 -->
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="5."/>
<!-- Cruise throttle + limits -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(20.)"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-RadOfDeg(20.)"/>
<!-- Climb loop (throttle) -->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.002"/> <!-- 0.005 -->
<define name="AUTO_THROTTLE_DGAIN" value="0.0"/> <!-- 0.005 -->
<define name="AUTO_THROTTLE_IGAIN" value="0.004"/> <!-- 0.005 -->
<!-- Climb loop (pitch) -->
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.03"/>
<define name="AUTO_PITCH_PGAIN" value="0.04"/> <!-- 0.03 -->
<define name="AUTO_PITCH_DGAIN" value="0.04"/> <!-- 0.03 -->
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
<!-- airspeed control -->
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.1"/>
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.12"/>
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
<define name="AIRSPEED_MAX" value="30"/>
<define name="AIRSPEED_MIN" value="10"/>
<!-- groundspeed control -->
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
<!-- pitch trim --> <!-- 5 deg -->
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(0.)"/>
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-0.)"/>
<define name="THROTTLE_SLEW" value="0.1"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.7"/>
<define name="ROLL_MAX_SETPOINT" value="0.8" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="ROLL_ATTITUDE_GAIN" value="8800."/>
<define name="ROLL_RATE_GAIN" value="500."/>
<define name="ROLL_IGAIN" value="150."/>
<define name="ROLL_KFFA" value="0"/>
<define name="ROLL_KFFD" value="0"/>
<define name="PITCH_PGAIN" value="14000."/>
<define name="PITCH_DGAIN" value="0."/>
<define name="PITCH_IGAIN" value="250."/>
<define name="PITCH_KFFA" value="0."/>
<define name="PITCH_KFFD" value="0."/>
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.0)"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<!--define name="ELEVATOR_OF_ROLL" value="1400"/-->
</section>
<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="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"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
<section name="SIMU">
<!--define name="ROLL_RESPONSE_FACTOR" value="10"/>
<define name="MAX_ROLL_DOT" value="20" unit="rad/s"/-->
<define name="JSBSIM_MODEL" value="&quot;Malolo1&quot;"/>
<!--define name="JSBSIM_INIT" value="&quot;Malolo1-IC&quot;"/-->
<define name="JSBSIM_LAUNCHSPEED" value="15.0"/>
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="RadOfDeg(0.)"/>
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="RadOfDeg(0.)"/>
</section>
</airframe>
+219
View File
@@ -0,0 +1,219 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Twinjet Multiplex (http://www.multiplex-rc.de/)
Tiny 2.12 board (http://paparazzi.enac.fr/wiki/index.php/Tiny_v2)
Tilted infrared sensor
-->
<airframe name="Twinjet 2 Tiny 2.12">
<modules>
<!--load name="adp_roll.xml"/-->
<!--load name="ins_vn100.xml"/-->
<!--load name="ets_module_sensors.xml"/-->
<!--load name="infrared_i2c.xml"/-->
<!--load name="max3100.xml"/>
<load name="gsm.xml"/-->
<!--load name="demo_module.xml">
<define name="TEST" value="1"/>
<define name="TEST_FLAG"/>
</load-->
<!--load name="enose.xml"/-->
<load name="light.xml"/>
<load name="infrared_adc.xml"/>
</modules>
<firmware name="fixedwing">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="USE_I2C0"/>
<target name="ap" board="tiny_2.11"/>
<target name="sim" board="pc"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="xbee_api"/>
<subsystem name="control" type="adaptive"/>
<subsystem name="ahrs" type="infrared"/>
<subsystem name="ins" type="alt_float"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="tiny_2.11" />
<target name="setup_actuators" board="tiny_2.11" />
</firmware>
<!-- commands section -->
<servos>
<servo name="MOTOR_LEFT" no="3" min="1000" neutral="1000" max="2000"/>
<servo name="MOTOR_RIGHT" no="4" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="6" min="1900" neutral="1515" max="1100"/>
<servo name="AILEVON_RIGHT" no="7" min="1100" neutral="1500" max="1900"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
<define name="MOTOR_YAW_RATE" value="0.0"/>
</section>
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<let var="yaw" value="@YAW * MOTOR_YAW_RATE"/>
<set servo="MOTOR_LEFT" value="@THROTTLE - $yaw"/>
<set servo="MOTOR_RIGHT" value="@THROTTLE + $yaw"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="INFRARED" prefix="IR_">
<define name="ADC_IR1_NEUTRAL" value="512"/>
<define name="ADC_IR2_NEUTRAL" value="512"/>
<define name="ADC_TOP_NEUTRAL" value="512"/>
<define name="LATERAL_CORRECTION" value="1."/>
<define name="LONGITUDINAL_CORRECTION" value="1."/>
<define name="VERTICAL_CORRECTION" value="1.25"/>
<define name="HORIZ_SENSOR_TILTED" value="1"/>
<define name="IR1_SIGN" value="-1"/>
<define name="IR2_SIGN" value="1"/>
<define name="TOP_SIGN" value="1"/>
<define name="ROLL_NEUTRAL_DEFAULT" value="-1.146" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0.15" unit="deg"/>
<define name="I2C_DEFAULT_CONF" value="1"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8600"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</section>
<section name="MISC">
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="20." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<!-- <define name="XBEE_INIT" value="&quot;ATPL2\rATRN1\rATTT80\r&quot;"/> -->
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="LIGHT_LED_1" value="3"/>
<define name="LIGHT_LED_2" value="5"/>
</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.0450000017881"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.319999992847"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.80"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.035000000149"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.01"/>
<define name="AUTO_THROTTLE_DGAIN" value="0"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.12"/>
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="0.035000000149"/>
<define name="AUTO_PITCH_IGAIN" value="0.01"/>
<define name="AUTO_PITCH_DGAIN" value="0"/>
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
<define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.15"/>
<!-- pitch trim -->
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>
<define name="THROTTLE_SLEW" value="0.3"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.995000004768"/>
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="ROLL_ATTITUDE_GAIN" value="3553.89208984"/>
<define name="ROLL_RATE_GAIN" value="0."/>
<define name="ROLL_IGAIN" value="500"/>
<define name="ROLL_KFFA" value="500"/>
<define name="ROLL_KFFD" value="500"/>
<define name="PITCH_PGAIN" value="14522.4716797"/>
<define name="PITCH_DGAIN" value="0."/>
<define name="PITCH_IGAIN" value="500"/>
<define name="PITCH_KFFA" value="0."/>
<define name="PITCH_KFFD" value="0."/>
<!--define name="ELEVATOR_OF_ROLL" value="1541."/-->
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.2)"/>
</section>
<section name="NAV">
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
<define name="NAV_CROSS_TRACK_ERROR_IGAIN" value="0."/>
<define name="NAV_CROSS_TRACK_ERROR_MAX" value="10." unit="deg"/>
</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="0.7"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.25"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.15"/><!-- 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="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"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
<section name="SIMU">
<define name="YAW_RESPONSE_FACTOR" value="1."/>
</section>
</airframe>
+5 -5
View File
@@ -6,11 +6,10 @@
LEA 5H GPS LEA 5H GPS
--> -->
<airframe name="Funjet"> <airframe name="Weasel">
<modules> <modules>
<load name="baro_board.xml"/> <!--load name="airspeed_ads1114.xml"/-->
<load name="airspeed_ads1114.xml"/>
<!--load name="mcp355x.xml"/--> <!--load name="mcp355x.xml"/-->
</modules> </modules>
@@ -18,7 +17,9 @@
<define name="USE_I2C0"/> <define name="USE_I2C0"/>
<define name="USE_I2C1"/> <define name="USE_I2C1"/>
<!--define name="AGR_CLIMB"/--> <!--define name="AGR_CLIMB"/-->
<define name="ALT_KALMAN"/>
<define name="USE_AIRSPEED"/> <define name="USE_AIRSPEED"/>
<!--define name="USE_BAROMETER"/-->
<!--define name="LOITER_TRIM"/--> <!--define name="LOITER_TRIM"/-->
<!--define name="PITCH_TRIM"/--> <!--define name="PITCH_TRIM"/-->
@@ -49,7 +50,6 @@
<firmware name="setup"> <firmware name="setup">
<target name="setup_actuators" board="umarim_1.0"/> <target name="setup_actuators" board="umarim_1.0"/>
<target name="tunnel" board="umarim_1.0"/>
</firmware> </firmware>
<!-- commands section --> <!-- commands section -->
@@ -122,6 +122,7 @@
<section name="INS" prefix="INS_"> <section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0.048" unit="rad"/> <define name="ROLL_NEUTRAL_DEFAULT" value="0.048" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="rad"/> <define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="rad"/>
<define name="BARO_SENS" value="1.0"/> <!-- TODO calibration -->
</section> </section>
<section name="BAT"> <section name="BAT">
@@ -133,7 +134,6 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/> <define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/> <define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/> <define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/> <define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/> <define name="TRIGGER_DELAY" value="1."/>
+45 -45
View File
@@ -1,12 +1,11 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<airframe name="Blender"> <airframe name="Blender">
<modules main_freq="512"> <modules main_freq="512">
<load name="booz_pwm.xml"> <load name="servo_switch.xml"/>
<define name="USE_PWM0"/> <load name="rotorcraft_cam.xml"/>
</load> <!--load name="sonar_maxbotix_booz.xml"/-->
<load name="booz_drop.xml"/>
<load name="booz_cam.xml"/>
<load name="sonar_maxbotix_booz.xml"/>
<!--load name="adc_generic.xml"> <!--load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_0"/> <configure name="ADC_CHANNEL_GENERIC1" value="ADC_0"/>
</load--> </load-->
@@ -30,21 +29,40 @@
<subsystem name="actuators" type="skiron"> <subsystem name="actuators" type="skiron">
<define name="SKIRON_I2C_SCL_TIME" value="25"/> <define name="SKIRON_I2C_SCL_TIME" value="25"/>
</subsystem> </subsystem>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="USE_PWM0"/>
</subsystem>
<subsystem name="imu" type="navgo"/> <subsystem name="imu" type="navgo"/>
<subsystem name="gps" type="ublox"> <subsystem name="gps" type="ublox">
<configure name="GPS_BAUD" value="B57600"/> <configure name="GPS_BAUD" value="B57600"/>
</subsystem> </subsystem>
<subsystem name="stabilization" type="euler"/> <subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_quat"/> <subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins" type="extended"/>
<subsystem name="ins" type="hff"/> <subsystem name="ins" type="hff"/>
</firmware> </firmware>
<servos> <section name="MIXING" prefix="MOTOR_MIXING_">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/> <define name="TRIM_ROLL" value="-50"/>
<servo name="BACK" no="2" min="0" neutral="0" max="255"/> <define name="TRIM_PITCH" value="-150"/>
<servo name="RIGHT" no="1" min="0" neutral="0" max="255"/> <define name="TRIM_YAW" value="-100"/>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/> <define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, -256, 0, 256}"/>
<define name="PITCH_COEF" value="{ 256, 0, -256, 0}"/>
<define name="YAW_COEF" value="{ -256, 256, -256, 256}"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
</section>
<servos driver="Skiron">
<servo name="FRONT" no="0" min="0" neutral="20" max="255"/>
<servo name="RIGHT" no="1" min="0" neutral="20" max="255"/>
<servo name="BACK" no="2" min="0" neutral="20" max="255"/>
<servo name="LEFT" no="3" min="0" neutral="20" max="255"/>
</servos>
<servos driver="Pwm">
<servo name="DROP" no="0" min="1000" neutral="1500" max="2000"/>
</servos> </servos>
<commands> <commands>
@@ -54,24 +72,13 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="ACTUATORS_SKIRON" prefix="ACTUATORS_SKIRON_"> <command_laws>
<define name="NB" value="4"/> <call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<define name="IDX" value="{ SERVO_FRONT, SERVO_BACK, SERVO_RIGHT, SERVO_LEFT }"/> <set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
</section> <set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<section name="SUPERVISION" prefix="SUPERVISION_"> <set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
<define name="MIN_MOTOR" value="20"/> </command_laws>
<define name="MAX_MOTOR" value="255"/>
<define name="TRIM_A" value="-50"/>
<define name="TRIM_E" value="-150"/>
<define name="TRIM_R" value="-100"/>
<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_"> <section name="IMU" prefix="IMU_">
@@ -250,25 +257,18 @@
<define name="BOOZ_FMS_TIMEOUT" value="0"/> <define name="BOOZ_FMS_TIMEOUT" value="0"/>
</section> </section>
<section name="CAM" prefix="BOOZ_CAM_"> <section name="CAM" prefix="ROTORCRAFT_CAM_">
<!--define name="TILT_NEUTRAL" value="1500"/> <define name="DEFAULT_MODE" value="ROTORCRAFT_CAM_MODE_MANUAL"/>
<define name="TILT_MIN" value="1060"/>
<define name="TILT_MAX" value="2250"/>
<define name="TILT_ANGLE_MIN" value="-90." unit="deg"/>
<define name="TILT_ANGLE_MAX" value=" 0." unit="deg"/-->
<define name="PAN_NEUTRAL" value="0"/>
<define name="PAN_MIN" value="0"/>
<define name="PAN_MAX" value="25736"/> <!-- 360 deg (2^12) -->
<define name="DEFAULT_MODE" value="BOOZ_CAM_MODE_MANUAL"/>
<define name="ON" value="{}"/> <define name="ON" value="{}"/>
<define name="OFF" value="{}"/> <define name="OFF" value="{}"/>
<!--define name="SetPwm(_v)" value="Booz2SetPwm1Value(_v)"/-->
</section> </section>
<section name="DROP"> <section name="SERVO_SWITCH">
<define name="DROP_SERVO_CLOSED" value="2000"/> <define name="SERVO_SWITCH_SERVO" value="DROP"/>
<define name="DROP_SERVO_OPEN" value="1000"/> <define name="SERVO_SWITCH_ON_VALUE" value="SERVO_DROP_MIN"/>
<define name="BoozDropPwm(_v)" value="BoozSetPwm0Value(_v)"/> <define name="SERVO_SWITCH_OFF_VALUE" value="SERVO_DROP_MAX"/>
<define name="DropOpen()" value="ServoSwitchOn()"/>
<define name="DropClose()" value="ServoSwitchOff()"/>
</section> </section>
<section name="MISC"> <section name="MISC">
+38 -37
View File
@@ -1,11 +1,8 @@
<airframe name="BOOZ2_G1"> <airframe name="BOOZ2_G1">
<modules main_freq="512"> <modules main_freq="512">
<load name="booz_pwm.xml"> <load name="servo_switch.xml"/>
<define name="USE_PWM1"/> <load name="rotorcraft_cam.xml"/>
</load>
<load name="booz_drop.xml"/>
<load name="booz_cam.xml"/>
<!--load name="sonar_maxbotix_booz.xml"/--> <!--load name="sonar_maxbotix_booz.xml"/-->
<!--load name="adc_generic_booz.xml"/--> <!--load name="adc_generic_booz.xml"/-->
<!--load name="sys_mon.xml"/--> <!--load name="sys_mon.xml"/-->
@@ -27,28 +24,30 @@
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/> <subsystem name="actuators" type="asctec"/>
<subsystem name="actuators" type="pwm">
<define name="USE_PWM0"/>
<define name="USE_PWM1"/>
</subsystem>
<subsystem name="imu" type="b2_v1.1"/> <subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"> <subsystem name="gps" type="ublox">
<configure name="GPS_BAUD" value="B57600"/> <configure name="GPS_BAUD" value="B57600"/>
</subsystem> </subsystem>
<subsystem name="stabilization" type="euler"/> <subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/> <subsystem name="ahrs" type="int_cmpl_euler"/>
<subsystem name="ins"/>
<subsystem name="ins" type="hff"/> <subsystem name="ins" type="hff"/>
<!--subsystem name="ins" type="extended"/-->
</firmware> </firmware>
<firmware name="booz_test_progs"> <servos driver="Asctec">
<target name="test_telemetry" board="booz_1.0"/> <servo name="PITCH" no="0" min="-100" neutral="0" max="100"/>
<target name="test_baro" board="booz_1.0"/> <servo name="ROLL" no="1" min="-100" neutral="0" max="100"/>
<target name="test_rc_spektrum" board="booz_1.0"/> <servo name="YAW" no="2" min="-100" neutral="0" max="100"/>
<target name="test_rc_ppm" board="booz_1.0"/> <servo name="THRUST" no="3" min="0" neutral="0" max="200"/>
</firmware> </servos>
<servos> <servos driver="Pwm">
<servo name="PITCH" no="0" min="0" neutral="0" max="255"/> <servo name="SWITCH" no="0" min="1060" neutral="1500" max="2120"/>
<servo name="ROLL" no="1" min="0" neutral="0" max="255"/> <servo name="CAM" no="1" min="1000" neutral="1500" max="2300"/>
<servo name="YAW" no="2" min="0" neutral="0" max="255"/>
<servo name="THRUST" no="3" min="0" neutral="0" max="255"/>
</servos> </servos>
<commands> <commands>
@@ -58,12 +57,19 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="SUPERVISION" prefix="SUPERVISION_"> <section name="TRIM">
<define name="TRIM_A" value="0"/> <define name="TRIM_ROLL" value="0"/>
<define name="TRIM_E" value="6"/> <define name="TRIM_PITCH" value="6"/>
<define name="TRIM_R" value="0"/> <define name="TRIM_YAW" value="0"/>
</section> </section>
<command_laws>
<set servo="PITCH" value="@PITCH - TRIM_PITCH"/>
<set servo="ROLL" value="@ROLL - TRIM_ROLL"/>
<set servo="YAW" value="@YAW - TRIM_YAW"/>
<set servo="THRUST" value="@THRUST"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32238"/> <define name="GYRO_P_NEUTRAL" value="32238"/>
@@ -158,8 +164,8 @@
<section name="INS" prefix="INS_"> <section name="INS" prefix="INS_">
<define name="BARO_SENS" value="15." integer="16"/> <define name="BARO_SENS" value="15." integer="16"/>
<!--define name="SONAR_SENS" value="2.146" integer="16"/--> <!--define name="SONAR_SENS" value="0.0128633" integer="16"/--> <!-- 3.3V supply -->
<define name="SONAR_SENS" value="0.0128633" integer="16"/> <define name="SONAR_SENS" value="0.00833333" integer="16"/> <!-- 5V supply -->
<define name="SONAR_MAX_RANGE" value="4.0"/> <define name="SONAR_MAX_RANGE" value="4.0"/>
</section> </section>
@@ -208,24 +214,19 @@
<define name="BOOZ_FMS_TIMEOUT" value="0"/> <define name="BOOZ_FMS_TIMEOUT" value="0"/>
</section> </section>
<section name="CAM" prefix="BOOZ_CAM_"> <section name="CAM" prefix="ROTORCRAFT_CAM_">
<define name="ON" value="LED_ON(CAM_SWITCH_LED)"/> <define name="ON" value="LED_ON(CAM_SWITCH_LED)"/>
<define name="OFF" value="LED_OFF(CAM_SWITCH_LED)"/> <define name="OFF" value="LED_OFF(CAM_SWITCH_LED)"/>
<define name="TILT_NEUTRAL" value="1500"/> <define name="TILT_SERVO" value="CAM"/>
<define name="TILT_MAX" value="1000"/> <define name="TILT_ANGLE_MAX" value="-90." unit="deg"/>
<define name="TILT_MIN" value="2300"/> <define name="TILT_ANGLE_MIN" value=" 10." unit="deg"/>
<define name="TILT_ANGLE_MIN" value="-90." unit="deg"/>
<define name="TILT_ANGLE_MAX" value=" 10." unit="deg"/>
<define name="PAN_NEUTRAL" value="0"/>
<define name="PAN_MIN" value="0"/>
<define name="PAN_MAX" value="25736"/> <!-- 360 deg (2^12) -->
<define name="SetPwm(_v)" value="BoozSetPwm1Value(_v)"/>
</section> </section>
<section name="DROP"> <section name="SERVO_SWITCH">
<define name="DROP_SERVO_CLOSED" value="2120"/> <define name="SERVO_SWITCH_ON_VALUE" value="SERVO_SWITCH_MIN"/>
<define name="DROP_SERVO_OPEN" value="1060"/> <define name="SERVO_SWITCH_OFF_VALUE" value="SERVO_SWITCH_MAX"/>
<!--define name="BoozDropPwm(_v)" value="BoozSetPwm0Value(_v)"/--> <define name="DropOpen()" value="ServoSwitchOn()"/>
<define name="DropClose()" value="ServoSwitchOff()"/>
</section> </section>
<section name="MISC"> <section name="MISC">
@@ -24,6 +24,7 @@
<subsystem name="telemetry" type="xbee_api"> <subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B38400"/> <configure name="MODEM_BAUD" value="B38400"/>
</subsystem> </subsystem>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="aspirin_v1.5"/> <subsystem name="imu" type="aspirin_v1.5"/>
<subsystem name="gps" type="ublox"> <subsystem name="gps" type="ublox">
@@ -70,11 +71,16 @@
</firmware> </firmware>
--> -->
<servos> <section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/> <define name="NB" value="4"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/> <define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
<servo name="RIGHT" no="2" min="0" neutral="0" max="255"/> </section>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
<servos driver="Mkk">
<servo name="FRONT" no="0" min="0" neutral="2" max="210"/>
<servo name="BACK" no="1" min="0" neutral="2" max="210"/>
<servo name="RIGHT" no="2" min="0" neutral="2" max="210"/>
<servo name="LEFT" no="3" min="0" neutral="2" max="210"/>
</servos> </servos>
<commands> <commands>
@@ -84,17 +90,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <section name="MIXING" prefix="MOTOR_MIXING_">
<define name="NB" value="4"/> <define name="TRIM_ROLL" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_PITCH" value="0"/>
</section> <define name="TRIM_YAW" value="0"/>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/> <define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/>
@@ -103,6 +102,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32581"/> <define name="GYRO_P_NEUTRAL" value="32581"/>
<define name="GYRO_Q_NEUTRAL" value="32008"/> <define name="GYRO_Q_NEUTRAL" value="32008"/>
@@ -23,6 +23,7 @@
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
</target> </target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="b2_v1.2"/> <subsystem name="imu" type="b2_v1.2"/>
@@ -70,11 +71,16 @@
</firmware> </firmware>
--> -->
<servos> <section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/> <define name="NB" value="4"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/> <define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
<servo name="RIGHT" no="2" min="0" neutral="0" max="255"/> </section>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
<servos driver="Mkk">
<servo name="FRONT" no="0" min="0" neutral="2" max="210"/>
<servo name="BACK" no="1" min="0" neutral="2" max="210"/>
<servo name="RIGHT" no="2" min="0" neutral="2" max="210"/>
<servo name="LEFT" no="3" min="0" neutral="2" max="210"/>
</servos> </servos>
<commands> <commands>
@@ -84,19 +90,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<!-- for the sim --> <section name="MIXING" prefix="MOTOR_MIXING_">
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <define name="TRIM_ROLL" value="0"/>
<define name="NB" value="4"/> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/> <define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/>
@@ -105,6 +102,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32581"/> <define name="GYRO_P_NEUTRAL" value="32581"/>
<define name="GYRO_Q_NEUTRAL" value="32008"/> <define name="GYRO_Q_NEUTRAL" value="32008"/>
+6 -18
View File
@@ -1,21 +1,18 @@
<!-- Paparazzi airframe DTD --> <!-- Paparazzi airframe DTD -->
<!ELEMENT airframe (include|servos|commands|csc_boards|rc_commands|auto_rc_commands|ap_only_commands|command_laws|section|makefile|modules|firmware)*> <!ELEMENT airframe (include|servos|commands|rc_commands|auto_rc_commands|ap_only_commands|command_laws|section|makefile|modules|firmware)*>
<!ELEMENT include EMPTY> <!ELEMENT include EMPTY>
<!ELEMENT servos (servo)*> <!ELEMENT servos (servo)*>
<!ELEMENT commands (axis)*> <!ELEMENT commands (axis)*>
<!ELEMENT csc_boards (board)*>
<!ELEMENT board (msg)*>
<!ELEMENT msg (field_map)*>
<!ELEMENT field_map EMPTY>
<!ELEMENT rc_commands (set)*> <!ELEMENT rc_commands (set)*>
<!ELEMENT auto_rc_commands (set)*> <!ELEMENT auto_rc_commands (set)*>
<!ELEMENT ap_only_commands (copy)*> <!ELEMENT ap_only_commands (copy)*>
<!ELEMENT command_laws (let|set|ratelimit)*> <!ELEMENT command_laws (let|set|call|ratelimit)*>
<!ELEMENT section (define|linear)*> <!ELEMENT section (define|linear)*>
<!ELEMENT servo EMPTY> <!ELEMENT servo EMPTY>
<!ELEMENT axis EMPTY> <!ELEMENT axis EMPTY>
<!ELEMENT set EMPTY> <!ELEMENT set EMPTY>
<!ELEMENT call EMPTY>
<!ELEMENT ratelimit EMPTY> <!ELEMENT ratelimit EMPTY>
<!ELEMENT copy EMPTY> <!ELEMENT copy EMPTY>
<!ELEMENT let EMPTY> <!ELEMENT let EMPTY>
@@ -54,7 +51,6 @@ driver CDATA #IMPLIED>
<!ATTLIST rc_commands> <!ATTLIST rc_commands>
<!ATTLIST ap_only_commands> <!ATTLIST ap_only_commands>
<!ATTLIST command_laws> <!ATTLIST command_laws>
<!ATTLIST csc_boards>
<!ATTLIST section <!ATTLIST section
name CDATA #IMPLIED name CDATA #IMPLIED
@@ -67,17 +63,6 @@ min CDATA #REQUIRED
neutral CDATA #REQUIRED neutral CDATA #REQUIRED
max CDATA #REQUIRED> max CDATA #REQUIRED>
<!ATTLIST board
id CDATA #REQUIRED>
<!ATTLIST msg
id CDATA #REQUIRED
type CDATA #REQUIRED>
<!ATTLIST field_map
field CDATA #REQUIRED
servo_id CDATA #REQUIRED>
<!ATTLIST axis <!ATTLIST axis
name CDATA #REQUIRED name CDATA #REQUIRED
failsafe_value CDATA #REQUIRED> failsafe_value CDATA #REQUIRED>
@@ -87,6 +72,9 @@ value CDATA #REQUIRED
command CDATA #IMPLIED command CDATA #IMPLIED
servo CDATA #IMPLIED> servo CDATA #IMPLIED>
<!ATTLIST call
fun CDATA #REQUIRED>
<!ATTLIST copy <!ATTLIST copy
command CDATA #REQUIRED> command CDATA #REQUIRED>
+32
View File
@@ -0,0 +1,32 @@
<!-- Default Aspirin V2.1 values based on the datasheet -->
<!-- You can also just leave out those defines then the defaults will be provided by imu_aspirin2.h -->
<airframe>
<section name="IMU" prefix="IMU_">
<!-- Use default driver values for gyro -->
<!-- Calibration Neutral -->
<!--define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/-->
<!-- SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 939.650 LSB/rad/sec / 12bit FRAC: 4096 / 939.65 -->
<!--define name="GYRO_P_SENS" value="4.359" integer="16"/>
<define name="GYRO_Q_SENS" value="4.359" integer="16"/>
<define name="GYRO_R_SENS" value="4.359" integer="16"/-->
<define name="ACCEL_X_NEUTRAL" value="20"/>
<define name="ACCEL_Y_NEUTRAL" value="-64"/>
<define name="ACCEL_Z_NEUTRAL" value="-56"/>
<define name="ACCEL_X_SENS" value="4.86426509754" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.90383669256" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.79740334168" integer="16"/>
<define name="MAG_X_NEUTRAL" value="-15"/>
<define name="MAG_Y_NEUTRAL" value="171"/>
<define name="MAG_Z_NEUTRAL" value="-137"/>
<define name="MAG_X_SENS" value="4.37201780121" integer="16"/>
<define name="MAG_Y_SENS" value="4.23841579524" integer="16"/>
<define name="MAG_Z_SENS" value="4.33314434312" integer="16"/>
</section>
</airframe>
+41 -52
View File
@@ -11,13 +11,13 @@
<airframe name="hexy_ll11a2pwm"> <airframe name="hexy_ll11a2pwm">
<servos min="0" neutral="0" max="0xff"> <servos driver="Pwm">
<servo name="FRONT_LEFT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT_LEFT" no="0" min="1000" neutral="1100" max="1950"/>
<servo name="FRONT_RIGHT" no="1" min="1000" neutral="1000" max="2000"/> <servo name="FRONT_RIGHT" no="1" min="1000" neutral="1100" max="1950"/>
<servo name="RIGHT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="2" min="1000" neutral="1100" max="1950"/>
<servo name="BACK_RIGHT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="BACK_RIGHT" no="3" min="1000" neutral="1100" max="1950"/>
<servo name="BACK_LEFT" no="4" min="1000" neutral="1000" max="2000"/> <servo name="BACK_LEFT" no="4" min="1000" neutral="1100" max="1950"/>
<servo name="LEFT" no="5" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="5" min="1000" neutral="1100" max="1950"/>
</servos> </servos>
<commands> <commands>
@@ -28,50 +28,33 @@
</commands> </commands>
<command_laws> <command_laws>
<!--<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/> <call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/> <set servo="FRONT_LEFT" value="motor_mixing.commands[SERVO_FRONT_LEFT]"/>
<set servo="MOTOR" value="@THROTTLE"/> <set servo="FRONT_RIGHT" value="motor_mixing.commands[SERVO_FRONT_RIGHT]"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/> <set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/> <set servo="BACK_RIGHT" value="motor_mixing.commands[SERVO_BACK_RIGHT]"/>
--> <set servo="BACK_LEFT" value="motor_mixing.commands[SERVO_BACK_LEFT]"/>
<set servo="FRONT_LEFT" value="0"/> <set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
<set servo="FRONT_RIGHT" value="1"/>
<set servo="RIGHT" value="2"/>
<set servo="BACK_RIGHT" value="3"/>
<set servo="BACK_LEFT" value="4"/>
<set servo="LEFT" value="5"/>
</command_laws> </command_laws>
<!-- for the sim --> <section name="MIXING" prefix="MOTOR_MIXING_">
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <define name="TRIM_ROLL" value="0"/>
<define name="NB" value="4"/> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
<define name="TRIM_R" value="0"/>
<define name="NB_MOTOR" value="6"/> <define name="NB_MOTOR" value="6"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 256, -256, -256, -256, 256, 256 }"/> <define name="ROLL_COEF" value="{ 256, -256, -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, 256, 0, -256, -256, 0 }"/> <define name="PITCH_COEF" value="{ 256, 256, 0, -256, -256, 0 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256, 256, -256 }"/> <define name="YAW_COEF" value="{ 256, -256, 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/>
<!--define name="MOTOR_INERTIA_COMPENSATION_FACTOR" value="2"/-->
</section> </section>
<include href="conf/airframes/esden/calib/asp21-001.xml"/> <include href="conf/airframes/esden/calib/asp21-001.xml"/>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg( 180. )"/> <define name="BODY_TO_IMU_PSI" value="180." unit="deg"/>
</section> </section>
<section name="AUTOPILOT"> <section name="AUTOPILOT">
@@ -229,26 +212,32 @@
<modules main_freq="512"> <modules main_freq="512">
<!--load name="vehicle_interface_overo_link.xml"/--> <!--load name="vehicle_interface_overo_link.xml"/-->
<load name="gps_ubx_ucenter.xml"/> <load name="gps_ubx_ucenter.xml"/>
<load name="led_safety_status.xml"/>
</modules> </modules>
<firmware name="rotorcraft"> <firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1"> <target name="ap" board="lisa_l_1.1">
<!-- <define name="BOOZ_START_DELAY" value="1"/> --> <subsystem name="radio_control" type="spektrum">
<subsystem name="radio_control" type="spektrum"/> <define name="RADIO_MODE" value="RADIO_FLAP"/>
<subsystem name="actuators" type="pwm_supervision"/> <define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<subsystem name="telemetry" type="transparent"/> <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="SERVO_HZ" value="400"/> </subsystem>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/> <configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
<!--define name = "RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT" value = "UART5"/-->
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target> </target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v2.1"/> <subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/> <subsystem name="stabilization" type="int_quat"/>
+233
View File
@@ -0,0 +1,233 @@
<!-- This is a star hexacopter frame equiped with Lisa/M 2.0, Aspirin 2.1 and hobbyking blue series 12A ESCs with SimonK firmware and 10/4.5 props -->
<!--
Applicable configuration:
airframe="airframes/esden/hexy_lm2a2pwm.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_tri.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml"
-->
<airframe name="hexy_lm2a2pwm">
<servos driver="Pwm">
<servo name="FRONT_LEFT" no="0" min="1000" neutral="1100" max="1950"/>
<servo name="FRONT_RIGHT" no="1" min="1000" neutral="1100" max="1950"/>
<servo name="RIGHT" no="2" min="1000" neutral="1100" max="1950"/>
<servo name="BACK_RIGHT" no="3" min="1000" neutral="1100" max="1950"/>
<servo name="BACK_LEFT" no="4" min="1000" neutral="1100" max="1950"/>
<servo name="LEFT" no="5" min="1000" neutral="1100" max="1950"/>
</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>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT_LEFT" value="motor_mixing.commands[SERVO_FRONT_LEFT]"/>
<set servo="FRONT_RIGHT" value="motor_mixing.commands[SERVO_FRONT_RIGHT]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="BACK_RIGHT" value="motor_mixing.commands[SERVO_BACK_RIGHT]"/>
<set servo="BACK_LEFT" value="motor_mixing.commands[SERVO_BACK_LEFT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="6"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 256, -256, -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, 256, 0, -256, -256, 0 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/>
</section>
<include href="conf/airframes/esden/calib/asp21-026.xml"/>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="180." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="180." unit="deg"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</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_PSI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="SP_MAX_P" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" 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(400.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="RadOfDeg(400.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<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.)"/>
<!-- simonk esc firmware gains light quad? -->
<!-- feedback -->
<define name="PHI_PGAIN" value="570"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="100"/>
<define name="THETA_PGAIN" value="570"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="100"/>
<define name="PSI_PGAIN" value="1300"/>
<define name="PSI_DGAIN" value="1000"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 530"/>
<define name="THETA_DDGAIN" value=" 530"/>
<define name="PSI_DDGAIN" value=" 300"/>
</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="830"/>
<define name="HOVER_KD" value="650"/>
<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="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value ="0.9"/-->
</section>
<section name="AHRS" prefix="AHRS_">
<define name="PROPAGATE_FREQUENCY" value="512"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="50"/>
<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"/-->
<load name="gps_ubx_ucenter.xml"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<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="1"/>
</subsystem>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/-->
</firmware>
<firmware name="lisa_test_progs">
<target name="test_led" board="lisa_m_2.0">
<configure name="SYS_TIME_LED" value="none"/>
</target>
<target name="test_uart" board="lisa_m_2.0"/>
<target name="test_servos" board="lisa_m_2.0"/>
<target name="test_telemetry" board="lisa_m_2.0"/>
<target name="test_imu_aspirin" board="lisa_m_2.0"/>
<target name="test_rc_spektrum" board="lisa_m_2.0"/>
<target name="test_baro" board="lisa_m_2.0"/>
<!--<target name="test_imu" board="lisa_m_2.0"/>
<target name="test_rc_ppm" board="lisa_m_2.0"/>
<target name="test_adc" board="lisa_m_2.0"/>
<target name="test_hmc5843" board="lisa_m_2.0"/>
<target name="test_itg3200" board="lisa_m_2.0"/>
<target name="test_adxl345" board="lisa_m_2.0"/>
<target name="test_esc_mkk_simple" board="lisa_m_2.0"/>
<target name="test_esc_asctecv1_simple" board="lisa_m_2.0"/>
<target name="test_actuators_mkk" board="lisa_m_2.0"/>
<target name="test_actuators_asctecv1" board="lisa_m_2.0"/-->
</firmware>
</airframe>
+39 -52
View File
@@ -11,11 +11,11 @@
<airframe name="quady_ll11a2pwm.xml"> <airframe name="quady_ll11a2pwm.xml">
<servos min="0" neutral="0" max="0xff"> <servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT" no="0" min="1000" neutral="1100" max="1950"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="1" min="1000" neutral="1100" max="1950"/>
<servo name="LEFT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="BACK" no="2" min="1000" neutral="1100" max="1950"/>
<servo name="RIGHT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="3" min="1000" neutral="1100" max="1950"/>
</servos> </servos>
<commands> <commands>
@@ -26,48 +26,31 @@
</commands> </commands>
<command_laws> <command_laws>
<!--<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/> <call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/> <set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="MOTOR" value="@THROTTLE"/> <set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/> <set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/> <set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
-->
<set servo="FRONT" value="0"/>
<set servo="BACK" value="1"/>
<set servo="LEFT" value="2"/>
<set servo="RIGHT" value="3"/>
</command_laws> </command_laws>
<!-- for the sim --> <section name="MIXING" prefix="MOTOR_MIXING_">
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <define name="TRIM_ROLL" value="0"/>
<define name="NB" value="4"/> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/> <define name="ROLL_COEF" value="{ 0, -256, 0, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/> <define name="PITCH_COEF" value="{ 256, 0, -256, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/> <define name="YAW_COEF" value="{ -256, 256, -256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
<!--define name="MOTOR_INERTIA_COMPENSATION_FACTOR" value="2"/-->
</section> </section>
<include href="conf/airframes/esden/calib/asp21-001.xml"/> <include href="conf/airframes/esden/calib/asp21-001.xml"/>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg( 225. )"/> <define name="BODY_TO_IMU_PSI" value="225." unit="deg"/>
</section> </section>
<section name="AUTOPILOT"> <section name="AUTOPILOT">
@@ -229,22 +212,27 @@
<firmware name="rotorcraft"> <firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1"> <target name="ap" board="lisa_l_1.1">
<!-- <define name="BOOZ_START_DELAY" value="1"/> --> <subsystem name="radio_control" type="spektrum">
<subsystem name="radio_control" type="spektrum"/> <define name="RADIO_MODE" value="RADIO_FLAP"/>
<subsystem name="actuators" type="pwm_supervision"/> <define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<subsystem name="telemetry" type="transparent"/> <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="SERVO_HZ" value="400"/> </subsystem>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/> <configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
<!--define name = "RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT" value = "UART5"/-->
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target> </target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v2.1"/> <subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/> <subsystem name="stabilization" type="int_quat"/>
@@ -255,7 +243,6 @@
<subsystem name="ahrs" type="int_cmpl_euler"/--> <subsystem name="ahrs" type="int_cmpl_euler"/-->
</firmware> </firmware>
<firmware name="lisa_test_progs"> <firmware name="lisa_test_progs">
<target name="test_led" board="lisa_l_1.1"> <target name="test_led" board="lisa_l_1.1">
<configure name="SYS_TIME_LED" value="none"/> <configure name="SYS_TIME_LED" value="none"/>
+35 -46
View File
@@ -11,11 +11,11 @@
<airframe name="quady_lm1a1pwm"> <airframe name="quady_lm1a1pwm">
<servos> <servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT" no="0" min="1000" neutral="1100" max="1950"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="1" min="1000" neutral="1100" max="1950"/>
<servo name="LEFT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="BACK" no="2" min="1000" neutral="1100" max="1950"/>
<servo name="RIGHT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="3" min="1000" neutral="1100" max="1950"/>
</servos> </servos>
<commands> <commands>
@@ -26,48 +26,31 @@
</commands> </commands>
<command_laws> <command_laws>
<!--<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/> <call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/> <set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="MOTOR" value="@THROTTLE"/> <set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/> <set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/> <set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
-->
<set servo="FRONT" value="0"/>
<set servo="BACK" value="1"/>
<set servo="LEFT" value="2"/>
<set servo="RIGHT" value="3"/>
</command_laws> </command_laws>
<!-- for the sim --> <section name="MIXING" prefix="MOTOR_MIXING_">
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <define name="TRIM_ROLL" value="0"/>
<define name="NB" value="4"/> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/> <define name="ROLL_COEF" value="{ 0, -256, 0, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/> <define name="PITCH_COEF" value="{ 256, 0, -256, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/> <define name="YAW_COEF" value="{ -256, 256, -256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
<!--define name="MOTOR_INERTIA_COMPENSATION_FACTOR" value="10"/-->
</section> </section>
<include href="conf/airframes/esden/calib/asp21-018.xml"/> <include href="conf/airframes/esden/calib/asp21-018.xml"/>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/> <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_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="45." unit="deg"/> <define name="BODY_TO_IMU_PSI" value="45." unit="deg"/>
</section> </section>
<section name="AUTOPILOT"> <section name="AUTOPILOT">
@@ -190,21 +173,27 @@
<firmware name="rotorcraft"> <firmware name="rotorcraft">
<target name="ap" board="lisa_m_1.0"> <target name="ap" board="lisa_m_1.0">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> --> <subsystem name="radio_control" type="spektrum">
<subsystem name="radio_control" type="spektrum"/> <define name="RADIO_MODE" value="RADIO_FLAP"/>
<subsystem name="actuators" type="pwm_supervision"/> <define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<subsystem name="telemetry" type="transparent"/> <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="SERVO_HZ" value="400"/> </subsystem>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/> <configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
</target> </target>
<target name="nps" board="pc"> <target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/> <subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target> </target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v1.0"/> <subsystem name="imu" type="aspirin_v1.0"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/> <subsystem name="stabilization" type="int_quat"/>
+39 -46
View File
@@ -11,11 +11,11 @@
<airframe name="quady_lm2a2pwm"> <airframe name="quady_lm2a2pwm">
<servos> <servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT" no="0" min="1000" neutral="1100" max="1950"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="1" min="1000" neutral="1100" max="1950"/>
<servo name="LEFT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="BACK" no="2" min="1000" neutral="1100" max="1950"/>
<servo name="RIGHT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="3" min="1000" neutral="1100" max="1950"/>
</servos> </servos>
<commands> <commands>
@@ -26,48 +26,31 @@
</commands> </commands>
<command_laws> <command_laws>
<!--<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/> <call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/> <set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="MOTOR" value="@THROTTLE"/> <set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/> <set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/> <set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
-->
<set servo="FRONT" value="0"/>
<set servo="BACK" value="1"/>
<set servo="LEFT" value="2"/>
<set servo="RIGHT" value="3"/>
</command_laws> </command_laws>
<!-- for the sim --> <section name="MIXING" prefix="MOTOR_MIXING_">
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <define name="TRIM_ROLL" value="0"/>
<define name="NB" value="4"/> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/> <define name="ROLL_COEF" value="{ 0, -256, 0, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/> <define name="PITCH_COEF" value="{ 256, 0, -256, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/> <define name="YAW_COEF" value="{ -256, 256, -256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
<!--define name="MOTOR_INERTIA_COMPENSATION_FACTOR" value="10"/-->
</section> </section>
<include href="conf/airframes/esden/calib/asp21-018.xml"/> <include href="conf/airframes/esden/calib/asp21-018.xml"/>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/> <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_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="45." unit="deg"/> <define name="BODY_TO_IMU_PSI" value="45." unit="deg"/>
</section> </section>
<section name="AUTOPILOT"> <section name="AUTOPILOT">
@@ -186,25 +169,35 @@
<modules main_freq="512"> <modules main_freq="512">
<!--load name="vehicle_interface_overo_link.xml"/--> <!--load name="vehicle_interface_overo_link.xml"/-->
<load name="gps_ubx_ucenter.xml"/> <load name="gps_ubx_ucenter.xml"/>
<load name="led_safety_status.xml">
<define name="SAFETY_WARNING_LED" value="5"/>
</load>
</modules> </modules>
<firmware name="rotorcraft"> <firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0"> <target name="ap" board="lisa_m_2.0">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> --> <subsystem name="radio_control" type="spektrum">
<subsystem name="radio_control" type="spektrum"/> <define name="RADIO_MODE" value="RADIO_FLAP"/>
<subsystem name="actuators" type="pwm_supervision"/> <define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<subsystem name="telemetry" type="transparent"/> <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="SERVO_HZ" value="400"/> </subsystem>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/> <configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
</target> </target>
<target name="nps" board="pc"> <target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/> <subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target> </target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v2.1"/> <subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/> <subsystem name="stabilization" type="int_quat"/>
+25 -16
View File
@@ -1,10 +1,17 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="BOOZ2_a1"> <airframe name="BOOZ2_a1">
<servos> <section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/> <define name="NB" value="4"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/> <define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
<servo name="RIGHT" no="2" min="0" neutral="0" max="255"/> </section>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
<servos driver="Mkk">
<servo name="FRONT" no="0" min="0" neutral="2" max="210"/>
<servo name="BACK" no="1" min="0" neutral="2" max="210"/>
<servo name="RIGHT" no="2" min="0" neutral="2" max="210"/>
<servo name="LEFT" no="3" min="0" neutral="2" max="210"/>
</servos> </servos>
<commands> <commands>
@@ -14,17 +21,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <section name="MIXING" prefix="MOTOR_MIXING_">
<define name="NB" value="4"/> <define name="TRIM_ROLL" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_PITCH" value="0"/>
</section> <define name="TRIM_YAW" value="0"/>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, 0, -256, 256}"/> <define name="ROLL_COEF" value="{ 0, 0, -256, 256}"/>
@@ -33,6 +33,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="33924"/> <define name="GYRO_P_NEUTRAL" value="33924"/>
@@ -199,6 +207,7 @@
</target> </target>
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.0"/> <subsystem name="imu" type="b2_v1.0"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
+31 -20
View File
@@ -1,13 +1,20 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is a custom hexa Lisa/L#3 and mikrokopter controllers --> <!-- this is a custom hexa Lisa/L#3 and mikrokopter controllers -->
<airframe name="booz2_a6"> <airframe name="booz2_a6">
<servos> <section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<servo name="BACK_RIGHT" no="0" min="0" neutral="0" max="255"/> <define name="NB" value="6"/>
<servo name="BACK_LEFT" no="1" min="0" neutral="0" max="255"/> <define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58, 0x5A, 0X5C }"/>
<servo name="CENTER_RIGHT" no="2" min="0" neutral="0" max="255"/> </section>
<servo name="CENTER_LEFT" no="3" min="0" neutral="0" max="255"/>
<servo name="FRONT_RIGHT" no="4" min="0" neutral="0" max="255"/> <servos driver="Mkk">
<servo name="FRONT_LEFT" no="5" min="0" neutral="0" max="255"/> <servo name="BACK_RIGHT" no="0" min="0" neutral="2" max="210"/>
<servo name="BACK_LEFT" no="1" min="0" neutral="2" max="210"/>
<servo name="CENTER_RIGHT" no="2" min="0" neutral="2" max="210"/>
<servo name="CENTER_LEFT" no="3" min="0" neutral="2" max="210"/>
<servo name="FRONT_RIGHT" no="4" min="0" neutral="2" max="210"/>
<servo name="FRONT_LEFT" no="5" min="0" neutral="2" max="210"/>
</servos> </servos>
<commands> <commands>
@@ -17,17 +24,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <section name="MIXING" prefix="MOTOR_MIXING_">
<define name="NB" value="6"/> <define name="TRIM_ROLL" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58, 0x5A, 0X5C }"/> <define name="TRIM_PITCH" value="0"/>
</section> <define name="TRIM_YAW" value="0"/>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
<define name="TRIM_R" value="0"/>
<define name="NB_MOTOR" value="6"/> <define name="NB_MOTOR" value="6"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -69, 69, -256, 256, -186, 186 }"/> <define name="ROLL_COEF" value="{ -69, 69, -256, 256, -186, 186 }"/>
@@ -36,6 +36,16 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="BACK_RIGHT" value="motor_mixing.commands[SERVO_BACK_RIGHT]"/>
<set servo="BACK_LEFT" value="motor_mixing.commands[SERVO_BACK_LEFT]"/>
<set servo="CENTER_RIGHT" value="motor_mixing.commands[SERVO_CENTER_RIGHT]"/>
<set servo="CENTER_LEFT" value="motor_mixing.commands[SERVO_CENTER_LEFT]"/>
<set servo="FRONT_RIGHT" value="motor_mixing.commands[SERVO_FRONT_RIGHT]"/>
<set servo="FRONT_LEFT" value="motor_mixing.commands[SERVO_FRONT_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="31948"/> <define name="GYRO_P_NEUTRAL" value="31948"/>
@@ -172,6 +182,7 @@
<target name="ap" board="lisa_l_1.0"> <target name="ap" board="lisa_l_1.0">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> --> <!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/> <subsystem name="radio_control" type="spektrum"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
</target> </target>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
@@ -200,8 +211,8 @@
<target name="test_adxl345" board="lisa_l_1.0"/> <target name="test_adxl345" board="lisa_l_1.0"/>
<target name="test_esc_mkk_simple" board="lisa_l_1.0"/> <target name="test_esc_mkk_simple" board="lisa_l_1.0"/>
<target name="test_esc_asctecv1_simple" board="lisa_l_1.0"/> <target name="test_esc_asctecv1_simple" board="lisa_l_1.0"/>
<target name="test_actuators_mkk" board="lisa_l_1.0"/> <!--target name="test_actuators_mkk" board="lisa_l_1.0"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.0"/> <target name="test_actuators_asctecv1" board="lisa_l_1.0"/-->
</firmware> </firmware>
</airframe> </airframe>
+23 -14
View File
@@ -1,12 +1,14 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers --> <!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
<airframe name="lisa_asctec"> <airframe name="lisa_asctec">
<servos> <servos driver="Asctec">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/> <servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/> <servo name="BACK" no="1" min="0" neutral="3" max="200"/>
<servo name="LEFT" no="2" min="0" neutral="0" max="255"/> <servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
<servo name="RIGHT" no="3" min="0" neutral="0" max="255"/> <servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
</servos> </servos>
<commands> <commands>
@@ -22,13 +24,10 @@
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section> </section>
<section name="MIXING" prefix="MOTOR_MIXING_">
<section name="SUPERVISION" prefix="SUPERVISION_"> <define name="TRIM_ROLL" value="0"/>
<define name="MIN_MOTOR" value="3"/> <define name="TRIM_PITCH" value="0"/>
<define name="MAX_MOTOR" value="200"/> <define name="TRIM_YAW" value="0"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/> <define name="ROLL_COEF" value="{ 0 , 0, 256, -256 }"/>
@@ -37,6 +36,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32276"/> <define name="GYRO_P_NEUTRAL" value="32276"/>
<define name="GYRO_Q_NEUTRAL" value="33987"/> <define name="GYRO_Q_NEUTRAL" value="33987"/>
@@ -183,6 +190,7 @@
<target name="ap" board="lisa_l_1.1"> <target name="ap" board="lisa_l_1.1">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> --> <!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/> <subsystem name="radio_control" type="spektrum"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="asctec_v2"/> <subsystem name="actuators" type="asctec_v2"/>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/> <define name="RADIO_MODE" value="RADIO_AUX2"/>
@@ -192,6 +200,7 @@
<target name="sim" board="pc"> <target name="sim" board="pc">
<subsystem name="fdm" type="jsbsim"/> <subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
</target> </target>
@@ -219,8 +228,8 @@
<target name="test_adxl345" 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_mkk_simple" board="lisa_l_1.1"/>
<target name="test_esc_asctecv1_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_mkk" board="lisa_l_1.1"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/> <target name="test_actuators_asctecv1" board="lisa_l_1.1"/-->
</firmware> </firmware>
@@ -25,7 +25,8 @@
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
</target> </target>
<subsystem name="actuators" type="pwm_supervision"> <subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/> <define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/> <define name="USE_SERVOS_7AND8"/>
</subsystem> </subsystem>
@@ -38,11 +39,11 @@
<subsystem name="ins"/> <subsystem name="ins"/>
</firmware> </firmware>
<servos> <servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/> <servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="RIGHT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="LEFT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
</servos> </servos>
<commands> <commands>
@@ -52,18 +53,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<command_laws> <section name="MIXING" prefix="MOTOR_MIXING_">
<!-- command_laws is needed for pwm_supervision --> <define name="TRIM_ROLL" value="0"/>
<!-- but can be empty if no additional servos are used --> <define name="TRIM_PITCH" value="0"/>
</command_laws> <define name="TRIM_YAW" value="0"/>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1900"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<!-- front/back turning CW, right/left CCW --> <!-- front/back turning CW, right/left CCW -->
@@ -73,6 +66,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="11"/> <define name="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/> <define name="ACCEL_Y_NEUTRAL" value="11"/>
+19 -13
View File
@@ -25,7 +25,8 @@
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
</target> </target>
<subsystem name="actuators" type="pwm_supervision"> <subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/> <define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/> <define name="USE_SERVOS_7AND8"/>
</subsystem> </subsystem>
@@ -43,11 +44,11 @@
<load name="geo_mag.xml"/> <load name="geo_mag.xml"/>
</modules> </modules>
<servos> <servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/> <servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/> <servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="RIGHT" no="2" min="1000" neutral="1000" max="2000"/> <servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="LEFT" no="3" min="1000" neutral="1000" max="2000"/> <servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
</servos> </servos>
<commands> <commands>
@@ -62,13 +63,10 @@
<!-- but can be empty if no additional servos are used --> <!-- but can be empty if no additional servos are used -->
</command_laws> </command_laws>
<section name="SUPERVISION" prefix="SUPERVISION_"> <section name="MIXING" prefix="MOTOR_MIXING_">
<define name="STOP_MOTOR" value="1000"/> <define name="TRIM_ROLL" value="0"/>
<define name="MIN_MOTOR" value="1100"/> <define name="TRIM_PITCH" value="0"/>
<define name="MAX_MOTOR" value="1900"/> <define name="TRIM_YAW" value="0"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<!-- front/back turning CW, right/left CCW --> <!-- front/back turning CW, right/left CCW -->
@@ -78,6 +76,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="11"/> <define name="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/> <define name="ACCEL_Y_NEUTRAL" value="11"/>
@@ -20,6 +20,7 @@
<subsystem name="radio_control" type="ppm"/> <subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/> <subsystem name="telemetry" type="transparent"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="mkk"/> <subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="aspirin_v1.5"/> <subsystem name="imu" type="aspirin_v1.5"/>
<subsystem name="gps" type="ublox"/> <subsystem name="gps" type="ublox"/>
@@ -28,6 +29,19 @@
<subsystem name="ins"/> <subsystem name="ins"/>
</firmware> </firmware>
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<!-- FRONT, BACK, RIGHT, LEFT -->
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>
<servos driver="Mkk">
<servo name="FRONT" no="0" min="0" neutral="2" max="200"/>
<servo name="BACK" no="1" min="0" neutral="2" max="200"/>
<servo name="RIGHT" no="2" min="0" neutral="2" max="200"/>
<servo name="LEFT" no="3" min="0" neutral="2" max="200"/>
</servos>
<commands> <commands>
<axis name="ROLL" failsafe_value="0"/> <axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/> <axis name="PITCH" failsafe_value="0"/>
@@ -35,18 +49,10 @@
<axis name="THRUST" failsafe_value="0"/> <axis name="THRUST" failsafe_value="0"/>
</commands> </commands>
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_"> <section name="MIXING" prefix="MOTOR_MIXING_">
<define name="NB" value="4"/> <define name="TRIM_ROLL" value="0"/>
<!-- FRONT, BACK, RIGHT, LEFT --> <define name="TRIM_PITCH" value="0"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/> <define name="TRIM_YAW" value="0"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<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="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/> <define name="SCALE" value="256"/>
<!-- front/back turning CW, left/right CCW --> <!-- front/back turning CW, left/right CCW -->
@@ -56,6 +62,14 @@
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/> <define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section> </section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_"> <section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="11"/> <define name="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/> <define name="ACCEL_Y_NEUTRAL" value="11"/>
+317
View File
@@ -0,0 +1,317 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
Lisa + Aspirin v2 using SPI only
-->
<airframe name="LisaAspirin2">
<servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="1" min="1200" neutral="1500" max="1800"/>
<servo name="ELEVATOR" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
<servo name="AILEVON_RIGHT" no="4" min="1800" neutral="1500" max="1200"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="FORCECRASH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
<!-- <set command="FORCECRASH" value="@FLAPS"/> -->
</rc_commands>
<command_laws>
<set servo="AILEVON_LEFT" value="@ROLL"/>
<set servo="AILEVON_RIGHT" value="-@ROLL"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW"/>
</command_laws>
<!-- Local magnetic field -->
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value="0.85490967783446"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 939.650 LSB/rad/sec / 12bit FRAC: 4096 / 939.65 -->
<define name="GYRO_P_SENS" value="4.359" integer="16"/>
<define name="GYRO_Q_SENS" value="4.359" integer="16"/>
<define name="GYRO_R_SENS" value="4.359" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- SENS = 2048 LSB/g / 9.81 ms2/g = 208.766564729 LSB/ms2 / 10bit FRAC: 1024 / 208.7665 -->
<define name="ACCEL_X_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Y_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Z_SENS" value="9.81" 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="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="-0.0" unit="rad"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0.103000000119" unit="rad"/>
</section>
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0"/>
<define name="PITCH_TRIM" value="788."/>
</section>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.8"/>
<define name="MAX_PITCH" value="0.8"/>
</section>
<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"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0."/>
</section>
<section name="CATAPULT" prefix="NAV_CATAPULT_" >
<define name="MOTOR_DELAY" value="45" />
<define name="HEADING_DELAY" value="(60*3)" />
<define name="ACCELERATION_THRESHOLD" value="1.75" />
<define name="INITIAL_PITCH" value="(15.0/57.0)" />
<define name="INITIAL_THROTTLE" value="1.0" />
</section>
<section name="GLS_APPROACH" prefix="APP_" >
<define name="ANGLE" value="5" />
<define name="INTERCEPT_AF_TOD" value="10" />
<define name="TARGET_SPEED" value="13" />
</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.104999996722"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
<define name="ALTITUDE_PRE_CLIMB_CORRECTION" value="0.0960000008345"/>
<!--
<define name="AUTO_PITCH_PGAIN" value="-0.00"/>
<define name="AUTO_PITCH_IGAIN" value="-0.00"/>
-->
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.36700001359"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.626999974251"/>
<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.518000006676" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.00"/>
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.307000011206"/>
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.16600000858"/>
<define name="COURSE_DGAIN" value="0.324999988079"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.889999985695"/>
<define name="ROLL_MAX_SETPOINT" value="0.586000025272" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="PITCH_PGAIN" value="12587.4130859"/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1273.88500977"/>
<define name="ROLL_SLEW" value="1."/>
<define name="ROLL_ATTITUDE_GAIN" value="7972.02783203"/>
<define name="ROLL_RATE_GAIN" value="500."/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="70"/>
<define name="BLEND_END" value="60"/>
<define name="CLIMB_THROTTLE" value="0.949999988079"/>
<define name="CLIMB_PITCH" value="0.352999985218"/>
<define name="DESCENT_THROTTLE" value="0."/>
<define name="DESCENT_PITCH" value="-0.252000004053"/>
<define name="CLIMB_NAV_RATIO" value="0.8"/>
<define name="DESCENT_NAV_RATIO" value="1.0"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<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="gps_ubx_ucenter.xml"/>
<!--
<load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="0" />
<configure name="ADC_CHANNEL_GENERIC2" value="1" />
</load>
-->
<load name="light.xml">
<define name="LIGHT_LED_STROBE" value="2"/>
<define name="LIGHT_LED_NAV" value="3"/>
<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>
<load name="nav_catapult.xml"/>
</modules>
<firmware name="fixedwing">
<target name="fbw" board="lisa_m_2.0">
<configure name="SYS_TIME_LED" value="2" />
<define name="RADIO_CONTROL_LED" value="4"/>
<configure name="FLASH_MODE" value="JTAG" />
<configure name="NO_LUFTBOOT" value="1" />
<!-- <configure name="BMP_PORT" value="/dev/ttyACM0" /> -->
<define name="OUTBACK_CHALLENGE_DANGEROUS_RULE_RC_LOST_NO_AP" value="1" />
<define name="OUTBACK_CHALLENGE_VERY_DANGEROUS_RULE_AP_CAN_FORCE_FAILSAFE" value="1" />
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="direct"/>
<subsystem name="intermcu" type="uart">
<configure name="INTERMCU_PORT_NR" value="2" />
</subsystem>
</firmware>
<firmware name="fixedwing">
<target name="ap" board="lisa_m_2.0">
<define name="LISA_M_LONGITUDINAL_X"/>
<configure name="SEPARATE_FBW" value="1"/>
<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="FLASH_MODE" value="JTAG" />
<configure name="NO_LUFTBOOT" value="1" />
<!-- <configure name="BMP_PORT" value="/dev/ttyACM0" /> -->
<configure name="AHRS_ALIGNER_LED" value="1"/>
<configure name="CPU_LED" value="1"/>
</target>
<target name="sim" board="pc"/>
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="RADIO_CONTROL_AUTO1"/>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="ahrs" type="float_dcm" />
<!-- Communication -->
<!-- <subsystem name="telemetry" type="xbee_api"> -->
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_PORT" value="UART2"/>
</subsystem>
<!-- Actuators -->
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="navigation" type="extra"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART1"/>
</subsystem>
<subsystem name="actuators" type="dummy"/>
<subsystem name="intermcu" type="uart">
<configure name="INTERMCU_PORT_NR" value="5" />
</subsystem>
</firmware>
<makefile>
</makefile>
</airframe>
+1 -1
View File
@@ -4,7 +4,7 @@
<firmware name="setup"> <firmware name="setup">
<target name="tunnel" board="lisa_m_2.0"/> <target name="tunnel" board="lisa_m_2.0"/>
<target name="setup_actuators" board="lisa_m_2.0"/> <!--target name="setup_actuators" board="lisa_m_2.0"/-->
</firmware> </firmware>
<firmware name="lisa_test_progs"> <firmware name="lisa_test_progs">
+2 -2
View File
@@ -186,7 +186,7 @@ fbw.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLI
fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c
fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE
fbw.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c fbw.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c
fbw.CFLAGS += -DADC -DUSE_AD0 fbw.CFLAGS += -DADC -DUSE_AD0
fbw.srcs += $(SRC_ARCH)/adc_hw.c fbw.srcs += $(SRC_ARCH)/adc_hw.c
@@ -202,7 +202,7 @@ ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLIN
ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/datalink/pprz_transport.c ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/datalink/pprz_transport.c
ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0 ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0
ap.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c ap.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c
ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400 ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400
ap.srcs += gps_ubx.c gps.c latlong.c ap.srcs += gps_ubx.c gps.c latlong.c
+2 -2
View File
@@ -195,7 +195,7 @@ fbw.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLI
fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c
fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE
fbw.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c fbw.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c
fbw.CFLAGS += -DADC -DUSE_AD0 fbw.CFLAGS += -DADC -DUSE_AD0
fbw.srcs += $(SRC_ARCH)/adc_hw.c fbw.srcs += $(SRC_ARCH)/adc_hw.c
@@ -208,7 +208,7 @@ ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLIN
ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/navigation/traffic_info.c subsystems/datalink/pprz_transport.c ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/navigation/traffic_info.c subsystems/datalink/pprz_transport.c
ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER
ap.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c ap.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c
ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400 ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400
ap.srcs += gps_ubx.c gps.c latlong.c ap.srcs += gps_ubx.c gps.c latlong.c
+8
View File
@@ -55,5 +55,13 @@ ifndef SYS_TIME_LED
SYS_TIME_LED = none SYS_TIME_LED = none
endif endif
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_pwm
endif
+10
View File
@@ -86,6 +86,16 @@ ifndef GPS_BAUD
GPS_BAUD=B38400 GPS_BAUD=B38400
endif endif
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_pwm
endif
# #
# this is the DRDY pin of a max1168 on a booz IMU # this is the DRDY pin of a max1168 on a booz IMU
# #
+10
View File
@@ -89,6 +89,16 @@ ifndef GPS_BAUD
GPS_BAUD=B38400 GPS_BAUD=B38400
endif endif
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_pwm
endif
# #
# this is the DRDY pin of a max1168 on a booz IMU # this is the DRDY pin of a max1168 on a booz IMU
# #
+10
View File
@@ -83,6 +83,16 @@ GPS_BAUD=B38400
endif endif
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_pwm
endif
ifndef ADC_IR1 ifndef ADC_IR1
ADC_IR1 = 1 ADC_IR1 = 1
+10
View File
@@ -86,6 +86,16 @@ GPS_BAUD=B38400
endif endif
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_pwm
endif
ifndef ADC_IR1 ifndef ADC_IR1
ADC_IR1 = 1 ADC_IR1 = 1
+83
View File
@@ -0,0 +1,83 @@
#
# yapa_2.0.makefile
#
# http://paparazzi.enac.fr/wiki/YAPA/v2.0
#
ARCH=lpc21
BOARD=yapa
BOARD_VERSION=2.0
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ifndef FLASH_MODE
FLASH_MODE = IAP
endif
LPC21ISP_BAUD = 38400
LPC21ISP_XTAL = 12000
#
# default LED configuration
#
ifndef RADIO_CONTROL_LED
RADIO_CONTROL_LED = none
endif
ifndef BARO_LED
BARO_LED = none
endif
ifndef AHRS_ALIGNER_LED
AHRS_ALIGNER_LED = none
endif
ifndef GPS_LED
GPS_LED = 2
endif
ifndef SYS_TIME_LED
SYS_TIME_LED = 1
endif
#
# default uart settings
#
ifndef GPS_PORT
GPS_PORT = UART0
endif
ifndef GPS_BAUD
GPS_BAUD = B38400
endif
ifndef MODEM_PORT
MODEM_PORT = UART1
endif
ifndef MODEM_BAUD
MODEM_BAUD = B57600
endif
ADC_IR_TOP = ADC_0
ADC_IR1 = ADC_1
ADC_IR2 = ADC_2
ADC_IR_NB_SAMPLES = 16
ADC_GYRO_NB_SAMPLES = 16
ADC_GENERIC_NB_SAMPLES = 16
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
#
ifndef ACTUATORS
ACTUATORS = actuators_4017
endif
# All targets on the TINY board run on the same processor achitecture
$(TARGET).ARCHDIR = $(ARCH)
+1 -10
View File
@@ -34,16 +34,7 @@ endif
ifeq ($(TARGET),$(ACTUATOR_TARGET)) ifeq ($(TARGET),$(ACTUATOR_TARGET))
ifeq ($(ACTUATORS),) ifneq ($(ACTUATORS),)
ifeq ($(BOARD),lisa_l)
include $(CFG_SHARED)/actuators_direct.makefile
endif
ifeq ($(BOARD),lisa_m)
include $(CFG_SHARED)/actuators_direct.makefile
endif
else
include $(CFG_SHARED)/$(ACTUATORS).makefile include $(CFG_SHARED)/$(ACTUATORS).makefile
endif endif

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