Files
paparazzi/conf/airframes/untested/quadrotor_mlkf.xml
T
2016-01-27 17:23:23 +01:00

190 lines
6.9 KiB
XML

<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Quadrotor with floating point unit">
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<configure name="USE_MAGNETOMETER" value="1"/>
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_PORT" value="UART1"/>
</subsystem>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="float_quat"/>
<subsystem name="ahrs" type="float_mlkf"/>
<subsystem name="ins"/>
</firmware>
<modules main_freq="512">
<load name="sys_mon.xml"/>
</modules>
<servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" 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"/>
<!-- front/back turning CW, right/left CCW -->
<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="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/>
<define name="ACCEL_Z_NEUTRAL" value="-25"/>
<!-- 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="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<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>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
</section>
<section name="INS" prefix="INS_">
</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_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="{RadOfDeg(400)}"/>
<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="{RadOfDeg(400)}"/>
<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="{RadOfDeg(250)}"/>
<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="{1000}"/>
<define name="PHI_DGAIN" value="{1000}"/>
<define name="PHI_IGAIN" value="{200}"/>
<define name="THETA_PGAIN" value="{1000}"/>
<define name="THETA_DGAIN" value="{1000}"/>
<define name="THETA_IGAIN" value="{200}"/>
<define name="PSI_PGAIN" value="{500}"/>
<define name="PSI_DGAIN" value="{500}"/>
<define name="PSI_IGAIN" value="{10}"/>
<!-- feedback angular acceleration error -->
<define name="PHI_DGAIN_D" value="{100}"/>
<define name="THETA_DGAIN_D" value="{100}"/>
<define name="PSI_DGAIN_D" value="{100}"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="{300}"/>
<define name="THETA_DDGAIN" value="{300}"/>
<define name="PSI_DDGAIN" value="{300}"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.5"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<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>