mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-04 22:17:01 +08:00
[airframes] CDW
This commit is contained in:
@@ -0,0 +1,224 @@
|
|||||||
|
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||||
|
|
||||||
|
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
|
||||||
|
|
||||||
|
<airframe name="lisa_asctec">
|
||||||
|
<!-- ************************* FIRMWARE ************************* -->
|
||||||
|
|
||||||
|
<firmware name="rotorcraft">
|
||||||
|
<target name="ap" board="lisa_l_1.0">
|
||||||
|
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
|
||||||
|
<subsystem name="radio_control" type="ppm"/>
|
||||||
|
<subsystem name="motor_mixing"/>
|
||||||
|
<subsystem name="actuators" type="asctec_v2"/>
|
||||||
|
<subsystem name="telemetry" type="xbee_api"/>
|
||||||
|
<define name="RADIO_KILL_SWITCH" value="RADIO_FLAPS"/>
|
||||||
|
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>
|
||||||
|
<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="imu" type="aspirin_v2.1"/>
|
||||||
|
<subsystem name="gps" type="ublox"/>
|
||||||
|
<subsystem name="stabilization" type="int_euler"/>
|
||||||
|
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||||
|
<subsystem name="ins" type="hff"/>
|
||||||
|
</firmware>
|
||||||
|
|
||||||
|
<firmware name="lisa_test_progs">
|
||||||
|
<target name="test_led" board="lisa_l_1.0"/>
|
||||||
|
<target name="test_uart" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_servos" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_telemetry" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_baro" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_imu_b2" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_imu_b2_2" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_imu_aspirin" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_rc_spektrum" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_rc_ppm" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_adc" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_hmc5843" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_itg3200" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_adxl345" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_esc_mkk_simple" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_esc_asctecv1_simple" board="lisa_l_1.1"/>
|
||||||
|
<!--target name="test_actuators_mkk" board="lisa_l_1.1"/>
|
||||||
|
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/-->
|
||||||
|
</firmware>
|
||||||
|
|
||||||
|
<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>
|
||||||
|
|
||||||
|
<!-- ************************* MODULES ************************* -->
|
||||||
|
|
||||||
|
<modules main_freq="512">
|
||||||
|
<!-- <load name="high_speed_logger_spi_link.xml"/> -->
|
||||||
|
<load name="imu_quality_assessment.xml"/>
|
||||||
|
</modules>
|
||||||
|
|
||||||
|
<!-- ************************* ACTUATORS ************************* -->
|
||||||
|
|
||||||
|
<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>
|
||||||
|
|
||||||
|
<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"/>
|
||||||
|
<!-- Driver expects: Front - Back - Left - Right -->
|
||||||
|
<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>
|
||||||
|
|
||||||
|
<command_laws>
|
||||||
|
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||||
|
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||||
|
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||||
|
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||||
|
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||||
|
</command_laws>
|
||||||
|
|
||||||
|
<!-- ************************* SENSORS ************************* -->
|
||||||
|
|
||||||
|
<section name="IMU" prefix="IMU_">
|
||||||
|
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||||
|
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||||
|
<define name="ACCEL_Z_NEUTRAL" value="200"/>
|
||||||
|
<define name="ACCEL_X_SENS" value="9.810" integer="16"/>
|
||||||
|
<define name="ACCEL_Y_SENS" value="9.810" integer="16"/>
|
||||||
|
<define name="ACCEL_Z_SENS" value="9.810" 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="180." unit="deg"/>
|
||||||
|
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||||
|
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="INS" prefix="INS_">
|
||||||
|
<define name="BARO_SENS" value="10." integer="16"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<!-- ************************* GAINS ************************* -->
|
||||||
|
|
||||||
|
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||||
|
<define name="SP_MAX_P" value="10000"/>
|
||||||
|
<define name="SP_MAX_Q" value="10000"/>
|
||||||
|
<define name="SP_MAX_R" value="10000"/>
|
||||||
|
<define name="GAIN_P" value="400"/>
|
||||||
|
<define name="GAIN_Q" value="400"/>
|
||||||
|
<define name="GAIN_R" value="350"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||||
|
<!-- setpoints -->
|
||||||
|
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||||
|
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||||
|
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||||
|
<define name="DEADBAND_R" value="250"/>
|
||||||
|
<!-- reference -->
|
||||||
|
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_P" value="0.85"/>
|
||||||
|
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||||
|
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_Q" value="0.85"/>
|
||||||
|
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||||
|
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_R" value="0.85"/>
|
||||||
|
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||||
|
<!-- 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="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||||
|
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||||
|
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||||
|
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||||
|
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||||
|
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||||
|
<define name="HOVER_KP" value="500"/>
|
||||||
|
<define name="HOVER_KD" value="200"/>
|
||||||
|
<define name="HOVER_KI" value="100"/>
|
||||||
|
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||||
|
<define name="RC_CLIMB_COEF" value="163"/>
|
||||||
|
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||||
|
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||||
|
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||||
|
<define name="PGAIN" value="100"/>
|
||||||
|
<define name="DGAIN" value="100"/>
|
||||||
|
<define name="IGAIN" value="0"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<!-- ************************* MISC ************************* -->
|
||||||
|
|
||||||
|
<!-- 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="MAGNETICS" prefix="AHRS_H_">
|
||||||
|
<define name="X" value="0.4"/>
|
||||||
|
<define name="Y" value="0"/>
|
||||||
|
<define name="Z" value="0.9"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="BAT">
|
||||||
|
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="MISC">
|
||||||
|
<define name="FACE_REINJ_1" value="1024"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="SIMULATOR" prefix="NPS_">
|
||||||
|
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||||
|
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||||
|
<define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h""/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
</airframe>
|
||||||
@@ -0,0 +1,214 @@
|
|||||||
|
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||||
|
|
||||||
|
<!--
|
||||||
|
|
||||||
|
http://www.robbe.de/roxxy-bl-outrunner-2827-34.html
|
||||||
|
|
||||||
|
Technische Daten
|
||||||
|
|
||||||
|
Abmessungen: Ø 28 x 29 mm
|
||||||
|
Freie Wellenlänge: 12.5 mm
|
||||||
|
Gewicht ca.: 57 g
|
||||||
|
Laststrom (5min/120°C): 9 A
|
||||||
|
Umdrehung / Volt: 760 Umin/V
|
||||||
|
Max.Wirkungsgrad: 76 %
|
||||||
|
Laststrom max. (60 Sek.): 10 A
|
||||||
|
Zellenzahl: 6-10 NC/NiMH
|
||||||
|
Leistung: 110 W
|
||||||
|
Wellendurchmesser: 3.17 mm
|
||||||
|
Spannung: 7-12 Volt
|
||||||
|
LiPo/LiIo-Zellen: 2-3
|
||||||
|
|
||||||
|
-->
|
||||||
|
|
||||||
|
<airframe name="BOOZ2_a1">
|
||||||
|
<!-- ************************* FIRMWARE ************************* -->
|
||||||
|
|
||||||
|
<firmware name="rotorcraft">
|
||||||
|
<target name="ap" board="lisa_m_2.0">
|
||||||
|
<define name="RADIO_KILL_SWITCH" value="RADIO_FLAPS"/>
|
||||||
|
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>
|
||||||
|
</target>
|
||||||
|
<target name="nps" board="pc">
|
||||||
|
<subsystem name="fdm" type="jsbsim"/>
|
||||||
|
</target>
|
||||||
|
<subsystem name="radio_control" type="ppm"/>
|
||||||
|
<subsystem name="telemetry" type="xbee_api"/>
|
||||||
|
<subsystem name="motor_mixing"/>
|
||||||
|
<subsystem name="actuators" type="mkk_v2"/>
|
||||||
|
<subsystem name="actuators" type="pwm">
|
||||||
|
<define name="USE_PWM0"/>
|
||||||
|
</subsystem>
|
||||||
|
<subsystem name="imu" type="aspirin_v2.1"/>
|
||||||
|
<subsystem name="gps" type="ublox"/>
|
||||||
|
<subsystem name="stabilization" type="int_euler"/>
|
||||||
|
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||||
|
<subsystem name="ins" type="hff"/>
|
||||||
|
</firmware>
|
||||||
|
|
||||||
|
<section name="AUTOPILOT">
|
||||||
|
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||||
|
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_RC_CLIMB"/>
|
||||||
|
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<!-- ************************* MODULES ************************* -->
|
||||||
|
|
||||||
|
<modules>
|
||||||
|
<load name="configure_actuators_mkk_v2.xml"/>
|
||||||
|
<load name="imu_quality_assessment.xml"/>
|
||||||
|
</modules>
|
||||||
|
|
||||||
|
<!-- ************************* ACTUATORS ************************* -->
|
||||||
|
|
||||||
|
<section name="ACTUATORS_MKK_V2" prefix="ACTUATORS_MKK_V2_">
|
||||||
|
<define name="NB" value="3"/>
|
||||||
|
<define name="ADDR" value="{ 0x52, 0x56, 0x54 }"/>
|
||||||
|
<define name="DEVICE" value="i2c1"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<servos driver="Mkk_v2">
|
||||||
|
<servo name="FRONTRIGHT" no="0" min="0" neutral="30" max="2047"/>
|
||||||
|
<servo name="FRONTLEFT" no="1" min="0" neutral="30" max="2047"/>
|
||||||
|
<servo name="BACK" no="2" min="0" neutral="30" max="2047"/>
|
||||||
|
</servos>
|
||||||
|
|
||||||
|
<servos driver="Pwm">
|
||||||
|
<servo name="TAIL" no="0" min="1000" neutral="1500" max="2000"/>
|
||||||
|
</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>
|
||||||
|
|
||||||
|
<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="3"/>
|
||||||
|
<define name="SCALE" value="2048"/>
|
||||||
|
<define name="ROLL_COEF" value="{ 2048, -2048, 0}"/>
|
||||||
|
<define name="PITCH_COEF" value="{ 1024, 1024, -2048}"/>
|
||||||
|
<define name="YAW_COEF" value="{ 0, 0, 0}"/>
|
||||||
|
<define name="THRUST_COEF" value="{ 2048, 2048, 2048}"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<command_laws>
|
||||||
|
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||||
|
<set servo="FRONTRIGHT" value="motor_mixing.commands[SERVO_FRONTRIGHT]"/>
|
||||||
|
<set servo="FRONTLEFT" value="motor_mixing.commands[SERVO_FRONTLEFT]"/>
|
||||||
|
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||||
|
<set servo="TAIL" value="@YAW"/>
|
||||||
|
</command_laws>
|
||||||
|
|
||||||
|
<!-- ************************* SENSORS ************************* -->
|
||||||
|
|
||||||
|
<section name="IMU" prefix="IMU_">
|
||||||
|
<define name="MAG_X_NEUTRAL" value="-152"/>
|
||||||
|
<define name="MAG_Y_NEUTRAL" value="-51"/>
|
||||||
|
<define name="MAG_Z_NEUTRAL" value="10"/>
|
||||||
|
<define name="MAG_X_SENS" value="4.04042714046" integer="16"/>
|
||||||
|
<define name="MAG_Y_SENS" value="3.95350991963" integer="16"/>
|
||||||
|
<define name="MAG_Z_SENS" value="3.83055079257" 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="-90." unit="deg"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="INS" prefix="INS_">
|
||||||
|
<define name="BARO_SENS" value="15." integer="16"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<!-- ************************* GAINS ************************* -->
|
||||||
|
|
||||||
|
<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="360." unit="deg/s"/>
|
||||||
|
<define name="DEADBAND_R" value="200"/>
|
||||||
|
<!-- reference -->
|
||||||
|
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_P" value="0.9"/>
|
||||||
|
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||||
|
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_Q" value="0.9"/>
|
||||||
|
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||||
|
<define name="REF_OMEGA_R" value="1200" unit="deg/s"/>
|
||||||
|
<define name="REF_ZETA_R" value="0.85"/>
|
||||||
|
<define name="REF_MAX_R" value="600." unit="deg/s"/>
|
||||||
|
<define name="REF_MAX_RDOT" value="RadOfDeg(7000.)"/>
|
||||||
|
<!-- feedback -->
|
||||||
|
<define name="PHI_PGAIN" value="400"/>
|
||||||
|
<define name="PHI_DGAIN" value="410"/>
|
||||||
|
<define name="PHI_IGAIN" value="0"/>
|
||||||
|
<define name="THETA_PGAIN" value="400"/>
|
||||||
|
<define name="THETA_DGAIN" value="410"/>
|
||||||
|
<define name="THETA_IGAIN" value="114"/>
|
||||||
|
<define name="PSI_PGAIN" value="900"/>
|
||||||
|
<define name="PSI_DGAIN" value="1328"/>
|
||||||
|
<define name="PSI_IGAIN" value="0"/>
|
||||||
|
<!-- feedforward -->
|
||||||
|
<define name="PHI_DDGAIN" value=" 100"/>
|
||||||
|
<define name="THETA_DDGAIN" value=" 100"/>
|
||||||
|
<define name="PSI_DDGAIN" value=" 300"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||||
|
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||||
|
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||||
|
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||||
|
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||||
|
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||||
|
<define name="HOVER_KP" value="500"/>
|
||||||
|
<define name="HOVER_KD" value="200"/>
|
||||||
|
<define name="HOVER_KI" value="100"/>
|
||||||
|
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||||
|
<define name="RC_CLIMB_COEF" value="163"/>
|
||||||
|
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||||
|
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||||
|
<define name="PGAIN" value="100"/>
|
||||||
|
<define name="DGAIN" value="100"/>
|
||||||
|
<define name="IGAIN" value="0"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<!-- ************************* MISC ************************* -->
|
||||||
|
|
||||||
|
<section name="BAT">
|
||||||
|
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="FMS">
|
||||||
|
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="MISC">
|
||||||
|
<define name="XBEE_INIT" value=""ATID3332\r""/>
|
||||||
|
<define name="FACE_REINJ_1" value="1024"/>
|
||||||
|
<define name="VoltageOfAdc(adc)" value="(0.00528*adc)"/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
<section name="SIMULATOR" prefix="NPS_">
|
||||||
|
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||||
|
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||||
|
<define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h""/>
|
||||||
|
</section>
|
||||||
|
|
||||||
|
</airframe>
|
||||||
Reference in New Issue
Block a user