mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
ea77d1a395
- unused airframe xml files fronm conf_example and conf_test.xml were moved to untested folder closes #1249
204 lines
7.5 KiB
XML
204 lines
7.5 KiB
XML
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
|
|
|
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
|
|
|
|
<airframe name="lisa_asctec">
|
|
|
|
<servos driver="Asctec_v2">
|
|
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
|
|
<servo name="BACK" no="1" min="0" neutral="3" max="200"/>
|
|
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
|
|
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
|
|
</servos>
|
|
|
|
<commands>
|
|
<axis name="PITCH" failsafe_value="0"/>
|
|
<axis name="ROLL" failsafe_value="0"/>
|
|
<axis name="YAW" failsafe_value="0"/>
|
|
<axis name="THRUST" failsafe_value="0"/>
|
|
</commands>
|
|
|
|
<!-- for the sim -->
|
|
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
|
<define name="NB" value="4"/>
|
|
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
|
|
</section>
|
|
|
|
<section name="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="{ 0 , 0, 256, -256 }"/>
|
|
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/>
|
|
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/>
|
|
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
|
|
</section>
|
|
|
|
<command_laws>
|
|
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
|
<set servo="FRONT" value="motor_mixing.commands[0]"/>
|
|
<set servo="BACK" value="motor_mixing.commands[1]"/>
|
|
<set servo="RIGHT" value="motor_mixing.commands[2]"/>
|
|
<set servo="LEFT" value="motor_mixing.commands[3]"/>
|
|
</command_laws>
|
|
|
|
<section name="IMU" prefix="IMU_">
|
|
<define name="GYRO_P_NEUTRAL" value="32276"/>
|
|
<define name="GYRO_Q_NEUTRAL" value="33987"/>
|
|
<define name="GYRO_R_NEUTRAL" value="32801"/>
|
|
<define name="GYRO_P_SENS" value="0.92466" integer="16"/>
|
|
<define name="GYRO_Q_SENS" value="0.93226" integer="16"/>
|
|
<define name="GYRO_R_SENS" value="0.92943" integer="16"/>
|
|
<define name="GYRO_PQ_SENS" value="0.0" integer="16"/>
|
|
<define name="GYRO_PR_SENS" value="0.0" integer="16"/>
|
|
<define name="GYRO_QR_SENS" value="0.0" integer="16"/>
|
|
|
|
<define name="ACCEL_X_NEUTRAL" value="25875"/>
|
|
<define name="ACCEL_Y_NEUTRAL" value="26273"/>
|
|
<define name="ACCEL_Z_NEUTRAL" value="26152"/>
|
|
<define name="ACCEL_X_SENS" value="1.8788156268" integer="16"/>
|
|
<define name="ACCEL_Y_SENS" value="1.88941543145" integer="16"/>
|
|
<define name="ACCEL_Z_SENS" value="1.90349115464" integer="16"/>
|
|
<define name="ACCEL_XY_SENS" value="0.0" integer="16"/>
|
|
<define name="ACCEL_XZ_SENS" value="0.0" integer="16"/>
|
|
<define name="ACCEL_YZ_SENS" value="0.0" integer="16"/>
|
|
|
|
<define name="MAG_X_NEUTRAL" value="0"/>
|
|
<define name="MAG_Y_NEUTRAL" value="0"/>
|
|
<define name="MAG_Z_NEUTRAL" value="0"/>
|
|
<define name="MAG_X_SENS" value="1." integer="16"/>
|
|
<define name="MAG_Y_SENS" value="1." integer="16"/>
|
|
<define name="MAG_Z_SENS" value="1." integer="16"/>
|
|
|
|
<define name="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="45." unit="deg"/>
|
|
|
|
</section>
|
|
|
|
<section name="AUTOPILOT">
|
|
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
|
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
|
<define name="MODE_AUTO2" value="AP_MODE_HOVER_Z_HOLD"/>
|
|
</section>
|
|
|
|
<section name="BAT">
|
|
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
|
</section>
|
|
|
|
|
|
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
|
|
|
<define name="SP_MAX_P" value="10000"/>
|
|
<define name="SP_MAX_Q" value="10000"/>
|
|
<define name="SP_MAX_R" value="10000"/>
|
|
|
|
<define name="GAIN_P" value="400"/>
|
|
<define name="GAIN_Q" value="400"/>
|
|
<define name="GAIN_R" value="350"/>
|
|
|
|
</section>
|
|
|
|
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
|
|
|
<!-- setpoints -->
|
|
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
|
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
|
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
|
<define name="DEADBAND_R" value="250"/>
|
|
|
|
<!-- reference -->
|
|
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
|
|
<define name="REF_ZETA_P" value="0.85"/>
|
|
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
|
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
|
|
|
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
|
|
<define name="REF_ZETA_Q" value="0.85"/>
|
|
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
|
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
|
|
|
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
|
|
<define name="REF_ZETA_R" value="0.85"/>
|
|
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
|
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
|
|
|
<!-- feedback -->
|
|
<define name="PHI_PGAIN" value="900"/>
|
|
<define name="PHI_DGAIN" value="200"/>
|
|
<define name="PHI_IGAIN" value="200"/>
|
|
|
|
<define name="THETA_PGAIN" value="900"/>
|
|
<define name="THETA_DGAIN" value="200"/>
|
|
<define name="THETA_IGAIN" value="200"/>
|
|
|
|
<define name="PSI_PGAIN" value="900"/>
|
|
<define name="PSI_DGAIN" value="200"/>
|
|
<define name="PSI_IGAIN" value="10"/>
|
|
|
|
<!-- feedforward -->
|
|
<define name="PHI_DDGAIN" value=" 200"/>
|
|
<define name="THETA_DDGAIN" value=" 200"/>
|
|
<define name="PSI_DDGAIN" value=" 200"/>
|
|
|
|
</section>
|
|
|
|
<section name="INS" prefix="INS_">
|
|
</section>
|
|
|
|
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
|
<define name="HOVER_KP" value="500"/>
|
|
<define name="HOVER_KD" value="200"/>
|
|
<define name="HOVER_KI" value="100"/>
|
|
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
|
|
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
|
|
</section>
|
|
|
|
|
|
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
|
<define name="PGAIN" value="100"/>
|
|
<define name="DGAIN" value="100"/>
|
|
<define name="IGAIN" value="0"/>
|
|
</section>
|
|
|
|
<section name="SIMULATOR" prefix="NPS_">
|
|
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
|
<define name="JSBSIM_MODEL" value=""simple_quad""/>
|
|
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
|
</section>
|
|
|
|
<modules main_freq="512">
|
|
</modules>
|
|
|
|
<firmware name="rotorcraft">
|
|
<target name="ap" board="lisa_l_1.1">
|
|
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
|
|
<subsystem name="motor_mixing"/>
|
|
<subsystem name="actuators" type="asctec_v2"/>
|
|
<subsystem name="telemetry" type="transparent"/>
|
|
<define name="USE_I2C_ACTUATORS_REBOOT_HACK"/>
|
|
</target>
|
|
<target name="nps" board="pc">
|
|
<subsystem name="fdm" type="jsbsim"/>
|
|
<subsystem name="radio_control" type="ppm"/>
|
|
<subsystem name="motor_mixing"/>
|
|
<subsystem name="actuators" type="mkk"/>
|
|
</target>
|
|
|
|
<subsystem name="radio_control" type="spektrum">
|
|
<define name="RADIO_MODE" value="RADIO_AUX2"/>
|
|
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
|
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
|
|
</subsystem>
|
|
|
|
<subsystem name="imu" type="b2_v1.1"/>
|
|
<subsystem name="gps" type="ublox"/>
|
|
<subsystem name="stabilization" type="int_euler"/>
|
|
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
|
<subsystem name="ins"/>
|
|
</firmware>
|
|
|
|
</airframe>
|