Update all configs to new UPPERCASE 3rd party naming convention and new aircraft ids

This commit is contained in:
Open UAS
2015-10-13 15:18:25 +02:00
committed by TU Delft developer
parent 6807c99dec
commit f88d40b370
44 changed files with 3751 additions and 27 deletions
@@ -2,8 +2,8 @@
<aircraft
name="Ark_Quad"
ac_id="2"
airframe="airframes/AggieAir/ark_quad_lisa_mx.xml"
radio="radios/Taranis_AggieAir.xml"
airframe="airframes/AGGIEAIR/ark_quad_lisa_mx.xml"
radio="radios/AGGIEAIR/aggieair_taranis.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_rate.xml settings/nps.xml settings/control/stabilization_att_float_euler.xml"
@@ -13,8 +13,8 @@
<aircraft
name="Minion_Lia"
ac_id="1"
airframe="airframes/AggieAir/rp3_lia.xml"
radio="radios/Taranis_AggieAir.xml"
airframe="airframes/AGGIEAIR/rp3_lia.xml"
radio="radios/AGGIEAIR/aggieair_taranis.xml"
telemetry="telemetry/default_fixedwing.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml settings/control/ctl_basic.xml"
+76 -10
View File
@@ -1,24 +1,90 @@
<conf>
<aircraft
name="Psi"
ac_id="218"
airframe="airframes/OPENUAS/openuas_ardrone2.xml"
radio="radios/dummy.xml"
name="Itsy-Bitsy"
ac_id="229"
airframe="airframes/OPENUAS/openuas_itsybitsy.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/OPENUAS/openuas_rotorcraft_simple.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/body_to_imu.xml settings/estimation/ahrs_int_cmpl_quat.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_indi.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml settings/control/stabilization_rate.xml settings/superbitrf.xml settings/nps.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/geo_mag.xml modules/air_data.xml"
gui_color="#fffffe72b9fd"
/>
<aircraft
name="Leapfrogeye"
ac_id="228"
airframe="airframes/OPENUAS/openuas_leapfrogeye.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/estimation/ahrs_secondary.xml settings/estimation/ahrs_int_cmpl_quat.xml settings/control/stabilization_att_indi.xml"
settings_modules="modules/geo_mag.xml modules/air_data.xml modules/video_thread.xml modules/cv_blob_locator.xml modules/video_rtp_stream.xml modules/nav_survey_rectangle_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/digital_cam_video.xml"
gui_color="#ffffe8b36503"
/>
<aircraft
name="Mentor"
ac_id="227"
airframe="airframes/OPENUAS/openuas_mentor.xml"
radio="radios/R6107SP_7ch.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/versatile_airspeed.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energy.xml settings/estimation/ac_char.xml"
settings_modules="modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/light.xml modules/digital_cam.xml"
gui_color="#ffffffffffff"
/>
<aircraft
name="Moksha"
ac_id="226"
airframe="airframes/OPENUAS/openuas_moksha.xml"
radio="radios/OPENUAS/openuas_mx22_cppm.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/versatile_airspeed.xml"
settings="settings/fixedwing_basic.xml"
settings_modules=""
gui_color="#ffffeb519c78"
/>
<aircraft
name="Psi"
ac_id="225"
airframe="airframes/OPENUAS/openuas_psi.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_rate.xml settings/estimation/ahrs_int_cmpl_quat.xml settings/estimation/body_to_imu.xml settings/control/stabilization_att_indi.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml"
gui_color="#fffffe72b9fd"
/>
<aircraft
name="Quadyshoty"
ac_id="224"
airframe="airframes/examples/quadshot_asp21_spektrum.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_int_cmpl_quat.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int_quat.xml"
settings_modules="modules/gps_ubx_ucenter.xml"
gui_color="#ffffffffffff"
/>
<aircraft
name="TaxiIII"
ac_id="223"
airframe="airframes/OPENUAS/openuas_taxiiii.xml"
radio="radios/OPENUAS/openuas_mx22.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/infrared_adc.xml"
gui_color="#ffffeb519c78"
/>
<aircraft
name="Vivify"
ac_id="217"
ac_id="222"
airframe="airframes/OPENUAS/openuas_vivify.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_obc2014_kingaroy.xml"
settings="settings/control/ctl_energy.xml [settings/estimation/ins_neutrals.xml] settings/estimation/ac_char.xml settings/fixedwing_basic.xml"
gui_color="#fffffac7c07a"
settings="settings/control/ctl_energy.xml settings/estimation/ac_char.xml settings/fixedwing_basic.xml"
settings_modules="modules/air_data.xml modules/gps_ubx_ucenter.xml modules/airspeed_adc.xml modules/tune_airspeed.xml modules/photogrammetry_calculator.xml modules/digital_cam_uart.xml modules/nav_survey_poly_osam.xml modules/nav_smooth.xml"
gui_color="#fffffac7c07a"
/>
</conf>
+13
View File
@@ -0,0 +1,13 @@
<conf>
<aircraft
name="Vivify"
ac_id="217"
airframe="airframes/OPENUAS/openuas_vivify.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_obc2014_kingaroy.xml"
settings="settings/control/ctl_energy.xml settings/estimation/ac_char.xml settings/fixedwing_basic.xml"
settings_modules="modules/air_data.xml modules/gps_ubx_ucenter.xml modules/airspeed_adc.xml modules/tune_airspeed.xml modules/photogrammetry_calculator.xml modules/digital_cam_uart.xml modules/nav_survey_poly_osam.xml modules/nav_smooth.xml"
gui_color="#fffffac7c07a"
/>
</conf>
@@ -45,7 +45,6 @@
<program name="Environment Simulator" command="sw/simulator/gaia">
<arg flag="-b" variable="ivy_bus"/>
</program>
<program name="Http Server" command="sw/ground_segment/tmtc/boa"/>
<program name="Plot Meteo Profile" command="sw/logalizer/plotprofile"/>
<program name="Weather Station" command="sw/ground_segment/misc/davis2ivy">
<arg flag="-b" variable="ivy_bus"/>
@@ -0,0 +1,262 @@
<!-- this is a LadyBird quadrotor frame equiped with Lisa/S 1.0 -->
<!-- The LadyBird frame comes with four brushed motors in an X configuration. -->
<!--
The motor and rotor configuration is the following:
Front
^
|
Motor3(NW) Motor0(NE)
CW CCW
\ /
,___,
| |
| |
|___|
/ \
CCW CW
Motor2(SW) Motor1(SE)
The Lisa/S is rotated by 13deg CCW against the frame.
-->
<!--
Applicable configuration:
airframe="airframes/examples/ladybird_lisa_s.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml settings/control/stabilization_rate.xml"
-->
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="itsybitsy">
<!-- The no= value is the phisycal connector on the autopilot board -->
<servos driver="Pwm">
<servo name="NE" no="0" min="0" neutral="50" max="1000"/>
<servo name="SE" no="1" min="0" neutral="50" max="1000"/>
<servo name="SW" no="2" min="0" neutral="50" max="1000"/>
<servo name="NW" no="3" min="0" neutral="50" max="1000"/>
</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="NE" value="motor_mixing.commands[0]"/>
<set servo="SE" value="motor_mixing.commands[1]"/>
<set servo="SW" value="motor_mixing.commands[2]"/>
<set servo="NW" value="motor_mixing.commands[3]"/>
</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="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<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="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="-13." unit="deg"/>
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- MAGNETO CALIBRATION NL -->
<define name="MAG_X_NEUTRAL" value="360"/>
<define name="MAG_Y_NEUTRAL" value="-602"/>
<define name="MAG_Z_NEUTRAL" value="-313"/>
<define name="MAG_X_SENS" value="3.87956285611" integer="16"/>
<define name="MAG_Y_SENS" value="4.00524696232" integer="16"/>
<define name="MAG_Z_SENS" value="4.09474740848" integer="16"/>
<!-- MAGNETO CURRENT CALIBRATION -->
<define name="MAG_X_CURRENT_COEF" value="0.0103422023767"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0084568317783"/>
<define name="MAG_Z_CURRENT_COEF" value="-0.01935617335"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<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"/>
<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="14000"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="2.8" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="3.2" unit="V"/>
<define name="LOW_BAT_LEVEL" value="3.4" unit="V"/>
<define name="MAX_BAT_LEVEL" value="4.2" unit="V"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<define name="SP_MAX_P" value="15000"/>
<define name="SP_MAX_Q" value="15000"/>
<define name="SP_MAX_R" value="15000"/>
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="418"/>
<define name="IGAIN_P" value="301"/>
<define name="IGAIN_Q" value="302"/>
<define name="IGAIN_R" value="303"/>
</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_PSI" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="SP_MAX_P" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" 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="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="90." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="400"/>
<define name="PHI_DGAIN" value="200"/>
<define name="PHI_IGAIN" value="100"/>
<define name="THETA_PGAIN" value="400"/>
<define name="THETA_DGAIN" value="200"/>
<define name="THETA_IGAIN" value="100"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="300"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value=" 300"/>
<define name="PHI_AGAIN" value="0"/>
<define name="THETA_AGAIN" value="0"/>
<define name="PSI_AGAIN" value="0"/>
</section>
<section name="INS" prefix="INS_">
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="276"/>
<define name="HOVER_KD" value="455"/>
<define name="HOVER_KI" value="100"/>
<define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value="0.5"/>
</section>
<section name="AHRS" prefix="AHRS_">
<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="39"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="19"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<load name="gps_ubx_ucenter.xml"/>
<load name="geo_mag.xml"/>
<load name="air_data.xml"/>
<!-- below temporary until tsted then remove it-->
<load name="send_imu_mag_current.xml"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_s_1.0">
<subsystem name="radio_control" type="superbitrf_rc"> <!-- type="ppm" -->
<!-- To store the binding parameters for the superbit radio in your
airframe file uncomment the following three lines and set the
correct values based on the output of the superbitrf telemetry
messages. -->
<!--define name="RADIO_TRANSMITTER_ID" value="1335259868"/--> <!-- MX22 module no1 -->
<!--define name="RADIO_TRANSMITTER_CHAN" value="9"/-->
<!--define name="RADIO_TRANSMITTER_PROTOCOL" value="0x01"/--><!--DSM_DSM2_2-->
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
</subsystem>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>
</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">
<!-- This airframe is using the servo PWM outputs directly to drive mosfets, which in turn directly drive brushed motors.
With the following settings we will be driving the motors with a 36KHz signal that should be well above anyone's hearing range.
If we went with the 500Hz that woul be the default we would be hearing a very annoying high pitched sound coming from the motors.
-->
<!-- Setting the PWM timer base frequency to 36MHz -->
<define name="PWM_BASE_FREQ" value="36000000"/>
<!-- Setting the PWM interval to 36KHz -->
<define name="SERVO_HZ" value="36000"/>
<define name="USE_SERVOS_1AND2"/>
</subsystem>
<subsystem name="telemetry" type="superbitrf"/>
<!-- Comment the previous line and uncomment the following one if you need
to use the debug serial interface for telemetry. -->
<!--subsystem name="telemetry" type="transparent"/-->
<subsystem name="imu" type="lisa_s_v1.0">
<define name="LISA_S_UPSIDE_DOWN"/> <!-- Upside down is a relative term. :) -->
</subsystem>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<!-- <configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>-->
<subsystem name="ins"/>
</firmware>
</airframe>
@@ -0,0 +1,261 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="leapfrogeye">
<firmware name="rotorcraft">
<target name="ap" board="bebop"/>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="udp"/>
</target>
<!--define name="USE_SONAR" value="TRUE"/-->
<!-- Subsystem section -->
<subsystem name="telemetry" type="transparent_udp"/>
<subsystem name="radio_control" type="datalink"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="bebop"/>
<subsystem name="imu" type="bebop"/>
<subsystem name="gps" type="furuno"/>
<subsystem name="stabilization" type="indi"/>
<subsystem name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</subsystem>
<subsystem name="ins" type="extended"/>
<subsystem name="guidance" type="indi"/>
</firmware>
<modules main_freq="512">
<load name="geo_mag.xml"/>
<load name="air_data.xml"/>
<!-- only for calibration once-->
<load name="send_imu_mag_current.xml"/>
<!--load name="logger_file.xml">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</load-->
<load name="video_thread.xml">
<define name="VIDEO_THREAD_FPS" value="4"/>
<define name="VIDEO_THREAD_CAMERA" value="bottom_camera"/>
<define name="VIDEO_THREAD_SHOT_PATH" value="/data/ftp/internal_000/images"/>
</load>
<load name="cv_blob_locator.xml"/>
<load name="video_rtp_stream.xml">
<define name="VIEWVIDEO_QUALITY_FACTOR" value="80"/>
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="1"/>
</load>
<load name="nav_survey_rectangle_rotorcraft.xml">
<define name="RECTANGLE_SURVEY_DEFAULT_SWEEP" value="10"/>
</load>
<load name="nav_survey_poly_rotorcraft.xml">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="10"/>
</load>
<load name="digital_cam_video.xml">
<define name="DC_AUTOSHOOT_DISTANCE_INTERVAL" value="5"/>
</load>
<load name="video_exif.xml"/>
</modules>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="6000"/>
</commands>
<servos driver="Default">
<servo name="TOP_RIGHT" no="0" min="3000" neutral="3000" max="12000"/>
<servo name="TOP_LEFT" no="1" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_LEFT" no="2" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_RIGHT" no="3" min="3000" neutral="3000" max="12000"/>
</servos>
<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="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE"/>
<define name="CALC_TAS_FACTOR" value="FALSE"/>
<define name="CALC_AMSL_BARO" value="TRUE"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Magneto calibration spesific for this airframe -->
<define name="MAG_X_NEUTRAL" value="-54"/>
<define name="MAG_Y_NEUTRAL" value="-1"/>
<define name="MAG_Z_NEUTRAL" value="134"/>
<define name="MAG_X_SENS" value="7.55622140532" integer="16"/>
<define name="MAG_Y_SENS" value="7.72221931874" integer="16"/>
<define name="MAG_Z_SENS" value="7.84828034818" integer="16"/>
<!-- Magneto current compensation factor calibration -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- NL -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<!-- DE -->
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="300" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>
</section>
<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.0639"/>
<define name="G1_Q" value="0.0361"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.1450"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="600.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="28.0"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="50.0"/>
<define name="FILT_ZETA" value="0.55"/>
<define name="FILT_OMEGA_R" value="50.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.1"/>
<define name="ACT_DYN_Q" value="0.1"/>
<define name="ACT_DYN_R" value="0.1"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="REF_MAX_SPEED" value="2" unit="m/s"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="2.5"/>
<define name="DESCEND_VSPEED" value="-1.0"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<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_NAV"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="11.0" unit="V"/>
<define name="LOW_BAT_LEVEL" value="11.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
+261
View File
@@ -0,0 +1,261 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
Lisa + Aspirin v2 using SPI only
-->
<airframe name="LisaAspirin2">
<!-- ************************* FIRMWARE ************************* -->
<firmware name="fixedwing">
<target name="ap" board="lisa_m_1.0">
<define name="LISA_M_LONGITUDINAL_X"/>
<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"/>
</target>
<target name="sim" board="pc"/>
<target name="nps" board="pc">
<!-- Note NPS needs the ppm type radio_control subsystem -->
<subsystem name="fdm" type="jsbsim"/>
</target>
<define name="USE_AIRSPEED"/>
<define name="AGR_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<!-- Sensors -->
<subsystem name="imu" type="aspirin_v2.1"/>
<!--
<subsystem name="ahrs" type="float_dcm">
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="USE_AHRS_GPS_ACCELERATIONS"/>
</subsystem>
-->
<subsystem name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN"/>
</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"/>
<configure name="MODEM_PORT" value="UART2"/>
</subsystem>
<!-- Actuators -->
<subsystem name="control" type="energy"/>
<!-- Sensors -->
<subsystem name="navigation"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART1"/>
</subsystem>
</firmware>
<!-- ************************* MODULES ************************* -->
<modules>
<load name="geo_mag.xml"/>
<load name="gps_ubx_ucenter.xml"/>
<load name="airspeed_ets.xml">
<define name="AIRSPEED_ETS_SYNC_SEND"/>
<define name="AIRSPEED_ETS_I2C_DEV" value="i2c2"/>
<define name="USE_I2C2"/>
</load>
<load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_1"/>
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_2"/>
</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.xml">
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12"/>
</load>
<!-- load name="nav_catapult.xml"/-->
<load name="nav_line.xml"/>
</modules>
<!-- ************************* ACTUATORS ************************* -->
<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"/>
</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="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.8"/>
<define name="MAX_PITCH" value="0.8"/>
</section>
<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>
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0"/>
<define name="PITCH_TRIM" value="788."/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="10.0" unit="deg"/>
<define name="DEFAULT_PITCH" value="5.0" unit="deg"/>
<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>
<!-- ************************* SENSORS ************************* -->
<section name="IMU" prefix="IMU_">
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-179"/>
<define name="MAG_Y_NEUTRAL" value="-21"/>
<define name="MAG_Z_NEUTRAL" value="79"/>
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
<define name="MAG_Z_SENS" value="4.40442339014" 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="AHRS" prefix="AHRS_">
<!-- Local magnetic field, on 3D fix is update by geo_mag module -->
<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="ROLL_NEUTRAL_DEFAULT" value="0.0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="5.9" unit="deg"/>
</section>
<!-- ************************* GAINS ************************* -->
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.89"/>
<define name="COURSE_DGAIN" value="0.27"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="1.0"/>
<define name="ROLL_MAX_SETPOINT" value="45" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="50" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-50" unit="deg"/>
<define name="PITCH_PGAIN" value="12000"/>
<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="VERTICAL CONTROL" prefix="V_CTL_">
<!-- power -->
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.183"/>
<define name="AIRSPEED_PGAIN" value="0.217"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="10."/>
<define name="MAX_ACCELERATION" value="2."/>
<!-- energy -->
<define name="ENERGY_TOT_PGAIN" value="0.205"/>
<define name="ENERGY_TOT_IGAIN" value="0.403"/>
<define name="ENERGY_DIFF_PGAIN" value="0.403"/>
<define name="ENERGY_DIFF_IGAIN" value="0.259"/>
<define name="GLIDE_RATIO" value="7."/>
<!-- auto throttle -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0." unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0."/>
<!-- extra's -->
<define name="AUTO_THROTTLE_OF_AIRSPEED_PGAIN" value="0.0"/>
<define name="AUTO_THROTTLE_OF_AIRSPEED_IGAIN" value="0.0"/>
<!-- extra's -->
<define name="AUTO_PITCH_OF_AIRSPEED_PGAIN" value="0.0"/>
<define name="AUTO_PITCH_OF_AIRSPEED_IGAIN" value="0.0"/>
<define name="AUTO_PITCH_OF_AIRSPEED_DGAIN" value="0.0"/>
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="m/s/s"/>
<!--define name="AUTO_GROUNDSPEED_SETPOINT" value="15." unit="m/s"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0"/-->
</section>
<!-- ************************* MISC ************************* -->
<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="CLIMB_AIRSPEED" value="14." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="12." unit="m/s"/>
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>
<define name="STALL_AIRSPEED" value="10." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<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="0.75" unit="seconds"/>
<define name="HEADING_DELAY" value="3.0" unit="seconds"/>
<define name="ACCELERATION_THRESHOLD" value="1.75"/>
<define name="INITIAL_PITCH" value="15.0" unit="deg"/>
<define name="INITIAL_THROTTLE" value="1.0"/>
</section>
<section name="GLS_APPROACH" prefix="APP_">
<define name="ANGLE" value="5" unit="deg"/>
<define name="INTERCEPT_AF_SD" value="10" unit="m"/>
<define name="TARGET_SPEED" value="13" unit="m/s"/>
</section>
<section name="DIGITAL_CAMERA" prefix="DC_">
<define name="AUTOSHOOT_PERIOD" value="1.5" unit="sec"/>
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="50" unit="meter"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="JSBSIM_MODEL" value="Malolo1" type="string"/>
<define name="COMMANDS_NB" value="4"/>
<define name="ACTUATOR_NAMES" value="throttle-cmd-norm, aileron-cmd-norm, elevator-cmd-norm, rudder-cmd-norm" type="string[]"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="JS_AXIS_MODE" value="4"/>
<define name="BYPASS_AHRS" value="TRUE"/>
<define name="BYPASS_INS" value="TRUE"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
+270
View File
@@ -0,0 +1,270 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
* Psi a slightly modified Parrot AR.Drone 2.0 (http://www.openuas.org/)
+ uBlox LEA5H and Sarantel helix GPS antenna
NOTES:
+ Original ballbearings replaced with real ball bearings for all axis
+ Frontcamera movable by servo on debug port - optional
+ Spektrum RX DSMX clone on debug port - optional
+ Iridium 9603N - optional
+ Flies on INDI control
-->
<airframe name="Psi">
<firmware name="rotorcraft">
<target name="ap" board="ardrone2">
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/>
<!--<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>-->
<define name="BAT_CHECKER_DELAY" value="50"/>
<!-- amount of time it take for the bat to check -->
<!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="50"/><!-- in seconds-->
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
</target>
<define name="USE_SONAR" value="TRUE"/>
<!--<define name="USE_UART2"/>-->
<!--<define name="DEBUG_NMEA"/>-->
<!-- <define name="DEBUG_SIRF"/>-->
<!-- Subsystem section -->
<subsystem name="telemetry" type="transparent_udp"/>
<subsystem name="radio_control" type="datalink"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="ardrone2"/>
<subsystem name="imu" type="ardrone2"/>
<subsystem name="gps" type="ublox"/>
<!--<subsystem name="gps" type="nmea"/>-->
<!-- for testing parrot dongele enablethis-->
<!-- <subsystem name="gps" type="sirf">-->
<!--<configure name="UART2_DEV" value="UART2"/>-->
<!--<configure name="GPS_PORT" value="UART2_DEV"/>-->
<!-- <configure name="GPS_BAUD" value="B57600"/>-->
<!-- </subsystem> -->
<subsystem name="stabilization" type="indi"/>
<subsystem name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</subsystem>
<subsystem name="ins" type="extended"/>
</firmware>
<modules main_freq="512">
<load name="bat_voltage_ardrone2.xml"/>
<load name="gps_ubx_ucenter.xml"/>
<load name="send_imu_mag_current.xml"/>
<load name="air_data.xml"/>
<load name="logger_file.xml"/>
</modules>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="3000"/>
</commands>
<servos driver="Default">
<servo name="TOP_LEFT" no="0" min="0" neutral="1" max="500"/>
<servo name="TOP_RIGHT" no="1" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_RIGHT" no="2" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_LEFT" no="3" min="0" neutral="1" max="500"/>
</servos>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<!-- Time cross layout (X), with order NW (CW), NE (CCW), SE (CW), SW (CCW) -->
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<!-- Accelero -->
<define name="ACCEL_X_NEUTRAL" value="2048"/>
<define name="ACCEL_Y_NEUTRAL" value="2048"/>
<define name="ACCEL_Z_NEUTRAL" value="2048"/>
<!-- Magneto calibration for this specific airframe TODO-->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="-180"/>
<define name="MAG_X_SENS" value="16." integer="16"/>
<define name="MAG_Y_SENS" value="16." integer="16"/>
<define name="MAG_Z_SENS" value="16." integer="16"/>
<!-- Magneto current calibration TODO -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
<!-- TODO should be zeros in ideal scenario -->
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- Local Magnetic field NL Testfield-->
<!--
<define name="H_X" value="0.382478"/>
<define name="H_Y" value="0.00563406"/>
<define name="H_Z" value="0.923948"/>
-->
<!-- Local Magnetic field DE Testfield -->
<define name="H_X" value="0.403896"/>
<define name="H_Y" value="0.012277"/>
<define name="H_Z" value="0.914723"/>
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="180" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
</section>
<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.032"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0032"/>
<define name="G2_R" value="0.16"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="380.0"/>
<define name="REF_ERR_Q" value="380.0"/>
<define name="REF_ERR_R" value="250.0"/>
<define name="REF_RATE_P" value="21.6"/>
<define name="REF_RATE_Q" value="21.6"/>
<define name="REF_RATE_R" value="21.0"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="20.0"/>
<define name="FILT_ZETA" value="0.55"/>
<define name="FILT_OMEGA_R" value="20.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="13"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;nw_motor&quot;, &quot;ne_motor&quot;, &quot;se_motor&quot;, &quot;sw_motor&quot;}"/>
<define name="JSBSIM_MODEL" value="&quot;simple_ardrone2&quot;"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_ardrone2.h&quot;"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<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_NAV"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
+376
View File
@@ -0,0 +1,376 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- Graupner Taxi III electro (http://www.graupner.de/)
TINY (http://paparazzi.enac.fr/wiki/index.php/)
* Aligned Infrared sensor for X,Y,Z
* Various options to connect XBee XSC 900Mhz or RFD900A or RFD868+
* GPS uBlox LEA5H
* 35Mhz CPPM receiver
Notes:
* The two aileron servos are connected via a Y-split cable and on
one actuator out connection on the board, no differential aileron possible :(
-->
<airframe name="TaxiIII">
<firmware name="fixedwing">
<target name="sim" board="pc"/>
<target name="ap" board="tiny_2.11"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="AGR_CLIMB"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="USE_I2C0"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<subsystem name="radio_control" type="ppm">
<!-- for debugging PPM value the one below -->
<!-- <define name="TELEMETRY_MODE_FBW" value="1"/> -->
</subsystem>
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_PORT" value="UART1"/>
</subsystem>
<subsystem name="control"/>
<subsystem name="ins" type="alt_float"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<!-- for setting values e.g. IR tuning via RC Tranmitter -->
<!-- <subsystem name="settings" type="rc"/>-->
</firmware>
<modules>
<load name="gps_ubx_ucenter.xml"/>
<load name="infrared_adc.xml"/>
<load name="ahrs_infrared.xml"/>
<!--
<load name="sys_mon.xml"/>
-->
<!--
<load name="adc_generic.xml">
-->
<!-- Voltage measuring sensor -->
<!--
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_3"/>
-->
<!-- RPM measuring sensor -->
<!--
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_4"/>
-->
<!-- Current measuring sensor -->
<!--
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_7"/>
</load>
-->
</modules>
<!-- Define here to which CONNECTOR NUMBER the servo is connected to, on the autopilot cicuit board -->
<servos>
<!-- Make sure esc is set to fixed endpoints, e.g.CastleCreastions range fixed is 1250ms - 1800ms -->
<servo name="MOTOR" no="0" min="1250" neutral="1300" max="1850"/>
<servo name="AILERON" no="2" min="1900" neutral="1500" max="1100"/>
<servo name="ELEVATOR" no="3" min="1100" neutral="1500" max="1900"/>
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
</servos>
<!-- commands section -->
<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"/>
<!-- for tuning via RC these ones below -->
<!--
<axis name="GAIN1" failsafe_value="0"/>
<axis name="CALIB" 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"/>
<!-- for tuning via RC these ones below -->
<!--
<set command="GAIN1" value="@GAIN1"/>
<set command="CALIB" value="@CALIB"/>
-->
</rc_commands>
<auto_rc_commands>
<!-- To still be able to use rudder, which is needed with sidewind landing in auto1 stabilization mode only YAW -->
<set command="YAW" value="@YAW"/>
<!-- for tuning via RC these ones below -->
<!--
<set command="GAIN1" value="@GAIN1"/>
<set command="CALIB" value="@CALIB"/> -->
</auto_rc_commands>
<!--For mixed controlflaps -->
<section name="MIXER">
<!-- just a tiny bit works well-->
<define name="ASSIST_ROLL_WITH_RUDDER" value="0.09"/>
</section>
<command_laws>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILERON" value="@ROLL"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW - @ROLL*ASSIST_ROLL_WITH_RUDDER"/>
</command_laws>
<!-- Do not set MAX_ROLL, MAX_PITCH to small of a value, otherwise one can NOT control the plane very well manually -->
<!-- If you have dual rate swith it of with same swtch as mode switch thus auto1 means dualrate is switched off also -->
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.95"/> <!-- radians -->
<define name="MAX_PITCH" value="0.95"/> <!-- radians -->
<!-- Or use as below -->
<!-- <define name="MAX_ROLL" value="RadOfDeg(95)"/> -->
<!-- <define name="MAX_PITCH" value="RadOfDeg(95)"/> -->
</section>
<section name="INFRARED" prefix="IR_">
<!-- NEUTRAL value below set via caliberation with all sensors covert and intill set to 0 the read via telemetry data and in this case 515 etc filled in later and reuploaded -->
<!-- In this plane IR1 points to side to side, the latereal axis -->
<!-- In this plane IR2 points to front and back, the longitudinal axis -->
<!--Reminder: reads X if value=0 is uploaded in airframe -->
<define name="ADC_IR1_NEUTRAL" value="512"/>
<!--Reminder: reads X if value=0 is uploaded in airframe -->
<define name="ADC_IR2_NEUTRAL" value="512"/>
<!--Reminder: reads X if value=0 is uploaded in airframe -->
<define name="ADC_TOP_NEUTRAL" value="512"/>
<!-- old way
<define name="CORRECTION_UP" value="1.0"/>
<define name="CORRECTION_DOWN" value="1.0"/>
<define name="CORRECTION_LEFT" value="1.0"/>
<define name="CORRECTION_RIGHT" value="1.0"/>
-->
<!-- =============== possible new values ========================= -->
<!-- <define name="DEFAULT_CONTRAST" value="200"/> -->
<!-- <define name="RAD_OF_IR_CONTRAST" value="0.75"/> -->
<!-- <linear name="RollOfIrs" arity="2" coeff1="0.7" coeff2="-0.7"/> -->
<!-- <linear name="PitchOfIrs" arity="2" coeff1="0.7" coeff2="0.7"/> -->
<!-- <linear name="TopOfIr" arity="1" coeff1="-1"/> -->
<!-- <define name="RAD_OF_IR_MAX_VALUE" value="0.0045"/> -->
<!-- <define name="RAD_OF_IR_MIN_VALUE" value="0.00075"/> -->
<!-- ============== possible new values end ===================== -->
<!-- The three axis must give similar values for similar air to ground contrasts. -->
<!-- If you e.g. have a different brand of IR piles for straight up n down sensors. -->
<define name="LATERAL_CORRECTION" value="0.8"/> <!-- was in the past 360_LATERAL_CORRECTION -->
<define name="LONGITUDINAL_CORRECTION" value="0.8"/> <!-- was in the past 360_LONGITUDINAL_CORRECTION -->
<!-- One can set the top down correction a little lower so leftrightfrontback is more accurate n faster -->
<define name="VERTICAL_CORRECTION" value="1.1"/> <!-- was in the past 360_VERTICAL_CORRECTION -->
<!-- ONLY enable the line below if the sensor is ALIGENED front to back, side to side. Thus not 45deg rotated, and Disable the TILTED LINE -->
<define name="HORIZ_SENSOR_ALIGNED" value="1"/>
<!-- ONLY enable the line below if the sensor is TILTED, and Disable the ALIGENED LINE -->
<!-- <define name="HORIZ_SENSOR_TILTED" value="1"/> -->
<!-- Ground(=Hotter than sky) on right side of airframe as seen from back -->
<!-- The Hotter side must give a positive value maybe -->
<!-- In this airframe IR1 points to front and side, the latereal AND longitudinal axis -->
<define name="IR1_SIGN" value="-1"/>
<!-- In this airframe IR2 points to front and side, the latereal AND longitudinal axis -->
<define name="IR2_SIGN" value="-1"/>
<define name="TOP_SIGN" value="1"/>
<!-- below is very important per individual airframe, first set to 0,
then adjusted after testflight data is analyzed.
Setting also can be adjusted realtime via tuning config
or tuning_via?_transmitter config.
-->
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
</section>
<section name="BAT">
<!-- If current-volts sensor is installed use line below-->
<!-- <define name="ADC_CHANNEL_CURRENT" value="ADC_3" /> -->
<!-- <define name="MilliAmpereOfAdc(adc)" value="(adc*88)"/> -->
<!-- <define name="ADC_CHANNEL_VOLTAGE" value="ADC_4" /> -->
<!-- The real multiplier is unknown we take 2 as test example -->
<!-- <define name="VoltageOfAdc(adc)" value ="(adc*2)"/> -->
<!-- If NO current-volts sensor installed uncomment below -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="18000" unit="mA"/>
<!--
<define name="VOLTAGE_ADC_A" value="0.0177531"/>
<define name="VOLTAGE_ADC_B" value="0.173626"/>
<define name="VoltageOfAdc(adc)" value ="(VOLTAGE_ADC_A * adc + VOLTAGE_ADC_B)"/>
-->
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/> <!-- 3S lipo 3.1*3=9.3 -->
<define name="CRITIC_BAT_LEVEL" value="10.0" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.6" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/> <!-- 3S lipo 4.2*3=12.6 -->
</section>
<section name="MISC">
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="14." 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="CONTROL_FREQUENCY" value="60" unit="Hz"/>-->
<!--UNLOCKED_HOME_MODE if set to TRUE means that HOME mode does not get stuck.
If not set before when you would enter home mode you had to flip a bit via the GCS to get out. -->
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
<!-- RC_LOST_MODE means that if your RC Transmitter signal is not received anymore in the autopilot, e.g. you switch it off
or fly a long range mission you define the wanted mode behaviour here.
If you do not define it, it defaults to flying to the flightplan HOME -->
<define name="RC_LOST_MODE" value="PPRZ_MODE_AUTO2"/>
<!-- OLD <define name="ALT_KALMAN_ENABLED" value="TRUE"/>-->
<define name="TRIGGER_DELAY" value="1.0"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="70.0"/>
<define name="MIN_CIRCLE_RADIUS" value="50.0"/><!-- needed for some nav modules like spiral-->
<!-- The Glide definitions are used for calculating the touch down point during auto landing -->
<!-- <define name="GLIDE_AIRSPEED" value="11."/>
<define name="GLIDE_VSPEED" value="1." unit="m/s"/>
<define name="GLIDE_PITCH" value="7." unit="deg"/>-->
</section>
<!-- ******************* VERTICAL CONTROL ******************************** -->
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.06"/> <!--unit="(m/s)/m"-->
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2." unit="m/s"/>
<!-- auto throttle inner loop -->
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.85" unit="%"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.65" unit="%"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.99" unit="%"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000" unit="pprz_t"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-2000" unit="pprz_t"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.0007" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.002"/>
<define name="AUTO_THROTTLE_DGAIN" value="0.0"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.2" unit="rad/(m/s)"/>
<define name="THROTTLE_SLEW_LIMITER" value="0.8" unit="s"/>
<!-- NOT YET USED auto airspeed and altitude inner loop -->
<!-- <define name="AIRSPEED_ETS_OFFSET" value="1542"/> -->
<!-- NEVER set AUTO_AIRSPEED_SETPOINT lower than airframe stall speed -->
<!--
<define name="AUTO_AIRSPEED_SETPOINT" value="19.0" unit="m/s"/>
<define name="AUTO_AIRSPEED_PGAIN" value="0.1"/>
<define name="AUTO_AIRSPEED_IGAIN" value="0.05"/>
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0" unit="degree/(m/s)"/>
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0" unit="%/(m/s)"/>
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0"/>
-->
<!-- investigate: if higher _AIRSPEED_SETPOINT then airframe tries to maintain a constand ground speed UNKNOWN -->
<!--
<define name="AUTO_GROUNDSPEED_SETPOINT" value="14.0" unit="m/s"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/>
-->
<!-- auto pitch inner loop -->
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="0.052"/>
<define name="AUTO_PITCH_IGAIN" value="0.065"/>
<define name="AUTO_PITCH_MAX_PITCH" value="0.45"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-0.40"/>
<!-- <define name="THROTTLE_SLEW" value="0.3"/> --> <!-- limiter for powerfull engines -->
<!-- pitch trim -->
<!-- not used for now -->
<!-- <define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>-->
</section>
<!-- ******************* HORIZONTAL CONTROL ******************************** -->
<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>
<!-- ***************************** AGGRESIVE ******************************* -->
<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="8"/> <!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
<define name="CLIMB_THROTTLE" value="0.90"/> <!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="RadOfDeg(45)"/> <!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.4"/> <!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="RadOfDeg(-30)"/> <!-- 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="0.99"/>
</section>
<!-- ****************************** FAILSAFE ******************************* -->
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0" unit="%"/>
<define name="DEFAULT_ROLL" value="0.15" unit="rad"/>
<define name="DEFAULT_PITCH" value="-0.1" unit="rad"/>
<define name="HOME_RADIUS" value="70" unit="m"/>
</section>
<!-- ****************************** DATALINK ******************************* -->
<section name="DATALINK" prefix="DATALINK_">
<define name="DEVICE_TYPE" value="PPRZ"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<!-- ******************************** SIMU ********************************* -->
<section name="SIMU">
<define name="YAW_RESPONSE_FACTOR" value="0.5"/> <!-- a to low of a value gives bad simulation results -->
</section>
</airframe>
@@ -1,5 +1,5 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<!-- This is the Flightplan of Team OpenUAS from the Netherlands for use in the
<!-- This is the Flightplan of Team OpenUAS for use in the
Australian UAV Outback Challenge of 2014.
Read about this challenge here:
@@ -52,6 +52,8 @@ TESTS:
//Set Generic options
#include "autopilot.h"
//Enable AHRS Health test functions
#include "subsystems/ahrs/ahrs_aligner.h"
//Enable advanced electrical power functions
#include "subsystems/electrical.h"
//Enable datalink tests
@@ -184,7 +186,7 @@ TST-3 = -26° 35' 23.2" * 151° 50' 45.9"
<!-- IDEA Close the hatch so not able to insert payload before there is a 3D fix , however maybe not so handy anyhow since we need to wat be fre we can insert-->
<!-- <set value="NavDropCloseHatch" var="unit"/> -->
<!-- if no valid fix or gps accuracy> 15m or no AHRS , it a no-go wait-->
<while cond="!GpsFixValid() || gps.pacc > 1500 || !(stateIsAttitudeValid())"/>
<while cond="!GpsFixValid() || gps.pacc > 1500 || stateIsAttitudeValid()"/>
</block>
<!-- *********** Set the ground reference height and the home position *********** -->
@@ -315,7 +317,7 @@ to “Airfield Home” and orbit for either a landing or regain of Data Link.
***************************************************** -->
<!-- maybe a HelperWaypoint to gettart n return from a mission Tracking to EL1
<set value="0" var="ap_state->commands[COMMAND_CAMBER]"/>
<set value="0" var="ap_state->commands[COMMAND_CAMBER]"/>-->
<!-- *********** Track to EL-1 *********** -->
<block name="EntryLane1" strip_button="Joe" strip_icon="lookdown.png" group="Mission">
@@ -0,0 +1,141 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="300" ground_alt="200" lat0="50.799999" lon0="7.566666" max_dist_from_home="1500" name="Basic" security_height="25">
<header>
#include "subsystems/datalink/datalink.h"
#include "modules/digital_cam/dc.h"
#define LINE_START_FUNCTION dc_Survey(40);
#define LINE_STOP_FUNCTION dc_autoshoot = DC_AUTOSHOOT_STOP;
</header>
<waypoints>
<waypoint name="HOME" x="0" y="0"/>
<waypoint name="STDBY" x="49.5" y="100.1"/>
<waypoint name="1" x="10.1" y="189.9"/>
<waypoint name="2" x="132.3" y="139.1"/>
<waypoint name="MOB" x="137.0" y="-11.6"/>
<waypoint name="S1" x="-109.0" y="245.9"/>
<waypoint name="S2" x="274.4" y="209.5"/>
<waypoint name="S3" x="322.1" y="29.9"/>
<waypoint name="S4" x="0.8" y="-68.1"/>
<waypoint name="S5" x="-239.9" y="81.8"/>
<waypoint alt="215.0" name="AF" x="177.4" y="45.1"/>
<waypoint alt="185.0" name="TD" x="28.8" y="57.0"/>
<waypoint name="_BASELEG" x="168.8" y="-13.8"/>
<waypoint name="CLIMB" x="-114.5" y="162.3"/>
</waypoints>
<sectors>
<sector name="POLY_SURVEY" color="green">
<corner name="S1"/>
<corner name="S2"/>
<corner name="S3"/>
<corner name="S4"/>
<corner name="S5"/>
</sector>
</sectors>
<exceptions/>
<blocks>
<block name="Wait GPS">
<set value="1" var="kill_throttle"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 10)"/>
<call fun="NavSetGroundReferenceHere()"/>
</block>
<block name="Holding point">
<set value="1" var="kill_throttle"/>
<attitude roll="0" throttle="0" vmode="throttle"/>
</block>
<block group="home" key="t" name="Takeoff" strip_button="Takeoff (wp CLIMB)" strip_icon="takeoff.png">
<exception cond="GetPosAlt() > GetAltRef()+25" deroute="Standby"/>
<set value="0" var="kill_throttle"/>
<set value="0" var="autopilot_flight_time"/>
<go from="HOME" pitch="15" throttle="1.0" vmode="throttle" wp="CLIMB"/>
</block>
<block group="home" key="Control+a" name="Standby" strip_button="Standby" strip_icon="home.png">
<circle radius="nav_radius" wp="STDBY"/>
</block>
<block group="base_pattern" key="F8" name="Figure 8 around wp 1" strip_button="Figure 8 (wp 1-2)" strip_icon="eight.png">
<eight center="1" radius="nav_radius" turn_around="2"/>
</block>
<block group="base_pattern" name="Oval 1-2" strip_button="Oval (wp 1-2)" strip_icon="oval.png">
<oval p1="1" p2="2" radius="nav_radius"/>
</block>
<block group="base_pattern" name="MOB" strip_button="Turn around here" strip_icon="mob.png">
<call fun="NavSetWaypointHere(WP_MOB)"/>
<set value="DEFAULT_CIRCLE_RADIUS" var="nav_radius"/>
<circle radius="nav_radius" wp="MOB"/>
</block>
<block group="extra_pattern" name="Line 1-2" strip_button="Line (wp 1-2)" strip_icon="line.png">
<call fun="nav_line_setup()"/>
<call fun="nav_line_run(WP_1, WP_2, nav_radius)"/>
</block>
<block group="extra_pattern" name="Survey S1-S3" strip_button="Survey (wp S1-S3)" strip_icon="survey.png">
<survey_rectangle grid="150" wp1="S1" wp2="S3"/>
</block>
<!--===================== Nav modules example blocks =================================-->
<block name="Bungee take-off">
<call fun="nav_bungee_takeoff_setup(WP_HOME)"/>
<call fun="nav_bungee_takeoff_run()"/>
</block>
<block group="nav_pattern" name="Poly Survey" strip_button="Poly Survey">
<call fun="nav_survey_polygon_setup(WP_S1,5,80,30,10,50,GetAltRef()+60)"/>
<call fun="nav_survey_polygon_run()"/>
</block>
<block group="nav_pattern" name="Border line 1-2" strip_button="Border Line">
<call fun="nav_line_border_setup()"/>
<call fun="nav_line_border_run(WP_1, WP_2, nav_radius)"/>
</block>
<block group="nav_pattern" name="Smooth nav (wp 1-2)" strip_button="Smooth nav">
<set var="snav_desired_tow" value="gps.tow / 1000. + 60."/>
<call fun="snav_init(WP_1, M_PI_2-atan2(WaypointY(WP_2)-WaypointY(WP_1),WaypointX(WP_2)-WaypointX(WP_1)), DEFAULT_CIRCLE_RADIUS/2.)"/>
<call fun="snav_circle1()"/>
<call fun="snav_route()"/>
<call fun="snav_circle2()"/>
<call fun="snav_on_time(DEFAULT_CIRCLE_RADIUS)"/>
<go from="1" hmode="route" wp="2"/>
<deroute block="Standby"/>
</block>
<block group="nav_pattern" name="Flower (wp 1-2)" strip_button="Flower">
<call fun="nav_flower_setup(WP_1, WP_2)"/>
<call fun="nav_flower_run()"/>
</block>
<block name="Poly survey osam">
<call fun="nav_survey_poly_osam_setup(WP_S1, 5, 100, 45)"/>
<call fun="nav_survey_poly_osam_run()"/>
</block>
<block name="Flight Line block">
<call fun="nav_line_osam_block_run(WP_S1, WP_S5, nav_radius, 30, 10)"/>
</block>
<block name="Vertical Raster">
<call fun="nav_vertical_raster_setup()"/>
<call fun="nav_vertical_raster_run(WP_S1, WP_S2, nav_radius, 50)"/>
</block>
<!--====================================================================================-->
<block group="land" name="Land Right AF-TD" strip_button="Land right (wp AF-TD)" strip_icon="land-right.png">
<set value="DEFAULT_CIRCLE_RADIUS" var="nav_radius"/>
<deroute block="land"/>
</block>
<block group="land" name="Land Left AF-TD" strip_button="Land left (wp AF-TD)" strip_icon="land-left.png">
<set value="-DEFAULT_CIRCLE_RADIUS" var="nav_radius"/>
<deroute block="land"/>
</block>
<block name="land">
<call fun="nav_compute_baseleg(WP_AF, WP_TD, WP__BASELEG, nav_radius)"/>
<circle radius="nav_radius" until="NavCircleCount() > 0.5" wp="_BASELEG"/>
<circle radius="nav_radius" until="And(NavQdrCloseTo(DegOfRad(baseleg_out_qdr)-(nav_radius/fabs(nav_radius))*10), 10 > fabs(GetPosAlt() - WaypointAlt(WP__BASELEG)))" wp="_BASELEG"/>
</block>
<block name="final">
<exception cond="GetAltRef() + 10 > GetPosAlt()" deroute="flare"/>
<go from="AF" hmode="route" vmode="glide" wp="TD"/>
</block>
<block name="flare">
<go approaching_time="0" from="AF" hmode="route" throttle="0.0" vmode="throttle" wp="TD"/>
<attitude roll="0.0" throttle="0.0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
@@ -5,18 +5,25 @@ It should be useable for UAS enthousiasts just starting in the field of autonomo
This flightplan should be kept as simple as possible and *not* to be extended with more functionality, if one needs that, plz use another flightplan.
For you first flights make sure you have more dan enough space and do not make decisions that would be unwise, you have a brain, best to put it to good use ;)
Your aircraft is your responsibility
Your safe aircraft operation is *your* responsibility
-->
<!-- Default flightplan alt set to 30m. This hight makes it fly over most of trees in this world by default. Security height 15m a tradeof between telemetry loss, airframe damage and avarage small building and hill height -->
<flight_plan alt="30" ground_alt="0" lat0="50.726999" lon0="7.567305" max_dist_from_home="100" name="Parrot Simple" security_height="15">
<flight_plan alt="230" ground_alt="200" lat0="50.799999" lon0="7.566666" max_dist_from_home="100" name="Parrot Simple" security_height="15">
<header>
#include "autopilot.h"
#include "subsystems/ahrs.h"
#include "subsystems/electrical.h"
#include "subsystems/datalink/datalink.h"
//Set Generic options
#include "autopilot.h"
//Enable AHRS Health test functions
#include "subsystems/ahrs/ahrs_aligner.h"
//Enable advanced electrical power functions
#include "subsystems/electrical.h"
//Enable datalink tests
#include "subsystems/datalink/datalink.h"
#include "firmwares/rotorcraft/guidance/guidance_v.h"
</header>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="_CLIMB" x="0.0" y="5.0"/>
@@ -43,8 +50,8 @@ Your aircraft is your responsibility
<block name="Setting home location"><!-- TODO: make sure there is an indicator in "ardrone2_simple.xml" GCS layout config screen displaying "Waiting for GPS position..."-->
<call fun="NavKillThrottle()"/>
<!-- if no valid fix or GPS accuracy > 11m or no AHRS , it's' a no-go, just wait TODO: timeout and message?-->
<!-- <while cond="!GpsFixValid() || gps.pacc > 1600 || !(ahrs.status == AHRS_RUNNING)"/>-->
<while cond="!GpsFixValid() || gps.pacc > 1100"/>
<!-- <while cond="!GpsFixValid() || gps.pacc > 1100 || stateIsAttitudeValid()"/>-->
<while cond="!GpsFixValid()"/>
<!-- Additional wait to allow for better GPS data in the last secons before takeoff -->
<while cond="LessThan(NavBlockTime(), 8)"/>
<call fun="NavSetGroundReferenceHere()"/>
@@ -129,10 +136,11 @@ Altough Switching the mode to auto2/NAV from any other mode will reset nav_headi
<!--TODO: better test detect landing different surfaces and agles with sonar baro combi of AR-Drone 2 -->
<call fun="NavStartDetectGround()"/>
<!--TODO: this is a throttle level for ARDrone2, should be nominaltrhrootle devided by 2 or so-->
<stay wp="_TDEMERGENCY" throttle="0.40" vmode="throttle"/>
<stay wp="_TDEMERGENCY" throttle="0.40" vmode="throttle"/> <!-- 0.40 is for AR.Drone 2.0 Bebop could be a lower value -->
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
</blocks>
</flight_plan>
@@ -0,0 +1,341 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<!--
This fightplan is designed to aid in tuning default control loops on a fixed wing aircraft. It should work in both simulation and for real flights, provided the main information is changed and waypoints are adapted to a suitable location for your airspace. The airspeed tuning may not work correctly in simulation **CHECK IT**!.
This flightplan is designed to be used in the first parts of the tuning process, and does NOT contain a landing block. It is likely extensive use of manual and auto1 modes are required. Ensure you are comfortable with manual flight, stall recovery, spin recovery, power-on landings, deadstick landings etc. Also ensure you do not fly beyond R/C range.
Since it is likely the aircraft is not tuned, do NOT rely on any stabilization or navigation features. For example, the STANDBY block may not work properly if the control loops are unstable. In addition, the flightplan blocks used to tune loops will not bring the aircraft back and will often let the aircraft continue on a straight course indefinitely. They may also allow unlimited climbs or descents.
This flightplan was inspired by versatile.xml. For further information about flightplans, visit:
http://paparazziuav.org/wiki/Flight_Plans
When obtaining values, sometimes they can be gleaned from standard GCS display widgets, but better is to use the realtime plotter and the average functionality or visually estimate from the plotter.
You will probably need at least two people (one pilot, one GCS operator; a spotter and/or data recorder may help as well).
It is expected the airframe file contain most default parameters. In addition, this tuning assumes some flags are NOT set, in particular AGR_CLIMB and STRONG_WIND.
Most controllers for the aircraft are PID controllers with variations. Most common, there is no D term and sometimes no I term. Some controllers implement ramping, feed-forward, etc. A good review of PID control loops and tuning methodology is available on Wikipedia:
http://en.wikipedia.org/wiki/PID_controller
After preliminary tuning, fine tuning will undoubtedly help your aircraft perform better. The Flight Benchmark module is useful for this process:
http://paparazziuav.org/wiki/FlightBenchmark
See http://paparazziuav.org/wiki/Tuning first for more information and to get started.
Tuning Procedure:
1. Try some manual flights, adjust trim mechanically and in the airframe file for nominal aircraft cruise speed. Make sure the GPS, datalink and others sensors are in correct working order. During the flight(s), record the following information:
a. V_CTL_AUTO_THROTTLE_(NOMINAL|MIN|MAX)_CRUISE_THROTTLE and V_CTL_AUTO_THROTTLE_(LOITER|DASH)_TRIM
-Fly straight and level at the nominal cruise, where the aircraft is trimmed properly, and write down the throttle setting and airspeed (if available from an airspeed sensor) or groundspeed. Ground speed will be affected by wind, but try to make a good guess by flying in different directions. Adjust any trims mechanically and/or in airframe file if this hasn't been done.
-Fly straight and level at a low speed, but still comfortably above stall (i.e. the lowest speed you would want the aircraft to loiter at), then trim the aircraft in pitch (up) to maintain altitude. Write down the throttle setting, speed and the trim of the pitch (look at COMMANDS:values[0]).
-Same as before, but at the highest speed the aircraft can maintain level flight forward (without climbing) and the highest speed you would like the aircraft to travel. Trim the aircraft in pitch (down) to maintain constant altitude. Write down the throttle setting, speed and pitch trim as before.
b. INS_(ROLL|PITCH)_NEUTRAL_DEFAULT (or IR_*)
-Fly straight and level at nominal cruise throttle after mechanical trims have been set and write down the pitch and roll readings.
c. AUTO1_MAX_(ROLL|PITCH) and H_CTL_(ROLL|PITCH)_(MAX|MIN)_SETPOINT
-Fly the aircraft through a series of banked turns (same altitude) with an aggressiveness you are comfortable with, and you feel the aircraft can handle. More aggressive means faster autopilot response. Write down the average maximum roll values (will need to visually check).
-Fly the aircraft through a series of short and longer climbs and descents, primarily using the elevator to induce pitch changes (as opposed to throttle). Write down the maximum corrective and climb/descent pitches observed.
-NOTE: If your radio is not producing 1000us - 2000us pulses over the full stick range (i.e. maximum throw usually, full rates) then it is likely your radio will never make the auto1 setpoints reach their maximum value. Either adjust radio settings, airframe file and radio file to ensure full range, or increase the maximum auto1 pitch and roll to account for this. Otherwise, you may have trouble having sufficient control authority in auto1.
d. DEFAULT_CIRCLE_RADIUS and HOME_RADIUS
-Fly the aircraft continuous in circles. Try to find a comfortable diameter that isn't difficult to maintain, but is small enough the aircraft doesn't fly far away during circles. Lean towards a larger diameter. Check approximate diameter by plotting NAVIGATION:pos_x and NAVIGATION:pos_y and looking at the amplitude of the sinusoids generated during the circles.
e. FAILSAFE_(DEFAULT_THROTTLE|DEFAULT_ROLL|DEFAULT_PITCH)
-Fly the aircraft in a gentle circle slowly with a slow (<1m/s) descent. Write down the pitch, roll and throttle. You should not have to correct pitch, roll or throttle very much during this action. In the event of the failsafe mode kicking in, and you want your aircraft to survive, envision the aircraft descending in this manner to the ground. Feel free to adjust to a different pattern if required (full dive for quick kill or straight and level descent if you have an extremely large flight region).
f. ALTITUDE_MAX_CLIMB and AGR_(CLIMB|DESCENT)_(THROTTLE|PITCH)
-Fly the aircraft at a constant average climb rate both up and down, and write down the average climb rate. Be sure the same value is comfortable for both climbs and descents
-Fly the aircraft at a constant aggressive climb rate, both up and down, and write down the pitch and throttle settings for both up and down. The aggressive climbs and descents may have different settings, depending on what looks reasonable.
After flying and trimming the aircraft, and recording the various parameters for the trimmed aircraft, land and update the airframe file. Use judgement when supplying values to the airframe file. For the INS_(ROLL|PITCH)_NEUTRAL_DEFAULT, put the negative of the recorded value in the airframe file.
2. Use auto1 to do the pitch/roll stabilization loop tuning. (In simulation, try it with the block Sim Pitch Roll Tuning)
WARNING: The Sim Pitch Roll Tuning block will undoubtedly cause a runaway aircraft with no altitude control if used and left on. Best if only used in simulation, and use auto1 in real flight testing.
a. Fly to a safe altitude and start a pass at cruise throttle in front of the pilot.
b. Switch to auto1 and immediately check if you can turn (roll) left AND right, and if you can pitch up and down. Be prepared to immediately take back manual control if something goes wrong (i.e. sudden dive or roll). If the response is extremely sluggish, you may need to increase gains (try double) or the max pitch/roll in auto1 may need to be increased.
c. Fly at cruise and adjust ROLL_ATTITUDE_GAIN (or ROLL_PGAIN). Increase the gain (more negative) if the response is sluggish, and decrease the gain if the aircraft oscillates in roll. The goal is to get the aircraft to have fast response without oscillating. It may help to use the realtime plotter and adjust ATTITUDE:phi and DESIRED:roll together. If the aircraft is behaving, attempt some aggressive (i.e. step) setpoint changes and watch the response on the realtime plot. Also, you may try adjusting the ROLL_RATE_GAIN. Try varying the speed to ensure the control is reasonable over the aircrafts speed range.
d. Do the same as above for the pitch (PITCH_PGAIN, ATTITUDE:theta, DESIRED:pitch, PITCH_IGAIN, PITCH_DGAIN).
e. If the aircraft seems to drift a bit in roll or pitch, you may need to adjust the *_(ROLL|PITCH)_NEUTRAL_DEFAULT; check the attitude readout when the elevator and aileron are neutral. If changing the throttle seems to induce a bit of roll, you can try adjusting AILERON_OF_THROTTLE, but this is best fixed mechanically with engine mounting.
f. It is ideal if the aircraft does not climb or descend as a result of rolling the aircraft. In addition, the "bank and yank" method of heading control in Paparazzi requires up elevator in addition to roll to properly turn. Normally in flight, when an aircraft banks the nose will fall off (sink) without any additional pitch input. Even when maintaining level flight in pitch (i.e. pitch setpoint of 0), under the same velocity, the effective lifting area/vector of the aircraft is reduced, likely resulting in a descent. To counter this, the pitch control loop uses the ELEVATOR_OF_ROLL gain to increase the pitch setpoint (thereby increasing angle of attack and thus lift). In auto1, hold a constant bank (experiment with different magnitudes) and bbserve the aircraft and data from ESTIMATOR:z_dot and DESIRED:climb. Adjust the ELEVATOR_OF_ROLL until climb is zero in banked turns.
After completing this, your aircraft should be able to stabilize itself. However, higher level control loops may still be unstable, so don't count on the autopilot bringing your plane back yet.
In tuning the remainder of the control loops, the goal is to slowly move upwards in the hiearchy of control enabling different control loops as you go while attempting to decouple any untuned control loops. To do this, various flight modes will be used.
3. Tune the auto throttle climb loop
a. Fly to a safe altitude some distance away on a course such that the aircraft will fly by the pilot/GCS.
b. Activate the block Level Auto Throttle Tuning and switch to auto2 (optionally, use block Variable Auto Throttle Tuning, where climb is initialized to zero and adjustable in the GCS notebook settings with nav_climb).
c. Observe the aircraft and data from ESTIMATOR:z_dot and DESIRED:climb. The aircraft should remain wings level and near constant pitch, with the climb rate remaining at zero. If oscillations in climb rate, aircraft pitch, or throttle setting occur, reduce gains. There are a significant number of gains in the auto throttle control loop, and several may need to be adjusted. You may also experiment adjusting the cruise, dash and loiter values if previous tests aren't providing sufficient performance. If slower oscillations or climb rate is drifting from zero, consider increasing the gains for crisper response without causing oscillations.
d. Activate the blocks Ascent Auto Throttle Tuning and Descent Auto Throttle Tuning and repeat C realizing the climb rate should be a minimum or maximum as set with V_CTL_ALTITUDE_MAX_CLIMB (optionally, change the nav_climb value with the notebook settings instead).
e. Try changing between Loiter, Cruise and Dash throttle settings corresponding to V_CTL_AUTO_THROTTLE_(NOMINAL|MIN|MAX)_CRUISE_THROTTLE and ensure climb remains stable. Adjust gains if required as in C.
f. Ensure the aircraft switched to manual control as it passes and gets further away from the pilot, at the pilot's discretion. Turn and line up for another pass, and switch to auto2. The previous block should still be active.
g. To help with tuning, a climb rate other than that specified in the current block could be induced by the pilot just prior to switching to auto2 to check various climb rate setpoint step changes. This also helps if one is nervous about allowing the autopilot to command a steep descent. One can descend manually and then switch to auto2 when the Level Auto Throttle Tuning block is active, which will cause the autopilot to stop the aircraft descending.
4. Tune the auto pitch climb loop
a. Fly to a safe altitude some distance away on a course such that the aircraft will fly by the pilot/GCS.
b. Activate the block Level Auto Pitch Tuning and switch to auto2 (optionally, use block Variable Auto Pitch Tuning, where climb is initialized to zero and adjustable in the GCS notebook settings with nav_climb).
c. Observe the aircraft and data from ESTIMATOR:z_dot and DESIRED:climb. The aircraft should remain wings level, with the climb rate remaining at zero. If fast oscillations in climb rate occur, reduce gains. Consider increasing gains until just before the onset of oscillations.
d. Activate the blocks Ascent Auto Pitch Tuning and Descent Auto Pitch Tuning and repeat C realizing the climb rate should be a minimum or maximum as set with V_CTL_ALTITUDE_MAX_CLIMB (optionally, change the nav_climb value with the notebook settings instead).
e. Try changing between Loiter, Cruise and Dash throttle settings corresponding to V_CTL_AUTO_THROTTLE_(NOMINAL|MIN|MAX)_CRUISE_THROTTLE and ensure climb remains stable. Adjust gains if required as in C.
f. Ensure the aircraft switched to manual control as it passes and gets further away from the pilot, at the pilot's discretion. Turn and line up for another pass, and switch to auto2. The previous block should still be active.
g. To help with tuning, a climb rate other than that specified in the current block could be induced by the pilot just prior to switching to auto2 to check various climb rate setpoint step changes. This also helps if one is nervous about allowing the autopilot to command a steep descent. One can descend manually and then switch to auto2 when the Level Auto Throttle Tuning block is active, which will cause the autopilot to stop the aircraft descending. If the aircraft does not seem to stabilize at the desired climb rate while in Loiter or Dash throttle modes (i.e always climbs or descends with a 0.0 climb setpoint), chances are the settings for V_CTL_AUTO_THROTTLE_(LOITER|DASH)_TRIM are set incorrectly.
The climb loop(s) should now be sufficiently tuned, unless one wishes to use the airspeed loops. If you plan to use airspeed, please tune the airspeed loop, which replaces the traditional Auto Throttle control loop.
5. Tune the altitude loop
a. Fly to a safe altitude some distance away on a course such that the aircraft will fly by the pilot/GCS.
b. Activate the block Altitude Tuning and switch to auto2.
c. Observe the aircraft and data from ESTIMATOR:z and DESIRED:altitude. The aircraft should remain wings level, with a constant altitude equal to the altitude which the aircraft was at what the Altitude Tuning block was activated. If oscillations occur in altitude, reduce the altitude_pgain. If the aircraft very slowly drifts or doesn't reach altitude, increase gain until just before oscillations begin.
d. You can adjust the altitude setpoint in the notebook using the altitude slider under flight params. Check response to step changes in altitude setpoints and adjust gain as required.
e. Try changing between Loiter, Cruise and Dash throttle settings corresponding to V_CTL_AUTO_THROTTLE_(NOMINAL|MIN|MAX)_CRUISE_THROTTLE and ensure climb remains stable. Adjust gains if required as in C.
f. Ensure the aircraft switched to manual control as it passes and gets further away from the pilot, at the pilot's discretion. Turn and line up for another pass, and switch to auto2. The previous block should still be active.
Now, all of the vertical loops should be tuned decently. Finally, the course loop can be tuned.
6. Tune the course loop
a. Fly to a safe altitude on a course you wish the aircraft to attempt to follow. A good suggestion would be away from the pilot perpendicular to the flight line.
b. While flying this course, but being near the pilot/GCS, activate the block Course Tuning then switch to auto2. This will use the aircrafts current course at the moment of activating the Course Tuning block. Note that no altitude control will be enabled, only a fixed throttle setting.
c. When the aircraft starts getting far away (but before it leaves piloting range!) return to manual control and complete a pattern that will bring the aircraft across the front of the pilot/GCS approximately parallel to the flight line (i.e. perpendicular to the course setpoint). When the aircraft is approaching the pilot/GCS, switch back to auto2. The aircraft will attempt to match the desired heading.
d. When switching to auto2, observe the behaviour of the aircraft and ATTITUDE:psi and DESIRED:course. It should maintain the setpoint altitude and turn to the desired course. If the aircraft overshoots the course and oscillates back and forth, reduce the course_pgain in settings and/or adjust the course_dgain. If the aircraft is sluggish in meeting the desired course or doesn't quite reach the proper course, increase the gain. If the aircraft tends to lose altitude during the course correction, try increasing elevator_of_roll (for climbs, reduce the gain).
e. Repeat C as necessary to tune the loop for crisp response without oscillations. Preferably, begin the course changes from both directions. Also, one can induce setpoint changes under auto2 continuously by adjusting nav_course in the settings.
f. Experiment with Loiter and Dash throttle settings.
The primary control loops should now be decently tuned!
7. Try activating STANDBY
a. Now that the control loops have been tuned, activate the Standby block. The aircraft should have no trouble joining and maintaining orbit around the waypoint. If there are oscillations across many parameters, you may need to tune (or detune) some loops more closely. This will undoubtedly take some practice and time. One gain to look at ELEVATOR_OF_ROLL. Experience has shown trying to maintain a circular loiter can be helped by adjusting this gain. In addition, increasing the radius of the circle may help as well.
Other things to consider:
This tuning only considers the base number of parameters. For many loops, PI, PD or full PID controllers (sometimes with feedforward and biases) are available. In addition, various flags and extra features introduce further parameters to adjust. For example, AGR_CLIMB modifies the altitude loop, the auto throttle loop and the course loop. The COURSE_SLEW_INCREMENT flag and value limits the change rate of the course setpoint, which may help with the course loop tuning or under extreme course setpoint changes. The COURSE_PRE_BANK_CORRECTION value adjusts a bias used if the aircraft is navigating a circle to tune the best bank angle when circling. The Flight Benchmark module may help in fine-tuning.
In addition, these loops were tuned with an effort to isolate loops (especially untuned ones) during tuning. Under normal navigation, there may be some interaction between these loops. This can be addressed with some gain and parameter fine-tuning. A good example is if the aircraft significantly loses altitude when banked, for example during a course correction. This may cause some oscillation between altitude and course loops.
Take a look at other airframe files for examples of other available parameters. For better understanding of control loops and how some of the flags add features and affect loops, the best method is to look at the code.
8. Tune the airspeed loop
The altitude loop has a couple different cascaded loops. Thus a number of state variables need to be watched. Climb is controlled by the pitch, as in the auto pitch loop (PI controller). As the pitch/climb will affect airspeed, this is compensated for in the airspeed loops. The airspeed and ground speed setpoints can be used in two ways. First, never set the airspeed setpoint below a safe low speed, i.e. above stall speed. If the airspeed setpoint is set above the ground speed setpoint, the controller will attempt to maintain constant airspeed, unless the groundspeed falls below its setpoint, in which case a minimum ground speed will be maintained using a higher airspeed to avoid being unable to return upwind in high winds. If the ground speed setpoint is set higher than the airspeed setpoint, the controller will attempt to maintain constant groundspeed, unless the airspeed falls below its setpoint, in which case the minimum airspeed will be maintained to avoid stall.
The groundspeed setpoint is set from the airframe file. A PI loop on the groundspeed generates the airspeed setpoint. This is bounded low by the airspeed setpoint in the airframe file. A PI loop on the airspeed generates the desired throttle setting. To tune these loops, an attempt will be made to decouple them. First, the airspeed loop will be tuned, then the groundspeed loop, then the pitch loop.
Before tuning the airspeed loop, be sure to measure the approximate cruise airspeed and groundspeed of the aircraft and use these as setpoints for tuning (can use the same value). After tuning, set each according to the desired control style (airspeed or groundspeed). In addition, be sure to use the settings file airspeed_ctl_tuning.xml.
a. Fly to a safe altitude some distance away on a course such that the aircraft will fly by the pilot/GCS.
b. Activate the block Airspeed (Airspeed) Tuning and switch to auto2.
c. Observe the aircraft and data from AIRSPEED:airspeed and AIRSPEED:airspeed_sp. The aircraft should remain wings level, with the airspeed constant around the setpoint. If there are oscillations or control is sluggish, adjust auto airspeed gains. You may also experiment adjusting the airspeed setpoint in settings to induce step changes.
d. Activate the block Airspeed (Groundspeed) Tuning and switch to auto2.
e. Observe the aircraft and data from GPS:speed and AIRSPEED:groundspeed_sp. The aircraft should remain wings level, with the groundspeed constant around the setpoint. If there are oscillations or control is sluggish, adjust auto groundspeed gains. You may also experiment adjusting the groundspeed setpoint in settings to induce step changes.
f. Activate the block Airspeed (Auto Pitch) Tuning and switch to auto2.
g. Observe the aircraft and data from ESTIMATOR:z_dot and DESIRED:climb. The aircraft should remain wings level, with the climb rate remaining at zero. If fast oscillations in climb rate occur, reduce gains. Consider increasing gains until just before the onset of oscillations. Adjust the nav_climb value with the notebook settings to induce step changes.
h. Ensure the aircraft switched to manual control as it passes and gets further away from the pilot, at the pilot's discretion. Turn and line up for another pass, and switch to auto2. The previous block should still be active.
After this, the airspeed loops should be tuned.
!!!!!!!!!!!!!!!!!SHOULD THE BLOCKS AUTOMATICALLY PROTECT AGAINST ALTITUDE AND OTHER STUFF? TIMEOUTS?!!!!!!!!!!!!!!
something like 20m/s*15s = 300m away, so do a 15sec timeout on blocks?
perhaps a few global alt exceptions? But where do they deroute to assuming the aircraft isn't tuned?
-->
<!-- Change the root element to match your airspace -->
<flight_plan alt="75" ground_alt="0" lat0="43.4622" lon0="1.2729" max_dist_from_home="1000" name="Tuning_FW" security_height="25" qfu="270">
<!-- The header section allows one to include advanced navigation routines and header files that allow access to variables that may be useful for exceptions or advanced flightplan routines dependent on various internal autopilot variables -->
<header>
#include "subsystems/navigation/nav_line.h"
#include "datalink.h"
</header>
<!-- The waypoints section must contain 1 or more waypoints. For tuning, setup STDBY in a location in front of the pilot at least DEFAULT_CIRCLE_RADIUS metres away from the flight line if restricted to no overflights. Setup 1 and 2 in front of and to the left and right of the pilot, respectively. These are only used for testing ovals and eights after tuning. Again, waypoints should be at least a radius away from the flight line (probably 1.5xRadius) to prevent overflights. HOME can be set somewhere in the vicinity of STDBY or the pilot. CLIMB is for takeoff (mostly for sim, should manually takeoff for tuning)-->
<waypoints>
<waypoint name="HOME" x="0" y="0"/>
<waypoint name="STDBY" x="30." y="100."/>
<waypoint name="1" x="100.1" y="70.9"/>
<waypoint name="2" x="-100.3" y="80.1"/>
<waypoint name="CLIMB" x="-125.0" y="45.0"/>
</waypoints>
<!-- The sectors section allows the definiton of regions of space from waypoints, useful for restricting flight area with exceptions -->
<sectors/>
<!-- The includes section allows predefined blocks of flightplan to be included -->
<includes/>
<!-- The exceptions section allows for global error and failsafe handling -->
<exceptions>
<!-- <exception cond="datalink_time > 15" deroute="Standby"/> -->
</exceptions>
<!-- The blocks section contains each block of the flightplan, which actually make the aircraft do something -->
<blocks>
<block name="Wait GPS">
<set value="1" var="kill_throttle"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 10)"/>
<call fun="NavSetGroundReferenceHere()"/>
</block>
<block name="Holding point">
<!--set var="nav_mode" value="NAV_MODE_ROLL"/-->
<set value="1" var="kill_throttle"/>
<attitude roll="0" throttle="0" vmode="throttle"/>
</block>
<!-- need this for simulation, manual takeoff for real testing -->
<block key="t" name="Takeoff" strip_button="Takeoff (wp CLIMB)" strip_icon="takeoff.png" group="home">
<exception cond="estimator_z > (ground_alt+25)" deroute="Standby"/>
<set value="0" var="kill_throttle"/>
<set value="0" var="estimator_flight_time"/>
<go from="HOME" throttle="1.0" vmode="throttle" wp="CLIMB" pitch="15"/>
</block>
<block key="<Control>a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<circle radius="nav_radius" wp="STDBY"/>
</block>
<!-- first, tune the pitch and roll loops. This can be done using auto1. Here for sim demos. This block may cause a fly-away or crash -->
<block name="Sim Pitch Roll Tuning">
<while cond="TRUE">
<attitude roll="0.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="30.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="-30.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="20.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="-20.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
<attitude roll="0.0" pitch="0.0" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="stage_time>7"/>
</while>
</block>
<!-- now tune the auto throttle climb loop -->
<!-- lateral_mode = LATERAL_MODE_ROLL
h_ctl_roll_setpoint = 0.0deg
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_THROTTLE
nav_pitch = 0.0deg
v_ctl_mode = V_CTL_MODE_AUTO_CLIMB
v_ctl_climb_setpoint = 0.0
-->
<block name="Level Auto Throttle Tuning">
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="0.0"/>
</while>
</block>
<block name="Ascent Auto Throttle Tuning">
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="V_CTL_ALTITUDE_MAX_CLIMB"/>
</while>
</block>
<block name="Descent Auto Throttle Tuning">
<while cond="estimator_z > (ground_alt + 25)">
<attitude roll="0.0" vmode="climb" climb="-V_CTL_ALTITUDE_MAX_CLIMB"/>
</while>
</block>
<block name="Variable Auto Throttle Tuning">
<set var="nav_climb" value="0.0"/>
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="nav_climb"/>
</while>
</block>
<!-- now tune the auto pitch loop -->
<!-- lateral_mode = LATERAL_MODE_ROLL
h_ctl_roll_setpoint = 0.0deg
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_PITCH
nav_throttle_setpoint = 9600*(V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE)
v_ctl_mode = V_CTL_MODE_AUTO_CLIMB
v_ctl_climb_setpoint = 0.0
-->
<block name="Level Auto Pitch Tuning">
<while cond="TRUE">
<attitude roll="0.0" pitch="auto" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" vmode="climb" climb="0.0"/>
</while>
</block>
<block name="Ascent Auto Pitch Tuning">
<while cond="TRUE">
<attitude roll="0.0" pitch="auto" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" vmode="climb" climb="V_CTL_ALTITUDE_MAX_CLIMB"/>
</while>
</block>
<block name="Descent Auto Pitch Tuning">
<while cond="estimator_z > (ground_alt + 25)">
<attitude roll="0.0" pitch="auto" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" vmode="climb" climb="-V_CTL_ALTITUDE_MAX_CLIMB"/>
</while>
</block>
<block name="Variable Auto Pitch Tuning">
<set var="nav_climb" value="0.0"/>
<while cond="TRUE">
<attitude roll="0.0" pitch="auto" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" vmode="climb" climb="nav_climb"/>
</while>
</block>
<!-- now tune the altitude loop -->
<!-- lateral_mode = LATERAL_MODE_ROLL
h_ctl_roll_setpoint = 0.0deg
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_THROTTLE
nav_pitch = 0.0deg
v_ctl_mode = V_CTL_MODE_AUTO_ALT
nav_altitude = flight_altitude -> can be set in the flight params setting page
-->
<block name="Altitude Tuning">
<set var="flight_altitude" value="estimator_z"/>
<while cond="TRUE">
<attitude roll="0.0" vmode="alt" alt="flight_altitude"/>
</while>
</block>
<!-- now that the stabilization and altitude working, tune the course loop -->
<!-- lateral_mode = LATERAL_MODE_COURSE
h_ctl_course_setpoint = nav_course
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_THROTTLE
nav_pitch = 0.0deg
v_ctl_mode = V_CTL_MODE_AUTO_THROTTLE
nav_throttle_setpoint = 9600*(V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE)
-->
<block name="Course Tuning">
<set var="nav_course" value="estimator_hspeed_dir"/>
<while cond="TRUE">
<heading course="nav_course" vmode="throttle" throttle="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" until="FALSE"/> <!--continues forever-->
</while>
</block>
<!-- everything should be good, try some stuff -->
<!-- airspeed control loop tuning -->
<!-- be sure to use the settings file airspeed_ctl_tuning.xml -->
<!-- airspeed will take precedence as groundspeed set lower
setting pitch pgain to zero disables the auto pitch part of the airspeed loop, no climb control
-->
<!--
<block name="Airspeed (Airspeed) Tuning">
<set var="v_ctl_auto_groundspeed_setpoint" value="0.5*V_CTL_AUTO_AIRSPEED_SETPOINT"/>
<set var="v_ctl_auto_airspeed_setpoint" value="V_CTL_AUTO_AIRSPEED_SETPOINT"/>
<set var="v_ctl_auto_pitch_pgain" value="0.0"/>
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="0.0"/>
</while>
</block>
-->
<!-- groundspeed will take precedence as airspeed set lower
setting pitch pgain to zero disables the auto pitch part of the airspeed loop, no climb control
-->
<!--
<block name="Airspeed (Groundspeed) Tuning">
<set var="v_ctl_auto_groundspeed_setpoint" value="V_CTL_AUTO_GROUNDSPEED_SETPOINT"/>
<set var="v_ctl_auto_airspeed_setpoint" value="0.5*V_CTL_AUTO_GROUNDSPEED_SETPOINT"/>
<set var="v_ctl_auto_pitch_pgain" value="0.0"/>
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="0.0"/>
</while>
</block>
-->
<!-- airspeed should be tuned now, use in addition to pitch, airspeed will take precedence (coupled with climb more than groundspeed) -->
<!--
<block name="Airspeed (Auto Pitch) Tuning">
<set var="v_ctl_auto_groundspeed_setpoint" value="0.5*V_CTL_AUTO_AIRSPEED_SETPOINT"/>
<set var="v_ctl_auto_airspeed_setpoint" value="V_CTL_AUTO_AIRSPEED_SETPOINT"/>
<set var="v_ctl_auto_pitch_pgain" value="V_CTL_AUTO_PITCH_PGAIN"/>
<set var="nav_climb" value="0.0"/>
<while cond="TRUE">
<attitude roll="0.0" vmode="climb" climb="nav_climb"/>
</while>
</block>
-->
<!-- extra typical blocks for testing after tuning -->
<block key="F8" name="Figure 8 around wp 1" strip_button="Figure 8 (wp 1-2)" strip_icon="eight.png" group="base_pattern">
<eight center="1" radius="nav_radius" turn_around="2"/>
</block>
<block name="Oval 1-2" strip_button="Oval (wp 1-2)" strip_icon="oval.png" group="base_pattern">
<oval p1="1" p2="2" radius="nav_radius"/>
</block>
<block name="Line 1-2" strip_button="Line (wp 1-2)" strip_icon="line.png" group="base_pattern">
<call fun="nav_line_init()"/>
<call fun="nav_line(WP_1, WP_2, nav_radius)"/>
</block>
</blocks>
</flight_plan>
+73
View File
@@ -0,0 +1,73 @@
<layout width="1918" height="1095">
<rows>
<widget NAME="map2d" SIZE="850">
<papget type="variable_setting" display="button" x="64" y="700">
<property name="variable" value="launch"/>
<property name="value" value="1."/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_launch.png"/>
</papget>
<papget type="message_field" display="text" x="100" y="20">
<property name="field" value="ESTIMATOR:z_dot"/>
<property name="scale" value="1"/>
<property name="format" value="Climb:%.1fm/s"/>
<property name="size" value="30."/>
<property name="color" value="pink"/>
</papget>
<papget type="goto_block" display="button" x="0" y="0">
<property name="block_name" value="Takeoff"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_takeoff.png"/>
</papget>
<papget type="message_field" display="gauge" x="70" y="0">
<property name="field" value="BAT:voltage"/>
<property name="scale" value="0.1"/>
<property name="min" value="0."/>
<property name="max" value="8.7"/>
<property name="size" value="100."/>
<property name="text" value="Bat(V)"/>
</papget>
<papget type="goto_block" display="button" x="256" y="0">
<property name="block_name" value="shoot"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_drop3.png"/>
</papget>
<papget type="message_field" display="ruler" x="0" y="577">
<property name="field" value="ESTIMATOR:z"/>
<property name="scale" value="1"/>
<property name="height" value="400."/>
<property name="index_of_right" value="false"/>
<property name="scale" value="1."/>
<property name="width" value="64."/>
<property name="scale" value="10"/>
</papget>
<papget type="variable_setting" display="button" x="192" y="0">
<property name="variable" value="home"/>
<property name="value" value="1."/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_home.png"/>
</papget>
<papget type="goto_block" display="button" x="128" y="0">
<property name="block_name" value="standby"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_standby.png"/>
</papget>
<papget type="message_field" display="gauge" x="370" y="0">
<property name="field" value="BAT:throttle"/>
<property name="scale" value="0.0104167"/>
<property name="min" value="0."/>
<property name="max" value="100."/>
<property name="size" value="100."/>
<property name="text" value="Throttle(%)"/>
</papget>
</widget>
<columns>
<rows SIZE="275">
<widget NAME="strips" SIZE="650"/>
</rows>
<widget size="100" name="altgraph"/>
<widget NAME="aircraft" SIZE="650"/>
<widget NAME="alarms"/>
</columns>
</rows>
</layout>
@@ -0,0 +1,73 @@
<layout width="1918" height="1095">
<rows>
<widget NAME="map2d" SIZE="350">
<papget type="message_field" display="text" x="100" y="20">
<property name="field" value="ESTIMATOR:z_dot"/>
<property name="scale" value="1"/>
<property name="format" value="Climb:%.1fm/s"/>
<property name="size" value="30."/>
<property name="color" value="pink"/>
</papget>
<papget type="goto_block" display="button" x="407" y="3">
<property name="block_name" value="shoot"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_drop3.png"/>
</papget>
<papget type="variable_setting" display="button" x="329" y="2">
<property name="variable" value="home"/>
<property name="value" value="1."/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_home.png"/>
</papget>
<papget type="message_field" display="gauge" x="172" y="145">
<property name="field" value="BAT:voltage"/>
<property name="scale" value="0.1"/>
<property name="min" value="0."/>
<property name="max" value="8.7"/>
<property name="size" value="100."/>
<property name="text" value="Bat(V)"/>
</papget>
<papget type="message_field" display="ruler" x="19" y="366">
<property name="field" value="ESTIMATOR:z"/>
<property name="scale" value="1"/>
<property name="height" value="400."/>
<property name="index_of_right" value="false"/>
<property name="scale" value="1."/>
<property name="width" value="64."/>
<property name="scale" value="10"/>
</papget>
<papget type="message_field" display="gauge" x="170" y="268">
<property name="field" value="BAT:throttle"/>
<property name="scale" value="0.0104167"/>
<property name="min" value="0."/>
<property name="max" value="100."/>
<property name="size" value="100."/>
<property name="text" value="Throttle(%)"/>
</papget>
<papget type="variable_setting" display="button" x="194" y="13">
<property name="variable" value="launch"/>
<property name="value" value="1."/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_launch.png"/>
</papget>
<papget type="goto_block" display="button" x="125" y="10">
<property name="block_name" value="Takeoff"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_takeoff.png"/>
</papget>
<papget type="goto_block" display="button" x="260" y="3">
<property name="block_name" value="standby"/>
<property name="locked" value="false"/>
<property name="icon" value="openuas_standby.png"/>
</papget>
</widget>
<columns>
<rows SIZE="275">
<widget NAME="strips" SIZE="650"/>
</rows>
<widget size="100" name="altgraph"/>
<widget NAME="aircraft" SIZE="650"/>
<widget NAME="alarms"/>
</columns>
</rows>
</layout>
+12
View File
@@ -0,0 +1,12 @@
<layout width="1224" height="706">
<columns>
<rows SIZE="500">
<widget NAME="strips" SIZE="300"/>
<widget NAME="alarms"/>
<widget NAME="aircraft"/>
</rows>
<rows>
<widget NAME="map2d"/>
</rows>
</columns>
</layout>
@@ -0,0 +1,19 @@
<joystick>
<input>
<axis index="1" name="roll" />
<axis index="2" name="pitch" />
<axis index="0" name="throttle" />
<axis index="4" name="yaw" />
<axis index="3" name="mode" />
</input>
<messages period="0.025">
<message class="datalink" name="RC_4CH" send_always="true">
<field name="mode" value="Fit(mode,-108,108,0,2)"/>
<field name="throttle" value="Fit(throttle,-117,117,0,127)" />
<field name="roll" value="-roll" />
<field name="yaw" value="Fit(-yaw,-105,105,-127,127)" />
<field name="pitch" value="-pitch" />
</message>
</messages>
</joystick>
@@ -0,0 +1,38 @@
<joystick>
<input>
<axis index="0" name="roll" />
<axis index="1" name="pitch" />
<axis index="2" name="yaw" />
<axis index="3" name="throttle" />
<button index="0" name="shoot" />
<button index="1" name="b2" />
<button index="2" name="b3" />
<button index="3" name="b4" />
<button index="4" name="b5" />
<button index="5" name="b6" />
<button index="6" name="b7" />
<button index="7" name="b8" />
<button index="8" name="b9" />
<button index="9" name="b10" />
<button index="10" name="b11" />
<button index="11" name="b12" />
</input>
<variables>
<var name="mode" default="0" />
<set var="mode" value="0" on_event="b3" />
<set var="mode" value="1" on_event="b4" />
<set var="mode" value="2" on_event="b5" />
</variables>
<messages period="0.025">
<message class="datalink" name="RC_4CH" send_always="true">
<field name="mode" value="mode" />
<field name="throttle" value="127-Scale(throttle,0,128)" />
<field name="roll" value="roll" />
<field name="yaw" value="yaw" />
<field name="pitch" value="pitch" />
</message>
</messages>
</joystick>
+42
View File
@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<!--
Attributes of root (Radio) tag :
name: name of RC
data_min: min width of a pulse to be considered as a data pulse
data_max: max width of a pulse to be considered as a data pulse
sync_min: min width of a pulse to be considered as a synchro pulse
sync_max: max width of a pulse to be considered as a synchro pulse
min, max and sync are expressed in micro-seconds
-->
<!--
Attributes of channel tag :
ctl: name of the command on the transmitter - only for displaying
function: logical command
average: (boolean) channel filtered through several frames (for discrete commands)
min: minimum pulse length (micro-seconds)
max: maximum pulse length (micro-seconds)
neutral: neutral pulse length (micro-seconds)
Note: a command may be reversed by exchanging min and max values
-->
<!DOCTYPE radio SYSTEM "../radio.dtd">
<radio name="Taranis" data_min="172" data_max="1811" sync_min ="5000" sync_max ="15000" pulse_type="POSITIVE">
<channel ctl="1" function="THROTTLE" min="172" neutral="172" max="1811" average="0"/>
<channel ctl="2" function="ROLL" min="172" neutral="992" max="1811" average="0"/>
<channel ctl="3" function="PITCH" min="1811" neutral="993" max="172" average="0"/>
<channel ctl="4" function="YAW" min="172" neutral="992" max="1811" average="0"/>
<channel ctl="5" function="SWITCH_A" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="6" function="FLAP" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="7" function="SWITCH_C" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="8" function="MODE" min="1811" neutral="992" max="172" average="1"/>
<channel ctl="9" function="SWITCH_E" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="10" function="KILL_SWITCH" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="11" function="SIM_SRC" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="12" function="SWITCH_H" min="172" neutral="992" max="1811" average="1"/>
<channel ctl="13" function="POT_S1" min="172" neutral="992" max="1811" average="0"/>
<channel ctl="14" function="POT_S2" min="172" neutral="992" max="1811" average="0"/>
<channel ctl="15" function="LEFT_SLIDER" min="172" neutral="992" max="1811" average="0"/>
<channel ctl="16" function="RIGHT_SLIDER" min="172" neutral="992" max="1811" average="0"/>
</radio>
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<!-- $Id: openuas_mx22_6ch.xml,v 1.0 2014/10/23 11:05:00 mmm Exp $
--
-- No license whatsoever, free to use, 2011 OpenUAS.org
--
-- This file can be used in combination with the paparazzi autopilot.
-->
<!--
-- Attributes of root (Radio) tag :
-- name: name of RC transmitter, e.g. Graupner MX22
-- data_min: min width of a pulse to be considered as a data pulse
-- data_max: max width of a pulse to be considered as a data pulse
-- sync_min: min width of a pulse to be considered as a synchro pulse
-- sync_max: max width of a pulse to be considered as a synchro pulse
-- min, max and sync are expressed in micro-seconds
-->
<!--
-- Attributes of channel tag :
-- ctl: name of the command on the transmitter - only for displaying
-- no: order in the PPM frame
-- function: logical command
-- averaged: channel filtered through several frames (for discrete commands)
-- min: minimum pulse length (micro-seconds)
-- max: maximum pulse length (micro-seconds)
-- neutral: neutral pulse length (micro-seconds)
-- Note: a command may be reversed by exchanging min and max values
-->
<!--
The order of the list below is of importance if you do not define a
"no=" (order in the PPM frame) parameter.
If you do not define this then the order of the PPM is the one of
the order of the functon in the list
-->
<!DOCTYPE radio SYSTEM "../radio.dtd">
<!-->pulse_type="POSITIVE">-->
<radio name="OpenUAS R615X cppm" data_min="900" data_max="2100" sync_min="5000" sync_max="16000" pulse_type="NEGATIVE">
<channel ctl="RightStickHorizontal" function="ROLL" min="1900" neutral="1500" max="1100" average="0"/>
<channel ctl="RightStickVertical" function="PITCH" min="2100" neutral="1500" max="900" average="0"/>
<channel ctl="LeftStickVertical" function="THROTTLE" min="900" neutral="920" max="2100" average="0"/>
<channel ctl="LeftStickHorizontal" function="YAW" min="900" neutral="1500" max="2100" average="0"/>
<channel ctl="CONTROL8" function="MODE" min="900" neutral="1500" max="2100" average="0"/>
<channel ctl="SW8" function="MANUALRELEASE" min="900" neutral="910" max="2100" average="1"/>
</radio>
+49
View File
@@ -0,0 +1,49 @@
<?xml version="1.0"?>
<!-- $Id: openuas_mx22.xml,v 1.0 2011/04/19 11:05:00 mmm Exp $
--
-- No license whatsoever, free to use, 2011 OpenUAS.org
--
-- This file can be used in combination with the paparazzi autopilot.
-->
<!--
-- Attributes of root (Radio) tag :
-- name: name of RC transmitter, e.g. Graupner MX22
-- data_min: min width of a pulse to be considered as a data pulse
-- data_max: max width of a pulse to be considered as a data pulse
-- sync_min: min width of a pulse to be considered as a synchro pulse
-- sync_max: max width of a pulse to be considered as a synchro pulse
-- min, max and sync are expressed in micro-seconds
-->
<!--
-- Attributes of channel tag :
-- ctl: name of the command on the transmitter - only for displaying
-- no: order in the PPM frame
-- function: logical command
-- averaged: channel filtered through several frames (for discrete commands)
-- min: minimum pulse length (micro-seconds)
-- max: maximum pulse length (micro-seconds)
-- neutral: neutral pulse length (micro-seconds)
-- Note: a command may be reversed by exchanging min and max values
-->
<!--
The order of the list below is of importance if you do not define a
"no=" (order in the PPM frame) parameter.
If you do not define this then the order of the PPM is the one of
the order of the functon in the list
-->
<!DOCTYPE radio SYSTEM "../radio.dtd">
<radio name="OpenUAS MX22" data_min="1000" data_max="2000" sync_min="5000" sync_max="15000" pulse_type="NEGATIVE">
<channel ctl="LeftStickVertical" function="THROTTLE" min="1070" neutral="1110" max="1950" average="0"/>
<channel ctl="RightStickHorizontal" function="ROLL" min="1094" neutral="1491" max="1829" average="0"/>
<channel ctl="RightStickVertical" function="PITCH" min="1910" neutral="1555" max="1130" average="0"/>
<channel ctl="LeftStickHorizontal" function="YAW" min="1986" neutral="1540" max="1050" average="0"/>
<channel ctl="CONTROL8" function="MODE" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="SW8" function="MANUALRELEASE" min="1000" neutral="1000" max="2000" average="1"/>
<channel ctl="CONTROL5" function="GAIN1" min="1000" neutral="1500" max="1900" average="0"/>
<channel ctl="CONTROL6" function="CALIB" min="1000" neutral="1500" max="1900" average="0"/>
<channel ctl="NONE" function="NOTUSED" min="1100" neutral="1500" max="1900" average="0"/>
</radio>
+49
View File
@@ -0,0 +1,49 @@
<?xml version="1.0"?>
<!-- $Id: openuas_mx22.xml,v 1.0 2011/04/19 11:05:00 mmm Exp $
--
-- No license whatsoever, free to use, 2011 OpenUAS.org
--
-- This file can be used in combination with the paparazzi autopilot.
-->
<!--
-- Attributes of root (Radio) tag :
-- name: name of RC transmitter, e.g. Graupner MX22
-- data_min: min width of a pulse to be considered as a data pulse
-- data_max: max width of a pulse to be considered as a data pulse
-- sync_min: min width of a pulse to be considered as a synchro pulse
-- sync_max: max width of a pulse to be considered as a synchro pulse
-- min, max and sync are expressed in micro-seconds
-->
<!--
-- Attributes of channel tag :
-- ctl: name of the command on the transmitter - only for displaying
-- no: order in the PPM frame
-- function: logical command
-- averaged: channel filtered through several frames (for discrete commands)
-- min: minimum pulse length (micro-seconds)
-- max: maximum pulse length (micro-seconds)
-- neutral: neutral pulse length (micro-seconds)
-- Note: a command may be reversed by exchanging min and max values
-->
<!--
The order of the list below is of importance if you do not define a
"no=" (order in the PPM frame) parameter.
If you do not define this then the order of the PPM is the one of
the order of the functon in the list
-->
<!DOCTYPE radio SYSTEM "../radio.dtd">
<radio name="OpenUAS MX22" data_min="1000" data_max="2000" sync_min="5000" sync_max="27000" pulse_type="NEGATIVE">
<channel ctl="LeftStickVertical" function="THROTTLE" min="1070" neutral="1110" max="1950" average="0"/>
<channel ctl="RightStickHorizontal" function="ROLL" min="1094" neutral="1491" max="1829" average="0"/>
<channel ctl="RightStickVertical" function="PITCH" min="1910" neutral="1555" max="1130" average="0"/>
<channel ctl="LeftStickHorizontal" function="YAW" min="1986" neutral="1540" max="1050" average="0"/>
<channel ctl="CONTROL8" function="MODE" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="SW8" function="MANUALRELEASE" min="1000" neutral="1000" max="2000" average="1"/>
<channel ctl="CONTROL5" function="GAIN1" min="1000" neutral="1500" max="1900" average="0"/>
<channel ctl="CONTROL6" function="CALIB" min="1000" neutral="1500" max="1900" average="0"/>
<channel ctl="NONE" function="NOTUSED" min="1100" neutral="1500" max="1900" average="0"/>
</radio>
@@ -0,0 +1,20 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<settings>
<dl_settings name="control">
<dl_settings name="dc">
<dl_setting max="255" min="0" step="1" module="digital_cam/dc" var="0" handler="send_command" shortname="Shutter">
<strip_button name="Photo" icon="digital-camera.png" value="32" group="imaging" />
<!--<strip_button name="Power" icon="off.png" value="111" group="maindc"/>-->
<!--<strip_button name="ZoomIn" icon="zoom.png" value="116" group="dczoom"/>-->
<!--<strip_button name="ZoomOut" icon="zoom.png" value="119" group="dczoom"/>-->
</dl_setting>
<dl_setting max="3" min="0" step="1" var="dc_autoshoot" >
<strip_button name="Start Autoshoot Periodic" icon="on.png" value="1" group="imaging" />
<strip_button name="Start Autoshoot Distance" icon="on.png" value="2" group="imaging" />
<strip_button name="Stop Autoshoot" icon="off.png" value="0" group="imaging" />
</dl_setting>
<dl_setting max="255" min="1" step="1" var="dc_autoshoot_quartersec_period" handler="Periodic4Hz" shortname="Periodic" param="DC_AUTOSHOOT_QUARTERSEC_PERIOD" unit="quarter-sec"/>
<dl_setting max="100" min="1" step="1" var="dc_autoshoot_meter_grid" shortname="PeriodicMeter" param="DC_AUTOSHOOT_METER_GRID" unit="meter"/>
</dl_settings>
</dl_settings>
</settings>
+24
View File
@@ -0,0 +1,24 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<settings>
<dl_settings name="control">
<dl_settings name="dc">
<dl_setting max="255" min="0" step="1" module="digital_cam/dc" var="0" handler="send_command" shortname="Shutter">
<strip_button name="Shoot Photo" icon="digital-camera.png" value="32" group="ouasimaging" />
<!--<strip_button name="Power" icon="off.png" value="111" group="maindc"/>-->
<!--<strip_button name="ZoomIn" icon="zoom.png" value="116" group="dczoom"/>-->
<!--<strip_button name="ZoomOut" icon="zoom.png" value="119" group="dczoom"/>-->
</dl_setting>
<dl_setting max="3" min="0" step="1" var="dc_autoshoot" >
<strip_button name="Start Autoshoot Periodic" icon="on.png" value="1" group="ouasimaging" />
<strip_button name="Start Autoshoot Distance" icon="on.png" value="2" group="ouasimaging" />
<strip_button name="Stop Autoshoot" icon="off.png" value="0" group="ouasimaging" />
</dl_setting>
<dl_setting max="255" min="1" step="1" var="dc_autoshoot_quartersec_period" handler="Periodic4Hz" shortname="Periodic" param="DC_AUTOSHOOT_QUARTERSEC_PERIOD" unit="quarter-sec"/>
<dl_setting max="100" min="1" step="1" var="dc_autoshoot_meter_grid" shortname="PeriodicMeter" param="DC_AUTOSHOOT_METER_GRID" unit="meter"/>
</dl_settings>
</dl_settings>
</settings>
@@ -0,0 +1,32 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<!-- A conf to use for standard operation (no tuning) -->
<settings>
<dl_settings>
<dl_settings NAME="flight params">
<dl_setting MAX="1000" MIN="0" STEP="10" VAR="flight_altitude" shortname="altitude"/>
<dl_setting MAX="360" MIN="0" STEP="1" VAR="nav_course"/>
<dl_setting MAX="10" MIN="-10" STEP="5" VAR="nav_shift" module="subsystems/nav" handler="IncreaseShift" shortname="inc. shift"/>
<dl_setting MAX="0" MIN="0" STEP="1" VAR="autopilot_flight_time" shortname="flight time" module="autopilot" handler="ResetFlightTimeAndLaunch"/>
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
<strip_button icon="circle-right.png" name="Circle right" value="1" group="circle"/>
<strip_button icon="circle-left.png" name="Circle left" value="-1" group="circle"/>
<key_press key="greater" value="1"/>
<key_press key="less" value="-1"/>
</dl_setting>
</dl_settings>
<dl_settings NAME="mode">
<dl_setting MAX="2" MIN="0" STEP="1" VAR="pprz_mode" module="autopilot" values="MANUAL|AUTO1|AUTO2|HOME|NOGPS|FAILSAFE"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="launch"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
<!-- <dl_setting MAX="0" MIN="0" STEP="1" VAR="estimator_flight_time" shortname="flight time"/>-->
<dl_setting MAX="1000" MIN="0" STEP="1" VAR="stage_time"/>
<!-- <dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/> -->
</dl_settings>
</dl_settings>
</settings>
+12
View File
@@ -0,0 +1,12 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<settings>
<dl_settings>
<dl_settings NAME="SkySegmentation">
<dl_setting var="obstacle_avoid_adjust_factor" min="0" step="1" max="255" module="../../../sw/ext/ardrone2_vision/modules/ObstacleAvoidSkySegmentation/sky_seg_avoid" shortname="adjust" />
<dl_setting var="avoid_navigation_data.mode" min="0" step="1" max="2" values="Off|Climb|Lateral" module="../../../sw/ext/ardrone2_vision/modules/ObstacleAvoidSkySegmentation/avoid_navigation" shortname="mode" />
</dl_settings>
</dl_settings>
</settings>
@@ -0,0 +1,12 @@
<!DOCTYPE settings SYSTEM "settings.dtd">
<settings>
<dl_settings>
<dl_settings NAME="SkySegmentation">
<dl_setting var="obstacle_avoid_adjust_factor" min="0" step="1" max="255" module="../../../sw/ext/ardrone2_vision/modules/ObstacleAvoidSkySegmentation/sky_seg_avoid" shortname="adjust" />
<dl_setting var="avoid_navigation_data.mode" min="0" step="1" max="2" values="Off|Climb|Lateral" module="../../../sw/ext/ardrone2_vision/modules/ObstacleAvoidSkySegmentation/avoid_navigation" shortname="mode" />
</dl_settings>
</dl_settings>
</settings>
@@ -0,0 +1,14 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<settings>
<dl_settings NAME="agressive">
<dl_settings NAME="agr">
<dl_setting MAX="1.0" MIN="0." STEP="0.05" VAR="agr_climb_throttle" shortname="climb_throttle" module="guidance/guidance_v" param="AGR_CLIMB_THROTTLE"/>
<dl_setting MAX="0.5" MIN="-0.1" STEP="0.05" VAR="agr_climb_pitch" shortname="climb_pitch" module="guidance/guidance_v" param="AGR_CLIMB_PITCH"/>
<dl_setting MAX="1.0" MIN="0." STEP="0.1" VAR="agr_climb_nav_ratio" shortname="climb_nav_ratio" module="guidance/guidance_v" param="AGR_CLIMB_NAV_RATIO"/>
<dl_setting MAX="1.0" MIN="0." STEP="0.05" VAR="agr_descent_throttle" shortname="descent_throttle" module="guidance/guidance_v" param="AGR_DESCENT_THROTTLE"/>
<dl_setting MAX="0.1" MIN="-0.5" STEP="0.05" VAR="agr_descent_pitch" shortname="descent_ptich" module="guidance/guidance_v" param="AGR_DESCENT_PITCH"/>
<dl_setting MAX="1.0" MIN="0." STEP="0.1" VAR="agr_descent_nav_ratio" shortname="descent_nav_ratio" module="guidance/guidance_v" param="AGR_DESCENT_NAV_RATIO"/>
</dl_settings>
</dl_settings>
</settings>
@@ -0,0 +1,100 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<!-- A conf to use to tune a new A/C -->
<settings>
<dl_settings>
<dl_settings NAME="flight params">
<dl_setting MAX="1000" MIN="0" STEP="10" VAR="flight_altitude" shortname="altitude"/>
<dl_setting MAX="10" MIN="-10" STEP="0.5" VAR="wind_east"/>
<dl_setting MAX="10" MIN="-10" STEP="0.5" VAR="wind_north"/>
</dl_settings>
<dl_settings NAME="mode">
<dl_setting MAX="2" MIN="0" STEP="1" VAR="pprz_mode" module="autopilot"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="alt_kalman_enabled" shortname="alt_kalman" module="estimator"/>
<dl_setting MAX="0" MIN="0" STEP="1" VAR="estimator_flight_time" shortname="flight time"/>
<dl_setting MAX="1000" MIN="0" STEP="1" VAR="stage_time"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="launch"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
<strip_button icon="circle-left.png" name="Circle left" value="-1"/>
<key_press key="greater" value="1"/>
<key_press key="less" value="-1"/>
</dl_setting>
</dl_settings>
<dl_settings NAME="control">
<dl_settings NAME="ins">
<dl_setting MAX="0.3" MIN="-0.3" STEP="0.01" VAR="ins_roll_neutral" shortname="roll_neutral" module="subsystems/ahrs" param="INS_ROLL_NEUTRAL_DEFAULT" unit="rad"/>
<dl_setting MAX="0.6" MIN="-0.6" STEP="0.01" VAR="ins_pitch_neutral" shortname="pitch_neutral" param="INS_PITCH_NEUTRAL_DEFAULT" unit="rad"/>
</dl_settings>
<dl_settings NAME="attitude">
<dl_setting MAX="25000" MIN="000" STEP="250" VAR="h_ctl_roll_pgain" shortname="roll_pgain" module="stabilization/stabilization_attitude"/>
<dl_setting MAX="1" MIN="0" STEP="0.05" VAR="h_ctl_roll_max_setpoint" shortname="max_roll" param="H_CTL_ROLL_MAX_SETPOINT"/>
<dl_setting MAX="000" MIN="-25000" STEP="250" VAR="h_ctl_pitch_pgain" shortname="pitch_pgain" param="H_CTL_PITCH_PGAIN"/>
<dl_setting MAX="30" MIN="0" STEP="0.1" VAR="h_ctl_pitch_dgain" shortname="pitch_dgain" param="H_CTL_PITCH_DGAIN"/>
<dl_setting MAX="5000" MIN="0" STEP="100" VAR="h_ctl_elevator_of_roll" shortname="elevator_of_roll" param="H_CTL_ELEVATOR_OF_ROLL"/>
<dl_setting MAX="5000" MIN="0" STEP="100" VAR="h_ctl_aileron_of_throttle" shortname="aileron_of_throttle"/>
<dl_setting MAX="0" MIN="-15000" STEP="250" VAR="h_ctl_roll_attitude_gain" shortname="roll attitude pgain" param="H_CTL_ROLL_ATTITUDE_GAIN"/>
<dl_setting MAX="0" MIN="-15000" STEP="250" VAR="h_ctl_roll_rate_gain" shortname="roll rate gain" param="H_CTL_ROLL_RATE_GAIN"/>
</dl_settings>
<dl_settings name="alt">
<dl_setting MAX="0" MIN="-0.2" STEP="0.01" VAR="v_ctl_altitude_pgain" shortname="alt_pgain" param="V_CTL_ALTITUDE_PGAIN"/>
</dl_settings>
<dl_settings name="auto_throttle">
<dl_setting MAX="1" MIN="0.0" STEP="0.05" VAR="v_ctl_auto_throttle_cruise_throttle" shortname="cruise throttle" module="guidance/guidance_v" handler="SetCruiseThrottle" param="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE">
<strip_button name="Loiter" value="0.1" group="tuning_basic_ins"/>
<strip_button name="Cruise" value="0" group="tuning_basic_ins"/>
<strip_button name="Dash" value="1" group="tuning_basic_ins"/>
</dl_setting>
<dl_setting MAX="0.00" MIN="-0.05" STEP="0.005" VAR="v_ctl_auto_throttle_pgain" shortname="throttle_pgain" param="V_CTL_AUTO_THROTTLE_PGAIN"/>
<dl_setting MAX="1" MIN="0.0" STEP="0.05" VAR="v_ctl_auto_throttle_igain" shortname="throttle_igain" param="V_CTL_AUTO_THROTTLE_IGAIN"/>
<dl_setting MAX="2" MIN="0.0" STEP="0.1" VAR="v_ctl_auto_throttle_dgain" shortname="throttle_dgain"/>
<!-- commented by poine - does anybody use that ?at all ? -->
<!-- <dl_setting MAX="0" MIN="-4000" STEP="100" VAR="v_ctl_auto_throttle_dash_trim" shortname="dash trim"/> -->
<!-- <dl_setting MIN="0" MAX="3000" STEP="100" VAR="v_ctl_auto_throttle_loiter_trim" shortname="loiter trim" param="V_CTL_AUTO_THROTTLE_LOITER_TRIM"/> -->
<dl_setting MAX="1" MIN="0" STEP="0.01" VAR="v_ctl_auto_throttle_climb_throttle_increment" shortname="throttle_incr" param="V_CTL_AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT"/>
<dl_setting MAX="1" MIN="0" STEP="0.01" VAR="v_ctl_auto_throttle_pitch_of_vz_pgain" shortname="pitch_of_vz" param="V_CTL_AUTO_THROTTLE_PITCH_OF_VZ_PGAIN"/>
<dl_setting MAX="10" MIN="-10" STEP="0.1" VAR="v_ctl_auto_throttle_pitch_of_vz_dgain" shortname="pitch_of_vz (d)"/>
</dl_settings>
<dl_settings name="auto_pitch">
<dl_setting MAX="-0.01" MIN="-0.1" STEP="0.01" VAR="v_ctl_auto_pitch_pgain" shortname="pgain" param="V_CTL_AUTO_PITCH_PGAIN"/>
<dl_setting MAX="1" MIN="0" STEP="0.01" VAR="v_ctl_auto_pitch_igain" shortname="igain" param="V_CTL_AUTO_PITCH_IGAIN"/>
</dl_settings>
<dl_settings name="nav">
<dl_setting MAX="-0.1" MIN="-3" STEP="0.05" VAR="h_ctl_course_pgain" shortname="course pgain" param="H_CTL_COURSE_PGAIN"/>
<dl_setting MAX="2" MIN="0" STEP="0.1" VAR="h_ctl_course_dgain" shortname="course dgain" param="H_CTL_COURSE_DGAIN"/>
<dl_setting MAX="2" MIN="0.1" STEP="0.05" VAR="h_ctl_course_pre_bank_correction" shortname="pre bank cor" param="H_CTL_COURSE_PRE_BANK_CORRECTION"/>
<dl_setting MAX="1" MIN="0.0" STEP="0.05" VAR="nav_glide_pitch_trim" shortname="glide pitch trim" param="NAV_GLIDE_PITCH_TRIM"/>
<dl_setting MAX="1" MIN="0.02" STEP="0.01" VAR="h_ctl_roll_slew" shortname="roll slew"/>
<dl_setting MAX="500" MIN="-500" STEP="5" VAR="nav_radius"/>
<dl_setting MAX="359" MIN="0" STEP="5" VAR="nav_course"/>
<dl_setting MAX="2" MIN="1" STEP="1" VAR="nav_mode"/>
<dl_setting MAX="5" MIN="-5" STEP="0.5" VAR="nav_climb"/>
<dl_setting MAX="15" MIN="-15" STEP="1" VAR="fp_pitch"/>
<dl_setting MAX="50" MIN="-50" STEP="5" VAR="nav_shift" module="subsystems/nav" handler="IncreaseShift" shortname="inc. shift"/>
<dl_setting MAX="50" MIN="5" STEP="0.5" VAR="nav_ground_speed_setpoint" shortname="ground speed"/>
<dl_setting MAX="0." MIN="-0.2" STEP="0.01" VAR="nav_ground_speed_pgain" shortname="ground speed pgain"/>
<dl_setting MAX="500" MIN="50" STEP="5" VAR="nav_survey_shift"/>
</dl_settings>
</dl_settings>
</dl_settings>
</settings>
@@ -0,0 +1,36 @@
<?xml version="1.0"?>
<!DOCTYPE settings SYSTEM "../settings.dtd">
<!-- A conf to use to tune an A/C using only the rc -->
<!--
<!ELEMENT settings (rc_settings?,dl_settings?)>
<!ELEMENT rc_settings (rc_mode*)>
<!ELEMENT rc_mode (rc_setting*)>
<!ELEMENT rc_setting EMPTY>
<!ATTLIST rc_mode name CDATA #REQUIRED>
<!ATTLIST rc_setting var CDATA #REQUIRED>
<!ATTLIST rc_setting type (int16|float) #REQUIRED>
<!ATTLIST rc_setting range CDATA #REQUIRED>
<!ATTLIST rc_setting rc (gain_1_up|gain_2_up|gain_1_down|gain_2_down) #REQUIRED>
-->
<settings>
<rc_settings>
<rc_mode NAME="AUTO1">
<rc_setting VAR="infrared_pitch_neutral" RANGE="0.2" RC="gain_1_up" TYPE="float"/>
<rc_setting VAR="infrared_roll_neutral" RANGE="-0.2" RC="gain_1_down" TYPE="float"/>
</rc_mode>
<rc_mode NAME="AUTO2">
<rc_setting VAR="h_ctl_course_pgain" RANGE="0.5" RC="gain_1_up" TYPE="float"/>
<rc_setting VAR="flight_altitude" RANGE="-100" RC="gain_1_down" TYPE="float"/>
</rc_mode>
</rc_settings>
</settings>
+1
View File
@@ -0,0 +1 @@
not yet
@@ -0,0 +1,63 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Main">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="1.1"/>
<message name="ROTORCRAFT_STATUS" period="0.9"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED" period="0.4"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="I2C_ERRORS" period="4.1"/>
<message name="UART_ERRORS" period="3.1"/>
<message name="IMU_ACCEL_RAW" period="0.05"/>
<message name="IMU_GYRO_RAW" period="0.05"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="BARO_RAW" period="0.1"/>
<message name="ARDRONE_NAVDATA" period="0.13"/>
<message name="IMU_GYRO_SCALED" period="0.25"/>
<message name="IMU_ACCEL_SCALED" period="0.25"/>
<message name="IMU_MAG_SCALED" period="0.25"/>
<message name="FILTER_ALIGNER" period="2.2"/>
<message name="FILTER" period="0.7"/>
<message name="AHRS_GYRO_BIAS_INT" period="0.08"/>
<message name="AHRS_QUAT_INT" period="0.26"/>
<message name="AHRS_ARDRONE2" period="0.11"/>
<message name="VFF" period="0.06"/>
<message name="VERT_LOOP" period="0.07"/>
<message name="INS" period="0.08"/>
<message name="INS_REF" period="5.1"/>
<message name="HOVER_LOOP" period="0.062"/>
<message name="GUIDANCE_H_REF" period="0.062"/>
<message name="STAB_ATTITUDE" period="0.4"/>
<message name="STAB_ATTITUDE_REF" period="2.1"/>
<message name="ROTORCRAFT_FP" period="0.8"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="INS_REF" period="5.1"/>
<!-- HFF messages are only sent if USE_HFF -->
<message name="HFF" period=".05"/>
<message name="HFF_GPS" period=".03"/>
<message name="HFF_DBG" period=".2"/>
</mode>
<mode name="raw_sensors" key_press="r">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_ACCEL_RAW" period=".05"/>
<message name="IMU_GYRO_RAW" period=".05"/>
<message name="IMU_MAG_RAW" period=".05"/>
<message name="BARO_RAW" period=".1"/>
<message name="ARDRONE_NAVDATA" period=".05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,63 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Main">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="1.1"/>
<message name="ROTORCRAFT_STATUS" period="0.9"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED" period="0.4"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="I2C_ERRORS" period="4.1"/>
<message name="UART_ERRORS" period="3.1"/>
<message name="IMU_ACCEL_RAW" period="0.05"/>
<message name="IMU_GYRO_RAW" period="0.05"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="BARO_RAW" period="0.1"/>
<message name="ARDRONE_NAVDATA" period="0.13"/>
<message name="IMU_GYRO_SCALED" period="0.25"/>
<message name="IMU_ACCEL_SCALED" period="0.25"/>
<message name="IMU_MAG_SCALED" period="0.25"/>
<message name="FILTER_ALIGNER" period="2.2"/>
<message name="FILTER" period="0.7"/>
<message name="AHRS_GYRO_BIAS_INT" period="0.08"/>
<message name="AHRS_QUAT_INT" period="0.26"/>
<message name="AHRS_ARDRONE2" period="0.11"/>
<message name="VFF" period="0.06"/>
<message name="VERT_LOOP" period="0.07"/>
<message name="INS" period="0.08"/>
<message name="INS_REF" period="5.1"/>
<message name="HOVER_LOOP" period="0.062"/>
<message name="GUIDANCE_H_REF" period="0.062"/>
<message name="STAB_ATTITUDE" period="0.4"/>
<message name="STAB_ATTITUDE_REF" period="2.1"/>
<message name="ROTORCRAFT_FP" period="0.8"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="INS_REF" period="5.1"/>
<!-- HFF messages are only sent if USE_HFF -->
<message name="HFF" period=".05"/>
<message name="HFF_GPS" period=".03"/>
<message name="HFF_DBG" period=".2"/>
</mode>
<mode name="raw_sensors" key_press="r">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_ACCEL_RAW" period=".05"/>
<message name="IMU_GYRO_RAW" period=".05"/>
<message name="IMU_MAG_RAW" period=".05"/>
<message name="BARO_RAW" period=".1"/>
<message name="ARDRONE_NAVDATA" period=".05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,46 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
<telemetry>
<process name="Main">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="0.7"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="INS_REF" period="0.25"/>
<message name="IMU_ACCEL_RAW" period="0.21"/>
<message name="IMU_GYRO_RAW" period="0.13"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="BARO_RAW" period="0.07"/>
<message name="ARDRONE_NAVDATA" period="0.05"/>
<message name="I2C_ERRORS" period="2.1"/>
<message name="UART_ERRORS" period="2.3"/>
</mode>
<mode name="vert_loop" key_press="v">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="0.9"/>
<message name="VFF" period=".05"/>
<message name="VERT_LOOP" period=".05"/>
<message name="INS" period=".05"/>
<message name="INS_REF" period="5.1"/>
</mode>
<mode name="mag_current_calibration">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_MAG_CURRENT_CALIBRATION" period="0.05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,46 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Main">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="0.7"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="INS_REF" period="0.25"/>
<message name="IMU_ACCEL_RAW" period="0.21"/>
<message name="IMU_GYRO_RAW" period="0.13"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="BARO_RAW" period="0.07"/>
<message name="ARDRONE_NAVDATA" period="0.05"/>
<message name="I2C_ERRORS" period="2.1"/>
<message name="UART_ERRORS" period="2.3"/>
</mode>
<mode name="vert_loop" key_press="v">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="0.9"/>
<message name="VFF" period=".05"/>
<message name="VERT_LOOP" period=".05"/>
<message name="INS" period=".05"/>
<message name="INS_REF" period="5.1"/>
</mode>
<mode name="mag_current_calibration">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_MAG_CURRENT_CALIBRATION" period="0.05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,114 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default">
<message name="AIRSPEED" period="1"/>
<message name="ALIVE" period="5"/>
<message name="GPS" period="0.25"/>
<message name="NAVIGATION" period="1."/>
<message name="ATTITUDE" period="0.1"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="ENERGY" period="2.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="0.2"/>
<message name="BAT" period="1.1"/>
<message name="BARO_MS5534A" period="1.0"/>
<message name="SCP_STATUS" period="1.0"/>
<message name="SEGMENT" period="1.2"/>
<message name="CALIBRATION" period="2.1"/>
<message name="NAVIGATION_REF" period="9."/>
<message name="PPRZ_MODE" period="5."/>
<message name="STATE_FILTER_STATUS" period="2.2"/>
<message name="DOWNLINK" period="5.1"/>
<message name="DL_VALUE" period="1.5"/>
<!-- <message name="IR_SENSORS" period="1.2"/> -->
<message name="GYRO_RATES" period="1.1"/>
<message name="SURVEY" period="2.1"/>
<message name="GPS_SOL" period="2.0"/>
<message name="IMU_ACCEL" period=".8"/>
<message name="IMU_GYRO" period=".6"/>
<message name="IMU_MAG" period="1.3"/>
</mode>
<mode name="minimal">
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="4"/>
<message name="GPS" period="1.05"/>
<message name="ESTIMATOR" period="1.3"/>
<message name="WP_MOVED" period="1.4"/>
<message name="CIRCLE" period="3.05"/>
<message name="DESIRED" period="4.05"/>
<message name="BAT" period="1.1"/>
<message name="SEGMENT" period="3.2"/>
<message name="CALIBRATION" period="5.1"/>
<message name="NAVIGATION_REF" period="9."/>
<message name="NAVIGATION" period="3."/>
<message name="PPRZ_MODE" period="5."/>
<message name="STATE_FILTER_STATUS" period="5."/>
<message name="DOWNLINK" period="5.1"/>
<message name="DL_VALUE" period="1.5"/>
<!-- <message name="IR_SENSORS" period="5.2"/> -->
<message name="GYRO_RATES" period="10.1"/>
<message name="SURVEY" period="2.1"/>
<message name="GPS_SOL" period="5.0"/>
</mode>
<mode name="extremal">
<message name="ALIVE" period="5"/>
<message name="GPS" period="5.1"/>
<message name="ESTIMATOR" period="5.3"/>
<message name="BAT" period="10.1"/>
<message name="DESIRED" period="10.2"/>
<message name="NAVIGATION" period="5.4"/>
<message name="PPRZ_MODE" period="7.5"/>
<message name="STATE_FILTER_STATUS" period="8."/>
<message name="DOWNLINK" period="5.7"/>
</mode>
<mode name="raw_sensors">
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_ACCEL_RAW" period=".05"/>
<message name="IMU_GYRO_RAW" period=".05"/>
<message name="IMU_MAG_RAW" period=".05"/>
</mode>
<mode name="scaled_sensors">
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_GYRO" period=".075"/>
<message name="IMU_ACCEL" period=".075"/>
<message name="IMU_MAG" period=".1"/>
</mode>
<mode name="debug_imu">
<message name="ATTITUDE" period="0.1"/>
<message name="ALIVE" period="5"/>
<message name="GPS" period="5.1"/>
<message name="ESTIMATOR" period="5.3"/>
<message name="BAT" period="10.1"/>
<message name="DESIRED" period="10.2"/>
<message name="NAVIGATION" period="5.4"/>
<message name="PPRZ_MODE" period="5.5"/>
<message name="STATE_FILTER_STATUS" period="5."/>
<message name="DOWNLINK" period="5.7"/>
<message name="IMU_ACCEL" period=".5"/>
<message name="IMU_GYRO" period=".5"/>
<message name="IMU_MAG" period=".5"/>
<message name="IMU_ACCEL_RAW" period=".5"/>
<message name="IMU_GYRO_RAW" period=".5"/>
<message name="IMU_MAG_RAW" period=".5"/>
</mode>
</process>
<process name="Fbw">
<mode name="default">
<message name="COMMANDS" period="5"/>
<message name="FBW_STATUS" period="2"/>
<message name="ACTUATORS" period="5"/> <!-- For trimming -->
</mode>
<mode name="debug">
<message name="PPM" period="0.5"/>
<message name="RC" period="0.5"/>
<message name="COMMANDS" period="0.5"/>
<message name="FBW_STATUS" period="1"/>
<message name="ACTUATORS" period="5"/> <!-- For trimming -->
</mode>
</process>
</telemetry>
@@ -0,0 +1,36 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default">
<message name="ESTIMATOR" period="2." phase="0."/>
<message name="NAVIGATION" period="2." phase="0."/>
<message name="GPS" period="2." phase="0."/>
<message name="ATTITUDE" period="4." phase="1"/>
<message name="DL_VALUE" period="4." phase="3"/>
<message name="WP_MOVED" period="4." phase="3"/>
<message name="DESIRED" period="8." phase="1"/>
<!-- Only one of the following is active at the same time: give them same time stamp -->
<message name="SEGMENT" period="8." phase="5"/>
<message name="CIRCLE" period="8." phase="5"/>
<message name="SURVEY" period="8." phase="5"/>
<message name="ALIVE" period="16." phase="1"/>
<message name="BAT" period="16." phase="1"/>
<message name="CALIBRATION" period="16." phase="1"/>
<message name="DATALINK_REPORT" period="16." phase="5"/>
<message name="GPS_SOL" period="16." phase="5"/>
<message name="NAVIGATION_REF" period="16." phase="9"/>
<message name="PPRZ_MODE" period="16." phase="9"/>
</mode>
</process>
<process name="Fbw">
<mode name="default">
<message name="FBW_STATUS" period="16." phase="13"/>
<message name="COMMANDS" period="16." phase="13"/>
<message name="ACTUATORS" period="16." phase="13"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,45 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="1.1"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="INS_REF" period="0.24"/>
<message name="IMU_ACCEL_RAW" period="0.26"/>
<message name="IMU_GYRO_RAW" period="0.23"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="IMU_MAG_SCALED" period=".1"/>
<message name="BARO_RAW" period="0.07"/>
<message name="ARDRONE_NAVDATA" period="0.08"/>
<message name="I2C_ERRORS" period="2.1"/>
<message name="UART_ERRORS" period="2.3"/>
<message name="WP_MOVED" period="1.3"/>
</mode>
<mode name="vert_loop" key_press="v">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="0.9"/>
<message name="VFF" period=".05"/>
<message name="VERT_LOOP" period=".05"/>
<message name="INS" period=".05"/>
<message name="INS_REF" period="5.1"/>
</mode>
<mode name="mag_current_calibration">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_MAG_CURRENT_CALIBRATION" period="0.05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,45 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default" key_press="d">
<message name="DL_VALUE" period="1.1"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="GPS_INT" period="0.25"/>
<message name="INS" period="0.25"/>
<message name="INS_REF" period="0.24"/>
<message name="IMU_ACCEL_RAW" period="0.26"/>
<message name="IMU_GYRO_RAW" period="0.23"/>
<message name="IMU_MAG_RAW" period="0.25"/>
<message name="IMU_MAG_SCALED" period=".1"/>
<message name="BARO_RAW" period="0.07"/>
<message name="ARDRONE_NAVDATA" period="0.08"/>
<message name="I2C_ERRORS" period="2.1"/>
<message name="UART_ERRORS" period="2.3"/>
<message name="WP_MOVED" period="1.3"/>
</mode>
<mode name="vert_loop" key_press="v">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="0.9"/>
<message name="VFF" period=".05"/>
<message name="VERT_LOOP" period=".05"/>
<message name="INS" period=".05"/>
<message name="INS_REF" period="5.1"/>
</mode>
<mode name="mag_current_calibration">
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_MAG_CURRENT_CALIBRATION" period="0.05"/>
</mode>
</process>
</telemetry>
@@ -0,0 +1,34 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default">
<message name="ESTIMATOR" period="3." phase="0."/>
<message name="NAVIGATION" period="3." phase="0."/>
<message name="GPS" period="3." phase="0."/>
<message name="ATTITUDE" period="6." phase="0"/>
<message name="DL_VALUE" period="3." phase="0"/>
<message name="WP_MOVED" period="6." phase="3"/>
<message name="DESIRED" period="6." phase="0"/>
<message name="SEGMENT" period="6." phase="0"/>
<message name="CIRCLE" period="6." phase="0"/>
<message name="SURVEY" period="6." phase="0"/>
<message name="PPRZ_MODE" period="12." phase="0"/>
<message name="BAT" period="12." phase="0"/>
<message name="ALIVE" period="18." phase="0"/>
<message name="CALIBRATION" period="18." phase="0"/>
<message name="DATALINK_REPORT" period="18." phase="0"/>
<message name="GPS_SOL" period="18." phase="0"/>
<message name="NAVIGATION_REF" period="18." phase="0"/>
</mode>
</process>
<process name="Fbw">
<mode name="default">
<message name="FBW_STATUS" period="18." phase="0"/>
</mode>
</process>
</telemetry>