mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-24 13:55:51 +08:00
194 lines
7.4 KiB
XML
194 lines
7.4 KiB
XML
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
|
|
|
<!-- this is a quadrotor frame in X-configuration equiped with
|
|
* Autopilot: Elle0 1.2 with STM32F4 http://wiki.paparazziuav.org/wiki/Elle0
|
|
* IMU: MPU9250 & MS5611 http://wiki.paparazziuav.org/wiki/Elle0#IMU
|
|
* Actuators: PWM motor controllers http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
|
|
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
|
* RC: two Spektrum sats http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#Spektrum
|
|
-->
|
|
|
|
<airframe name="Quadrotor Elle0 pwm">
|
|
|
|
<firmware name="rotorcraft">
|
|
<target name="ap" board="elle0_1.2">
|
|
</target>
|
|
|
|
<target name="nps" board="pc">
|
|
<module name="fdm" type="jsbsim"/>
|
|
</target>
|
|
|
|
<module name="radio_control" type="spektrum">
|
|
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
|
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
|
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
|
</module>
|
|
|
|
<module name="motor_mixing"/>
|
|
<module name="actuators" type="pwm">
|
|
<define name="SERVO_HZ" value="400"/>
|
|
</module>
|
|
|
|
<module name="telemetry" type="transparent"/>
|
|
<module name="imu" type="elle0"/>
|
|
<module name="gps" type="ublox"/>
|
|
<module name="stabilization" type="int_quat"/>
|
|
<module name="ahrs" type="float_mlkf">
|
|
<!-- Uncomment to enable all axis update from the Magnetometer. Do
|
|
it only if you have a very well calibrated and tested
|
|
magnetometer otherwise your attitude will drift. -->
|
|
<!--define name="AHRS_MAG_UPDATE_ALL_AXES" value="1"/-->
|
|
</module>
|
|
<module name="ins" type="hff"/>
|
|
|
|
<!--define name="KILL_ON_GROUND_DETECT" value="TRUE"/-->
|
|
</firmware>
|
|
|
|
<modules>
|
|
<module name="gps" type="ubx_ucenter"/>
|
|
<module name="geo_mag"/>
|
|
<module name="air_data"/>
|
|
</modules>
|
|
|
|
<servos driver="Pwm">
|
|
<servo name="FR" no="0" min="1000" neutral="1100" max="2000"/>
|
|
<servo name="BR" no="1" min="1000" neutral="1100" max="2000"/>
|
|
<servo name="BL" no="2" min="1000" neutral="1100" max="2000"/>
|
|
<servo name="FL" no="3" min="1000" neutral="1100" max="2000"/>
|
|
</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_">
|
|
<!-- front left (CW), front right (CCW), back right (CW), back left (CCW) -->
|
|
<define name="TYPE" value="QUAD_X"/>
|
|
</section>
|
|
|
|
<command_laws>
|
|
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
|
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
|
|
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
|
|
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
|
|
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
|
|
</command_laws>
|
|
|
|
<section name="IMU" prefix="IMU_">
|
|
|
|
<!-- replace this with your own calibration -->
|
|
<define name="MAG_X_NEUTRAL" value="30"/>
|
|
<define name="MAG_Y_NEUTRAL" value="127"/>
|
|
<define name="MAG_Z_NEUTRAL" value="140"/>
|
|
<define name="MAG_X_SENS" value="7.11726808648" integer="16"/>
|
|
<define name="MAG_Y_SENS" value="7.09366475279" integer="16"/>
|
|
<define name="MAG_Z_SENS" value="6.84467824688" integer="16"/>
|
|
|
|
<define name="ACCEL_X_NEUTRAL" value="-52"/>
|
|
<define name="ACCEL_Y_NEUTRAL" value="-4"/>
|
|
<define name="ACCEL_Z_NEUTRAL" value="-7"/>
|
|
<define name="ACCEL_X_SENS" value="2.45056441681" integer="16"/>
|
|
<define name="ACCEL_Y_SENS" value="2.44991708802" integer="16"/>
|
|
<define name="ACCEL_Z_SENS" value="2.44199722843" 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="0." unit="deg"/>
|
|
</section>
|
|
|
|
<section name="AHRS" prefix="AHRS_">
|
|
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
|
|
<define name="H_X" value="0.3770441"/>
|
|
<define name="H_Y" value="0.0193986"/>
|
|
<define name="H_Z" value="0.9259921"/>
|
|
</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="400" 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="400" 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="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="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="500"/>
|
|
<define name="PSI_DGAIN" value="300"/>
|
|
<define name="PSI_IGAIN" value="10"/>
|
|
|
|
<!-- 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="USE_SPEED_REF" value="TRUE"/>
|
|
<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="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
|
<define name="JSBSIM_MODEL" value="simple_x_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="10.1" unit="V"/>
|
|
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
|
</section>
|
|
|
|
</airframe>
|