mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
3559306dd8
* Modified disco airframe used in flat spin landing experiment * Added disco_modified.xml airframe to conf * Removed unnecessary nav modules and sim defines, updated servo ThrottleHigh value * Fixed ThrottleHigh() value
603 lines
33 KiB
XML
603 lines
33 KiB
XML
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
|
<airframe name="Disco_FlatSpin">
|
|
<description>
|
|
|
|
* Parrot Disco Fixedwing Modiefied Hardware with added Pixracer board.
|
|
+ Airframe to validate all onboard functionally...
|
|
Disco FlatSpin
|
|
+ Autopilot: Pixracer 1
|
|
+ Actuators: Hitec HS5055 servos
|
|
+ GPS: uBlox M8N GNSS
|
|
+ TELEMETRY: 3DR Si1000 based 868
|
|
+ CURRENT: V/A power block sensing
|
|
+ RC RX: R-XSR FrSky Receiver with SBUS out
|
|
|
|
NOTES:
|
|
|
|
+ Hey, calibrate your magneto! Yes, you too ;), unit UKF auto works... output
|
|
+ One could make a flightplan mimicking exact default behaviour of Parrot assisted flight
|
|
+ Enlarged battery bay ,and option fit a 5200 mAh 3S battery. The all-up weight (AUW)) of the airframe will be ~150g more
|
|
Center of gravity still the same, flighttime doubles...
|
|
+ If you change your control from ETECS to Classic or New make sure to disable the settings/estimation/ac_char
|
|
+ PPRZLink v2 advised for tcas fun
|
|
|
|
WIP:
|
|
|
|
RC:
|
|
The RC receiver Orange R620X make sure to set modeswitch to Auto2 on your TX when binding!
|
|
else if one would lose RC or switch of transmitter during Auto2 flight, it will hop to manual.. very bad...
|
|
|
|
A PPM receiver could theoretically be used, only for Linux ARCH no software to handle it is written (hint!)
|
|
SUMD also. For the PPRZ Spektum could also, but not if you also want to fly it with RC but without PPRZ as AP only original
|
|
since Spektrum serial is not handled by the Parrot main AP
|
|
|
|
The setup ot Transmitter is in such a way that one could fly without PPRC just Parrot with a 3rd party transmitter
|
|
Thus modeswitch on 5 for well.. mode
|
|
|
|
TX Channel Nr Function Control type Comments
|
|
1 Roll Stick
|
|
2 Pitch Stick
|
|
3 Throttle Stick
|
|
4 Yaw Stick Used to set the Disco in loiter
|
|
5 Gear 3-position switch Used to configure the piloting mode:
|
|
Auto-pilot with Parrot SkyController2 (Risky so better limit this one exept if you teaching people to fly with Skycontroller student AND RCTX for teacher )
|
|
Auto-pilot with RC controller
|
|
Full manual with RC controller
|
|
6 Automatic Take-off/Landing 2-position trainer switch Used in “Auto-pilot with RC controller” mode
|
|
Start: SWx Landing: SWy
|
|
Motor off in manual mode SW?
|
|
</description>
|
|
<firmware name="fixedwing">
|
|
<!-- ********************** For in the real flying hardware ******************** -->
|
|
<target name="ap" board="px4fmu_4.0"/>
|
|
|
|
<!-- Towards a better and no messing it all up kind of aligner -->
|
|
<!--
|
|
<define name="AHRS_ALIGNER_SAMPLES_NB" value="200"/>
|
|
<define name="LOW_NOISE_THRESHOLD" value="30000"/>
|
|
<define name="LOW_NOISE_TIME" value="10"/>
|
|
-->
|
|
<define name="ADC_CHANNEL_VSUPPLY" value="ADC_1"/><!-- TODO to boardfile, if default remove define-->
|
|
|
|
|
|
<!-- <configure name="CPU_LED" value="1"/>--> <!-- Change to whatever you like -->
|
|
|
|
<!-- Note that PERIODIC_FREQUENCY should be least equal or greater than AHRS_PROPAGATE_FREQUENCY -->
|
|
<configure name="PERIODIC_FREQUENCY" value="512"/> <!-- unit="Hz" -->
|
|
|
|
<!--<define name="DISCO_GYRO_RANGE" value="MPU60X0_GYRO_RANGE_1000"/>-->
|
|
<!--<define name="DISCO_ACCEL_RANGE" value="MPU60X0_ACCEL_RANGE_16G"/>--><!-- Set to 8G maybe possible -->
|
|
<!--<define name="DISCO_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/>-->
|
|
<!--<define name="DISCO_SMPLRT_DIV" value="3"/>--><!-- Do not change randomly ;) -->
|
|
|
|
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/><!-- unit="Hz" -->
|
|
<configure name="AHRS_CORRECT_FREQUENCY" value="500"/> <!-- unit="Hz" -->
|
|
<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/><!-- TODO: best value unit="Hz" -->
|
|
|
|
<configure name="NAVIGATION_FREQUENCY" value="16"/> <!-- unit="Hz" -->
|
|
<configure name="CONTROL_FREQUENCY" value="120"/> <!-- unit="Hz" -->
|
|
<configure name="TELEMETRY_FREQUENCY" value="60"/> <!-- unit="Hz" -->
|
|
<configure name="MODULES_FREQUENCY" value="512"/> <!-- unit="Hz" -->
|
|
|
|
<module name="radio_control" type="sbus"/>
|
|
|
|
<module name="imu" type="mpu9250_spi">
|
|
<configure name="IMU_MPU9250_SPI_DEV" value="spi1"/>
|
|
<configure name="IMU_MPU9250_SPI_SLAVE_IDX" value="SPI_SLAVE2"/>
|
|
<define name="IMU_MPU9250_READ_MAG" value="FALSE"/>
|
|
<define name="IMU_MPU9250_GYRO_RANGE" value="MPU9250_GYRO_RANGE_2000" />
|
|
<!-- To be able (for now) to set AP IMU orientation -->
|
|
<!-- <define name="IMU_MPU9250_CHAN_X" value="1"/>
|
|
<define name="IMU_MPU9250_CHAN_Y" value="0"/>
|
|
<define name="IMU_MPU9250_CHAN_Z" value="2"/>
|
|
<define name="IMU_MPU9250_X_SIGN" value="-1"/>
|
|
<define name="IMU_MPU9250_Y_SIGN" value="-1"/>
|
|
<define name="IMU_MPU9250_Z_SIGN" value="-1"/> -->
|
|
</module>
|
|
|
|
<module name="mag" type="hmc58xx">
|
|
<!-- We will use the magnetometer that is available on our GPS board
|
|
Thi one is temperature compensated and furthest away from all other devices
|
|
so less influence (still to measure raw mag values to check this though )
|
|
In case we where sloppy building in the GPS+mag combo , we always are ;)
|
|
we need to compensate this a bit e.g. the pitch
|
|
lucky the tree axis are aligned already in hardware ;) -->
|
|
<!-- <define name="MAG_TO_IMU_THETA" value="6" unit="deg"/>-->
|
|
<configure name="MAG_HMC58XX_I2C_DEV" value="i2c1"/>
|
|
<define name="MODULE_HMC58XX_UPDATE_AHRS" value="FALSE"/><!-- When all calib and works to TRUE -->
|
|
<define name="HMC58XX_CHAN_X" value="1"/>
|
|
<define name="HMC58XX_CHAN_Y" value="0"/>
|
|
<define name="HMC58XX_CHAN_Z" value="2"/>
|
|
<define name="HMC58XX_CHAN_X_SIGN" value="-"/>
|
|
<define name="HMC58XX_CHAN_Y_SIGN" value="+"/>
|
|
<define name="HMC58XX_CHAN_Z_SIGN" value="+"/>
|
|
</module>
|
|
|
|
<!-- If you build in your GPS where the MAGNETOMETER resides on the board
|
|
not aligned with the Accelerometer/Gyro axis then set these values -->
|
|
<define name="MAG_TO_IMU_PHI" value="0.0" unit="deg"/>
|
|
<define name="MAG_TO_IMU_PSI" value="0.0" unit="deg"/>
|
|
<define name="MAG_TO_IMU_THETA" value="0.0" unit="deg"/>
|
|
|
|
<module name="actuators" type="pwm"/>
|
|
<!-- This GPS is a real ublox M8N, so setting can be saved, no need
|
|
for ubx_ucenter one has can set it oneself since we have all kinds
|
|
of nifty Galileo setting we rather keep that, but for now, laziness -->
|
|
<module name="gps" type="ubx_ucenter"/>
|
|
|
|
<!-- SBUS out is AETR by default but our transmitter sends TAER -->
|
|
<!-- <module name="radio_control" type="datalink">--> <!-- The output type of RX, over the air it can can be all kinds e.g. DSMX-->
|
|
<!-- <define name="RADIO_CONTROL_NB_CHANNEL" value="7"/>
|
|
</module>-->
|
|
|
|
<module name="current_sensor">
|
|
<define name="USE_ADC_3"/>
|
|
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
|
|
<define name="CURRENT_ESTIMATION_NONLINEARITY" value="1.3"/><!-- TODO determine -->
|
|
</module>
|
|
|
|
<module name="telemetry" type="transparent"/>
|
|
|
|
<module name="gps" type="ublox"/>
|
|
|
|
<define name="AGR_CLIMB"/> <!--Has aggressive mode handy for testing purposes -->
|
|
<define name="TUNE_AGRESSIVE_CLIMB"/>
|
|
|
|
<define name="STRONG_WIND"/>
|
|
<define name="WIND_INFO"/>
|
|
<define name="WIND_INFO_RET"/>
|
|
|
|
<define name="autopilot_motors_on" value="TRUE"/><!-- TODO: choose ;) -->
|
|
<!-- temp fix for geomag, normally only used for rotorcraft -->
|
|
<define name="SENSOR_SYNC_SEND"/> <!-- Temp for debugging Baro -->
|
|
<configure name="USE_BARO_BOARD" value="TRUE"/>
|
|
|
|
<!-- amount of time it take for the bat to trigger check -->
|
|
<!-- to avoid bat low spike detection when strong pullup which draws short sudden power-->
|
|
<!-- TODO: specificaly test for Disco see if needed or which value -->
|
|
<define name="BAT_CHECKER_DELAY" value="80" unit="s/10"/> <!-- in tenth of seconds per default use ELECTRICAL_PERIODIC_FREQ if you for some reason want it differently-->
|
|
|
|
<!-- Only one main battery so CATASTROPHIC_BATTERY kill should be somewhat delayed -->
|
|
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="410" unit="s/10"/> <!-- in tenth of seconds for engine kill or in ELECTRICAL_PERIODIC_FREQ-->
|
|
|
|
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
|
|
<define name="USE_AHRS_GPS_ACCELERATIONS" value="TRUE"/> <!-- forward acceleration compensation from GPS speed -->
|
|
<define name="USE_MAGNETOMETER_ONGROUND" value="TRUE"/> <!--DEFINE only used if float_dcm Use magnetic compensation before takeoff only while GPS course not good -->
|
|
|
|
<configure name="USE_MAGNETOMETER" value="TRUE"/><!-- should be as in USE the device -->
|
|
|
|
<!-- ************************* MODULES ************************* -->
|
|
|
|
<module name="ahrs" type="float_cmpl_quat"> <!-- Compare e.g. float_dcm -->
|
|
<configure name="AHRS_USE_MAGNETOMETER" value="TRUE"/> <!-- as in USE it for values in the AHRS -->
|
|
<configure name="AHRS_ALIGNER_LED" value="2"/><!-- Which color you want sir? ;) -->
|
|
<define name="AHRS_MAG_UPDATE_ALL_AXES" value="TRUE"/> <!-- if TRUE with those high roll n pith angles magneto should be calibrated well or use UKF autocalib -->
|
|
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/><!-- TRUE by default Use GPS course to update heading for time being,if FALSE data from magneto only -->
|
|
<!-- <define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="FALSE"/>--> <!--Already TRUE by default Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing)"-->
|
|
<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="FALSE"/> <!-- AHRS_GRAVITY_UPDATE_COORDINATED_TURN assumes the GPS speed is in the X axis direction. Quadshot, DelftaCopter and other hybrids can have the GPS speed in the negative Z direction" -->
|
|
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="FALSE"/> <!-- apply a low pass filter on rotational velocity"-->
|
|
<define name="AHRS_BIAS_UPDATE_HEADING_THRESHOLD" value="0.174533" unit="rad"/> <!-- don't update gyro bias if heading deviation is above this rotation threshold"-->
|
|
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="3.0" unit="m/s"/> <!-- CAREFULL, Don't update heading from GPS course if GPS ground speed is below is this threshold in m/s" -->
|
|
<!-- Some insights https://lists.nongnu.org/archive/html/paparazzi-devel/2013-10/msg00126.html -->
|
|
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0.5"/> <!-- TODO: determine Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
|
|
<define name="AHRS_ICQ_IMU_ID" value="ABI_BROADCAST"/> <!-- ABI sender id of IMU to use -->
|
|
<define name="AHRS_ICQ_MAG_ID" value="MAG_CALIB_UKF_ID" /><!-- for when using the mag_clib_ukf -->
|
|
</module>
|
|
|
|
<module name="ins" type="alt_float"/>
|
|
|
|
<module name="control" type="new"/>
|
|
<module name="navigation"/>
|
|
<!--<module name="imu_quality_assessment"/>--><!--needs fixing for FW fix test then disable after initial tuning-->
|
|
<module name="send_imu_mag_current"/> <!-- Can be Disabled after one time calibration, quite the same for all Discos -->
|
|
|
|
<!-- Also used if QNH needed -->
|
|
<module name="air_data">
|
|
<define name="CALC_AIRSPEED" value="FALSE"/><!-- we set use airspeed elsewhere-->
|
|
<define name="CALC_TAS_FACTOR" value="FALSE"/>
|
|
<define name="CALC_AMSL_BARO" value="TRUE"/>
|
|
</module>
|
|
|
|
<module name="geo_mag"/>
|
|
<module name="nav" type="line"/>
|
|
|
|
</firmware>
|
|
|
|
|
|
|
|
<!-- ************************* ACTUATORS ************************* -->
|
|
<servos>
|
|
<servo name="S_THROTTLE_LEFT" no="0" min="1100" neutral="1110" max="1900"/>
|
|
<servo name="S_THROTTLE_RIGHT" no="1" min="1100" neutral="1110" max="1900"/>
|
|
<servo name="S_ELEVON_LEFT" no="2" min="1100" neutral="1500" max="1900"/>
|
|
<servo name="S_ELEVON_RIGHT" no="3" min="1900" neutral="1500" max="1100"/>
|
|
</servos>
|
|
|
|
<section name="ServoPositions">
|
|
<define name="ThrottleHigh()" value="(imcu_get_command(COMMAND_THROTTLE)>9600/2)" />
|
|
</section>
|
|
|
|
<!-- ********************* SERVO MIXER *************************** -->
|
|
<section name="MIXER">
|
|
<define name="ELEVON_ROLL_FACTOR" value="0.7f"/>
|
|
<define name="ELEVON_PITCH_FACTOR" value="0.6f"/>
|
|
<define name="ELEVON_YAW_FACTOR" value="0.9f"/>
|
|
<!-- Set up/down deflection differences, needs many in flight tests to find acceptable values-->
|
|
<define name="ELEVON_DIFF" value="0.3f"/> <!-- TODO: not used yet, not tuned yet... -->
|
|
</section>
|
|
|
|
<!-- ************************ COMMAND LAWS ***************************** -->
|
|
<command_laws>
|
|
|
|
<let var="aileron" value="@ROLL * ELEVON_ROLL_FACTOR"/>
|
|
<let var="elevator" value="@PITCH * ELEVON_PITCH_FACTOR"/>
|
|
<let var="leftyaw" value="(@YAW >= 0? 0 : 1)"/>
|
|
<let var="rightyaw" value="(1 - $leftyaw)"/>
|
|
<!-- opposite of left -->
|
|
<let var="rudderleft" value="-(@YAW * $leftyaw) * ELEVON_YAW_FACTOR"/>
|
|
<let var="rudderright" value="(@YAW * $rightyaw) * ELEVON_YAW_FACTOR"/>
|
|
<let var="throttleleft" value="@THROTTLE*$leftyaw"/>
|
|
<let var="throttleright" value="@THROTTLE*$rightyaw"/>
|
|
<set servo="S_THROTTLE_LEFT" value="$throttleleft"/>
|
|
<set servo="S_THROTTLE_RIGHT" value="$throttleright"/>
|
|
<set servo="S_ELEVON_LEFT" value="$elevator - $aileron + $rudderleft"/>
|
|
<set servo="S_ELEVON_RIGHT" value="$elevator + $aileron + $rudderright "/>
|
|
</command_laws>
|
|
|
|
<!-- ********************** RC COMMANDS ************************** -->
|
|
<rc_commands>
|
|
<set command="THROTTLE" value="@THROTTLE"/>
|
|
<set command="ROLL" value="@ROLL"/>
|
|
<set command="PITCH" value="@PITCH"/>
|
|
<set command="YAW" value="@YAW"/>
|
|
<!-- for EXTRAs e.g. tuning via RC these ones below -->
|
|
<!-- <set command="GAIN1" value="@GAIN1"/> -->
|
|
<!-- <set command="CALIB" value="@GAIN2"/> -->
|
|
</rc_commands>
|
|
|
|
<!-- ************************ AUTO RC COMMANDS ***************************** -->
|
|
<auto_rc_commands>
|
|
<!--**TEMPorary for heading change steering if someting not OK with course in Autonomous flight **-->
|
|
<set command="YAW" value="@YAW"/>
|
|
<!-- To be able to set gain values via RC Transmitter these ones below.
|
|
This way the can keep his eye on a fast moving plane and set somegain values
|
|
makes life of a single testpiloted AC much easier -->
|
|
<!--<set command="GAIN1" value="@GAIN1"/>
|
|
<set command="CALIB" value="@GAIN2"/>-->
|
|
<!-- Todo to determin best pitch for flare in auto2 one can add Pitch command temporary also-->
|
|
<!--<set command="PITCH" value="@PITCH"/>-->
|
|
</auto_rc_commands>
|
|
|
|
<!-- ************************ COMMANDS ***************************** -->
|
|
<commands>
|
|
<axis name="THROTTLE" failsafe_value="0"/>
|
|
<axis name="ROLL" failsafe_value="5"/>
|
|
<axis name="PITCH" failsafe_value="-6"/>
|
|
<axis name="YAW" failsafe_value="0"/>
|
|
</commands>
|
|
|
|
<!-- ************************ AUTO1 ***************************** -->
|
|
<!-- 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="45" unit="deg"/> <!-- More autority while testflying for first time -->
|
|
<define name="MAX_PITCH" value="40" unit="deg"/> <!-- More autority while testflying for first time -->
|
|
</section>
|
|
|
|
<!-- ************************ TRIM ***************************** -->
|
|
<section name="TRIM" prefix="COMMAND_">
|
|
<define name="ROLL_TRIM" value="0.0"/>
|
|
<define name="PITCH_TRIM" value="0.0"/>
|
|
</section>
|
|
|
|
<!-- ************************ FAILSAFE ***************************** -->
|
|
<!-- Strategy for failsafe is slow wide circles and loosing height in a controlled fashion -->
|
|
<section name="FAILSAFE" prefix="FAILSAFE_">
|
|
<define name="DEFAULT_THROTTLE" value="0.0" unit="%"/>
|
|
<define name="DEFAULT_ROLL" value="15.0" unit="deg"/>
|
|
<define name="DEFAULT_PITCH" value="-10.0" unit="deg"/>
|
|
<define name="DELAY_WITHOUT_GPS" value="5" unit="s"/>
|
|
</section>
|
|
|
|
<!-- ************************* IMU ************************* -->
|
|
<section name="IMU" prefix="IMU_">
|
|
|
|
<!-- ***************** GYRO *****************-->
|
|
<define name="GYRO_P_SENS" value=" 1.01" integer="16"/>
|
|
<define name="GYRO_Q_SENS" value=" 1.01" integer="16"/>
|
|
<define name="GYRO_R_SENS" value=" 1.01" integer="16"/>
|
|
|
|
<!-- ***************** ACCELO *****************-->
|
|
<!-- Replace these values with your own calibration, on the correct sensor -->
|
|
<define name="ACCEL_X_NEUTRAL" value="-72"/>
|
|
<define name="ACCEL_Y_NEUTRAL" value="-3"/>
|
|
<define name="ACCEL_Z_NEUTRAL" value="16"/>
|
|
|
|
<define name="ACCEL_X_SENS" value="4.88551667342" integer="16"/>
|
|
<define name="ACCEL_Y_SENS" value="4.87127085018" integer="16"/>
|
|
<define name="ACCEL_Z_SENS" value="4.81849471549" integer="16"/>
|
|
|
|
<!-- ***************** MAGNETO *****************-->
|
|
<!--define name="MAG_OFFSET" value="-?.0" unit="deg"--> <!-- TODO: at least 3 axis in worst case -->
|
|
|
|
<define name="MAG_X_NEUTRAL" value="-76"/>
|
|
<define name="MAG_Y_NEUTRAL" value="-148"/>
|
|
<define name="MAG_Z_NEUTRAL" value="-544"/>
|
|
<define name="MAG_X_SENS" value="9.32170888384" integer="16"/>
|
|
<define name="MAG_Y_SENS" value="9.08947221668" integer="16"/>
|
|
<define name="MAG_Z_SENS" value="9.38604192016" integer="16"/>
|
|
|
|
<!-- Should be same for everyone -->
|
|
<define name="MAG_X_CURRENT_COEF" value="0.000321738038902"/>
|
|
<define name="MAG_Y_CURRENT_COEF" value="-0.000820010304048"/>
|
|
<define name="MAG_Z_CURRENT_COEF" value="0.00139218924958"/>
|
|
|
|
<define name="BODY_TO_IMU_PHI" value="0.0" unit="deg"/>
|
|
<define name="BODY_TO_IMU_THETA" value="0.0" unit="deg"/><!-- TODO: validate -->
|
|
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/>
|
|
</section>
|
|
|
|
<!-- ************************* AHRS ************************* -->
|
|
<section name="AHRS" prefix="AHRS_">
|
|
<!-- Values used if no GNSS fix, on 3D fix is update by geo_mag module -->
|
|
<!-- Better keep geo_mag module ifyou have a GNSDS, else replace the values with your local magnetic field -->
|
|
|
|
<!-- Local Magnetic field DE2018 -->
|
|
<define name="H_X" value="0.403761"/>
|
|
<define name="H_Y" value="0.014826"/>
|
|
<define name="H_Z" value="0.914744"/>
|
|
</section>
|
|
|
|
<!-- ************************* INS ************************* -->
|
|
<section name="INS">
|
|
<!-- For those super precice target landings ;) well better build in a uBLox M8P-->
|
|
<define name="INS_BODY_TO_GPS_X" value="0.0" unit="m"/>
|
|
<define name="INS_BODY_TO_GPS_Y" value="0.0" unit="m"/>
|
|
<define name="INS_BODY_TO_GPS_Z" value="0.03" unit="m"/>
|
|
|
|
<!-- <define name="USE_INS_MODULE"/> -->
|
|
|
|
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
|
|
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="deg"/><!-- not taken into account -->
|
|
|
|
<!-- Use GPS altitude measurments and set the R gain -->
|
|
<define name="USE_GPS_ALT" value="1"/>
|
|
<define name="VFF_R_GPS" value="0.02"/>
|
|
</section>
|
|
|
|
<!-- ************************* MAG_CALIB_UKF ************************* -->
|
|
<section name="MAG_CALIB_UKF" prefix="MAG_CALIB_UKF_">
|
|
<define name="HOTSTART" value="FALSE"/><!-- for faster convergence flights to flight -->
|
|
<define name="HOTSTART_SAVE_FILE" value=""/><!--<define name="HOTSTART_SAVE_FILE" value="/data/ftp/internal_000/mag_ukf_calib.txt"/>-->
|
|
<define name="NORM" value="1.0f"/>
|
|
<define name="NOISE_RMS" value="5e-2f"/>
|
|
<define name="GEO_MAG_TIMEOUT" value="0"/>
|
|
<define name="INITIAL_STATE" value="0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0" type="float[]"/>
|
|
<define name="VERBOSE" value="FALSE"/><!-- Disable after testing -->
|
|
</section>
|
|
|
|
<!-- ************************* GAINS ************************* -->
|
|
<!-- ************************* H ************************* -->
|
|
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
|
|
|
<define name="COURSE_PGAIN" value="1.25"/><!-- TODO: Tune values -->
|
|
<define name="COURSE_DGAIN" value="0.2"/><!-- TODO: Tune values -->
|
|
<define name="COURSE_TAU" value="0.5"/><!-- TODO: Tune values -->
|
|
<!--
|
|
The prebank is an adjustment to the roll setting which is performed when the aircraft is
|
|
trying to do a circle and when it is close to the circumference of the circle. This way
|
|
it does not fly straight into the circumference but instead it starts to make a roll as
|
|
the one needed to fly in circles.
|
|
There is a value in the airframe file COURSE_PRE_BANK_CORRECTION which can be used to
|
|
increase o decrease the effect. If set to 1 then the normal prebank is done.
|
|
If set to 0.5 then half of the additional roll is done. This causes the aircraft to not roll
|
|
enough in order to fly the intended circle and it ends up flying in a larger circle.
|
|
A value > 1 makes it fly a smaller circle.
|
|
|
|
https://github.com/paparazzi/paparazzi/blob/master/sw/airborne/modules/nav.c#L132
|
|
-->
|
|
<define name="COURSE_PRE_BANK_CORRECTION" value="0.97"/>
|
|
|
|
<define name="ROLL_MAX_SETPOINT" value="75" unit="deg"/>
|
|
<define name="PITCH_MAX_SETPOINT" value="60" unit="deg"/>
|
|
<define name="PITCH_MIN_SETPOINT" value="-60" unit="deg"/>
|
|
|
|
<define name="PITCH_PGAIN" value="6500"/>
|
|
<define name="PITCH_DGAIN" value="100"/>
|
|
<define name="PITCH_IGAIN" value="30"/>
|
|
<define name="PITCH_KFFA" value="10."/>
|
|
<define name="PITCH_KFFD" value="0."/>
|
|
|
|
<define name="ELEVATOR_OF_ROLL" value="1500" unit="PPRZ_MAX"/>
|
|
<define name="ROLL_SLEW" value="0.5"/><!-- TODO: Determine best value-->
|
|
<define name="ROLL_ATTITUDE_GAIN" value="11000."/>
|
|
<define name="ROLL_RATE_GAIN" value="1400"/>
|
|
<define name="ROLL_IGAIN" value="100."/>
|
|
<define name="ROLL_KFFA" value="100"/>
|
|
<define name="ROLL_KFFD" value="0"/>
|
|
|
|
<!--<define name="PITCH_OF_ROLL" value="4." unit="deg"/>--><!-- TODO: : ?-->
|
|
<define name="AILERON_OF_THROTTLE" value="0.0"/><!-- TODO: : ?-->
|
|
|
|
</section>
|
|
|
|
<!-- We have value of Classic as well as ETECS, this since airframe is first flown "Classic" the ETECS, make tunng a bit easier
|
|
It is NOT (yet?) switchable on the fly in flight -->
|
|
|
|
<!-- ****************************** V ****************************** -->
|
|
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
|
<!-- power -->
|
|
<define name="POWER_CTL_BAT_NOMINAL" value="11.5" unit="volt"/>
|
|
|
|
<!-- Classic -->
|
|
<!-- outer loop proportional gain -->
|
|
<define name="ALTITUDE_PGAIN" value="0.15"/> <!--unit="(m/s)/m"-->
|
|
<!-- disable climb rate limiter -->
|
|
<define name="AUTO_CLIMB_LIMIT" value="2*V_CTL_ALTITUDE_MAX_CLIMB"/>
|
|
<!-- auto throttle -->
|
|
<!-- Cruise throttle + limits -->
|
|
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.30" unit="%"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.50" unit="%"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.90" 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.39" unit="%/(m/s)"/> <!-- TODO: Determine -->
|
|
|
|
<!-- Climb loop (throttle) -->
|
|
<define name="AUTO_THROTTLE_PGAIN" value="0.005" 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.11" unit="rad/(m/s)"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_PITCH" value="0." unit="rad"/> <!-- default 0 -->
|
|
|
|
<define name="THROTTLE_SLEW_LIMITER" value="0.6" unit="m/s/s"/> <!-- Limiter for e.g. a powerful motor -->
|
|
|
|
<!-- airspeed control -->
|
|
<!-- Best to never set AUTO_AIRSPEED_SETPOINT lower than airframe stall speed if you hate repairs ;) -->
|
|
<!-- investigate: howto if higher then _AIRSPEED_SETPOINT then airframe tries to maintain a constand ground speed UNKNOWN -->
|
|
<define name="AUTO_AIRSPEED_SETPOINT" value="15.0" unit="m/s"/>
|
|
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.12" unit="%/(m/s)"/>
|
|
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.09"/>
|
|
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.02"/>
|
|
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.12" unit="degree/(m/s)"/>
|
|
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
|
|
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.06"/>
|
|
|
|
<define name="AIRSPEED_MAX" value="23.0" unit="m/s"/>
|
|
<define name="AIRSPEED_MIN" value="9.0" unit="m/s"/>
|
|
|
|
<!-- pitch trim -->
|
|
<define name="PITCH_LOITER_TRIM" value="0." unit="deg"/> <!-- Non ETECS -->
|
|
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/> <!-- Non ETECS -->
|
|
|
|
<!-- groundspeed control -->
|
|
<define name="AUTO_GROUNDSPEED_SETPOINT" value="5.0" unit="m/s"/>
|
|
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.8"/>
|
|
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.2"/>
|
|
|
|
<define name="AIRSPEED_PGAIN" value="0.19"/>
|
|
|
|
<!-- outer loop saturation -->
|
|
<define name="ALTITUDE_MAX_CLIMB" value="3.0" unit="m/s"/> <!-- TODO: Determine -->
|
|
<define name="MAX_ACCELERATION" value="0.9" unit="G"/> <!-- TODO: Determine -->
|
|
|
|
<!-- auto pitch inner loop -->
|
|
|
|
<!-- Climb loop (pitch) -->
|
|
<define name="AUTO_PITCH_PGAIN" value="0.030"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_PITCH_DGAIN" value="0.01"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_PITCH_IGAIN" value="0.00"/> <!-- TODO: Determine -->
|
|
<!--define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/-->
|
|
<define name="AUTO_PITCH_MAX_PITCH" value="55" unit="deg"/><!-- TODO: Determine default and best -->
|
|
<define name="AUTO_PITCH_MIN_PITCH" value="-55" unit="deg"/><!-- TODO: Determine default and best -->
|
|
|
|
<!-- ============= ETECS ============= -->
|
|
<define name="ENERGY_TOT_PGAIN" value="0.35"/> <!-- TODO: Determine -->
|
|
<define name="ENERGY_TOT_IGAIN" value="0.20"/> <!-- TODO: Determine -->
|
|
<define name="ENERGY_DIFF_PGAIN" value="0.40"/> <!-- TODO: Determine -->
|
|
<define name="ENERGY_DIFF_IGAIN" value="0.10"/> <!-- TODO: Determine -->
|
|
|
|
<define name="GLIDE_RATIO" value="7."/> <!-- 7 to 1 --> <!-- TODO: Determine default but also with heavier batt -->
|
|
|
|
<define name="AUTO_THROTTLE_OF_AIRSPEED_PGAIN" value="0.06"/>
|
|
<define name="AUTO_THROTTLE_OF_AIRSPEED_IGAIN" value="0.01"/>
|
|
|
|
<define name="AUTO_PITCH_OF_AIRSPEED_PGAIN" value="0.01"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_PITCH_OF_AIRSPEED_IGAIN" value="0.003"/> <!-- TODO: Determine -->
|
|
<define name="AUTO_PITCH_OF_AIRSPEED_DGAIN" value="0.03"/> <!-- TODO: Determine -->
|
|
|
|
</section>
|
|
|
|
<!-- ************************* AGGRESSIVE *************************** -->
|
|
<section name="AGGRESSIVE" prefix="AGR_">
|
|
<define name="BLEND_START" value="40" unit="m"/> <!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
|
<define name="BLEND_END" value="10" unit="m"/> <!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
|
<define name="CLIMB_THROTTLE" value="0.99" unit="%"/> <!-- Throttlelevel for Aggressive Climb -->
|
|
<define name="CLIMB_PITCH" value="45" unit="deg"/> <!-- Pitch for Aggressive Climb -->
|
|
<define name="DESCENT_THROTTLE" value="0.7" unit="%"/> <!-- Throttlelevel for Aggressive Decent -->
|
|
<define name="DESCENT_PITCH" value="-45" unit="deg"/> <!-- Pitch for Aggressive Decent -->
|
|
<define name="CLIMB_NAV_RATIO" value="0.8" unit="%"/> <!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
|
<define name="DESCENT_NAV_RATIO" value="1.0" unit="%"/>
|
|
</section>
|
|
|
|
<!-- **************************** BAT ****************************** -->
|
|
<section name="BAT">
|
|
<!-- <define name="MAX_BAT_CAPACITY" value="2700" unit="mAh"/> --> <!-- The Default Parrot Disco 2700mAh battery -->
|
|
<!--<define name="MilliAmpereOfAdc(_adc)" value="(_adc-632)*4.14"/>--> <!-- TODO: calibrate even better -->
|
|
<!-- tested at V 11.7 the avg --> <!-- 1idel RPM then 1.0A half throttle 4A-->
|
|
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="600" unit="mA"/> <!-- 500mA, with additional RC receiver ~600mA -->
|
|
<define name="MILLIAMP_AT_FULL_THROTTLE" value="11000" unit="mA"/> <!-- At 11.7 10.6 A at 12.2v 11.0A rounded then to 11000 to be at safe side-->
|
|
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/> <!-- 3S lipo 3x4.2 = 12.6 -->
|
|
<define name="LOW_BAT_LEVEL" value="10.6" unit="V"/>
|
|
<define name="CRITIC_BAT_LEVEL" value="10.0" unit="V"/>
|
|
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/> <!-- TODO: test when AP board switches off -->
|
|
<define name="MIN_BAT_LEVEL" value="9.0" unit="V"/><!-- Get rid if this one maybe? -->
|
|
</section>
|
|
|
|
<!-- ***************************** MISC **************************** -->
|
|
<section name="MISC">
|
|
<!-- All for use with default motor and propeller -->
|
|
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/> <!-- TODO: Determine -->
|
|
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/> <!-- TODO: Determine -->
|
|
<define name="MAXIMUM_AIRSPEED" value="23." unit="m/s"/> <!-- TODO: Determine -->
|
|
|
|
<!-- Values here are only referred to by the flightplan m*_s*_airspeed.xml in final AC -->
|
|
<define name="CLIMB_AIRSPEED" value="12." unit="m/s"/> <!-- TODO: Determine max and get best values -->
|
|
<define name="TRACKING_AIRSPEED" value="18." unit="m/s"/> <!-- TODO: Tune to optimum value -->
|
|
<define name="GLIDE_AIRSPEED" value="10." unit="m/s"/> <!-- TODO: Tune to optimum value -->
|
|
<define name="STALL_AIRSPEED" value="7." unit="m/s"/> <!-- TODO: Determine limit of plane in testflights (and set at this * 1.1?) -->
|
|
<define name="RACE_AIRSPEED" value="22." unit="m/s"/>
|
|
<define name="MIN_SPEED_FOR_TAKEOFF" value="11." unit="m/s"/> <!-- TODO: determine and change to make it for airspeed -->
|
|
<!-- AIRSPEED_SETPOINT_SLEW is in m/s/s - e.g. a change from 15m/s to 18m/s takes 3s with the default value of 1.-->
|
|
<define name="AIRSPEED_SETPOINT_SLEW" value="1.5" unit="m/s/s"/> <!-- TODO: Tune to optimum value -->
|
|
|
|
<define name="TAKEOFF_PITCH_ANGLE" value="35" unit="deg"/> <!-- TODO: Tune to optimum value -->
|
|
<define name="FLARE_PITCH_ANGLE" value="40" unit="deg"/> <!-- TODO: Tune to optimum value -->
|
|
<define name="NAV_GLIDE_PITCH_TRIM" value="1.0" unit="deg"/> <!-- TODO: determine -->
|
|
|
|
<define name="KILL_MODE_DISTANCE" value="MAX_DIST_FROM_HOME*1.3+HOME_RADIUS" unit="m"/> <!-- improve value by default turn radius calc -->
|
|
|
|
<define name="DEFAULT_CIRCLE_RADIUS" value="35." unit="m"/> <!-- TODO: Determine convinient minimum -->
|
|
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
|
<define name="LANDING_CIRCLE_RADIUS" value="30." unit="m"/> <!-- TODO: determine optimum minimum -->
|
|
<!-- MIN_CIRCLE_RADIUS used and needed for spiral navigation function and panic autolanding turns-->
|
|
<define name="MIN_CIRCLE_RADIUS" value="25." unit="m"/> <!-- TODO: determine optimum minimum -->
|
|
|
|
<define name="CARROT" value="4." unit="s"/>
|
|
|
|
<!--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="AP_MODE_AUTO2"/>
|
|
|
|
<!-- TODO: SET some modem values with multipoint also the $AC_ID -->
|
|
<!-- Here XBEE init will be misused to set SiK Si10xx based modems as the Hope and RFdesign -->
|
|
<!-- <define name="XBEE_INIT" value="ATS17=$AC_ID\rATS16=134\rAT&W\rATZ\r" type="string"/> -->
|
|
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
|
</section>
|
|
|
|
<!-- ************************ GLS_APPROACH ************************* -->
|
|
<!-- see: -->
|
|
<section name="GLS_APPROACH" prefix="APP_">
|
|
<define name="DISTANCE_AF_SD" value="20" unit="m"/>
|
|
<define name="ANGLE" value="4" unit="deg"/> <!-- TODO: determine optimal value -->
|
|
<define name="INTERCEPT_AF_SD" value="80" unit="m"/> <!--Watch it after landing airspeed = 0 thus aircraft throttles up again, not good -->
|
|
<!--<define name="INTERCEPT_RATE" value="0.624" unit="m/s/s"/>-->
|
|
<define name="TARGET_SPEED" value="12.0" unit="m/s"/> <!-- Via airspeed -->
|
|
</section>
|
|
|
|
<!-- ********************** GCS SPECIFICS ************************** -->
|
|
<section name="GCS">
|
|
<define name="AC_ICON" value="flyingwing"/>
|
|
<define name="ALT_SHIFT_PLUS_PLUS" value="40"/>
|
|
<define name="ALT_SHIFT_PLUS" value="20"/>
|
|
<define name="ALT_SHIFT_MINUS" value="-20"/>
|
|
</section>
|
|
|
|
</airframe>
|