<!DOCTYPE airframe SYSTEM "airframe.dtd"> <!-- this is a quadrotor frame equiped with * Autopilot: Lisa/M 1.0 http://paparazzi.enac.fr/wiki/Lisa/M_v1 * IMU: Aspirin 1.1 http://paparazzi.enac.fr/wiki/AspirinIMU * Actuators: PWM motor controllers http://paparazzi.enac.fr/wiki/Subsystem/actuators#PWM_Supervision * GPS: Ublox http://paparazzi.enac.fr/wiki/Subsystem/gps --> <airframe name="Quadrotor LisaM"> <firmware name="rotorcraft"> <target name="ap" board="lisa_m_1.0"> <subsystem name="radio_control" type="ppm"> <!-- evtl das hier weg--> <!--define name="RADIO_MODE" value="RADIO_AUX1"/--> </subsystem> <!-- MPU600 is configured to output data at 500Hz --> <!--configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/--> </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"> <define name="SERVO_HZ" value="400"/> <define name="SERVO_HZ_SECONDARY" value="40"/> <define name="USE_SERVOS_7AND8"/> </subsystem> <subsystem name="telemetry" type="transparent"/> <subsystem name="imu" type="aspirin_v1.5"/> <subsystem name="gps" type="ublox"/> <subsystem name="stabilization" type="int_quat"/> <subsystem name="ahrs" type="int_cmpl_quat"/> <subsystem name="ins"/> </firmware> <!-- Using Geo Mag module --> <modules> <!--load name="geo_mag.xml"/--> <load name="rotorcraft_cam.xml"/> </modules> <servos driver="Pwm"> <servo name="SE" no="0" min="1000" neutral="1200" max="2100"/> <servo name="SW" no="1" min="1000" neutral="1200" max="2100"/> <servo name="NE" no="2" min="1000" neutral="1200" max="2100"/> <servo name="NW" no="3" min="1000" neutral="1200" max="2100"/> <servo name="CAM" no="4" min="1000" neutral="1500" max="2300"/> </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"/> <!-- evtl das hier weg--> <axis name="TILT" 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 }"/--> <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="SE" value="motor_mixing.commands[SERVO_SE]"/> <set servo="SW" value="motor_mixing.commands[SERVO_SW]"/> <set servo="NE" value="motor_mixing.commands[SERVO_NE]"/> <set servo="NW" value="motor_mixing.commands[SERVO_NW]"/> </command_laws> <!--section name="SUPERVISION" prefix="SUPERVISION_"> <define name="STOP_MOTOR" value="1000"/> <define name="MIN_MOTOR" value="1200"/> <define name="MAX_MOTOR" value="2100"/> <define name="TRIM_A" value="0"/> <define name="TRIM_E" value="0"/> <define name="TRIM_R" 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="GYRO_P_NEUTRAL" value="-10"/> <define name="GYRO_Q_NEUTRAL" value="-48"/> <define name="GYRO_R_NEUTRAL" value="-109"/> <define name="GYRO_P_SENS" value="4.412" integer="16"/> <define name="GYRO_Q_SENS" value="4.412" integer="16"/> <define name="GYRO_R_SENS" value="4.412" 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="5"/> <define name="ACCEL_Y_NEUTRAL" value="-9"/> <define name="ACCEL_Z_NEUTRAL" value="-11"/> <define name="ACCEL_X_SENS" value="38.2756504816" integer="16"/> <define name="ACCEL_Y_SENS" value="38.2543914278" integer="16"/> <define name="ACCEL_Z_SENS" value="39.5478012981" 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="-72"/> <define name="MAG_Y_NEUTRAL" value="28"/> <define name="MAG_Z_NEUTRAL" value="-27"/> <define name="MAG_X_SENS" value="5.31271228406" integer="16"/> <define name="MAG_Y_SENS" value="4.22090091915" integer="16"/> <define name="MAG_Z_SENS" value="5.51595889515" 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="MAG_XY_SENS" value="0.0" integer="16"/> <define name="MAG_XZ_SENS" value="0.0" integer="16"/> <define name="MAG_YZ_SENS" value="0.0" integer="16"/> <define name="BODY_TO_IMU_PHI" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/> <define name="BODY_TO_IMU_PSI" value="RadOfDeg( 0. )"/> </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_"> <define name="BARO_SENS" value="22.3" integer="16"/> </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="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"/> <!-- evtl weg --> <define name="SP_PSI_DELTA_LIMIT" value="45." unit="deg"/> <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="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="180." unit="deg/s"/> <define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/> <!-- feedback --> <define name="PHI_PGAIN" value="1000"/> <define name="PHI_DGAIN" value="400"/> <define name="PHI_IGAIN" value="200"/> <define name="THETA_PGAIN" value="1000"/> <define name="THETA_DGAIN" value="400"/> <define name="THETA_IGAIN" value="200"/> <define name="PSI_PGAIN" value="713"/> <define name="PSI_DGAIN" value="297"/> <define name="PSI_IGAIN" value="47"/> <!-- 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="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="213"/> <define name="HOVER_KD" value="80"/> <define name="HOVER_KI" value="20"/> <!-- 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"/> <!-- NOMINAL_HOVER_THROTTLE sets a fixed value instead of the adaptive estimation --> <!--define name="NOMINAL_HOVER_THROTTLE" value="0.5"/--> </section> <section name="GUIDANCE_H" prefix="GUIDANCE_H_"> <define name="MAX_BANK" value="20" unit="deg"/> <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="INITIAL_CONDITITONS" value=""reset00""/> <define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/> </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"/> <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> <section name="CAM" prefix="ROTORCRAFT_CAM_"> <define name="ON" value="{}"/> <define name="OFF" value="{}"/> <define name="TILT_SERVO" value="CAM"/> <define name="TILT_ANGLE_MAX" value="-90." unit="deg"/> <define name="TILT_ANGLE_MIN" value=" 10." unit="deg"/> </section> </airframe>