mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
20900c46fb
This is no longer used since #1910 Close #2671
216 lines
7.9 KiB
XML
216 lines
7.9 KiB
XML
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
|
|
|
<airframe name="bebop">
|
|
|
|
<firmware name="rotorcraft">
|
|
<target name="ap" board="bebop"/>
|
|
|
|
<target name="nps" board="pc">
|
|
<module name="fdm" type="jsbsim"/>
|
|
<module name="udp"/>
|
|
</target>
|
|
|
|
<!--define name="USE_SONAR" value="TRUE"/-->
|
|
<define name="USE_I2C3" value="TRUE"/>
|
|
|
|
<define name="UART2_DEV" value="/dev/ttyUSB0"/>
|
|
<!--define name="UART2_DEV" value="/dev/ttyACM0"/-->
|
|
|
|
<!-- Subsystem section -->
|
|
<module name="telemetry" type="transparent">
|
|
<configure name="MODEM_PORT" value="UART2"/>
|
|
<configure name="MODEM_BAUD" value="B57600"/>
|
|
</module>
|
|
<module name="radio_control" type="datalink"/>
|
|
<module name="motor_mixing"/>
|
|
<module name="actuators" type="bebop"/>
|
|
<module name="imu" type="bebop"/>
|
|
<module name="gps" type="furuno"/>
|
|
<module name="stabilization" type="int_quat"/>
|
|
<module name="ahrs" type="float_mlkf"/>
|
|
<module name="ins" type="extended"/>
|
|
</firmware>
|
|
|
|
<modules main_freq="512">
|
|
<module name="geo_mag"/>
|
|
<module name="air_data"/>
|
|
<module name="send_imu_mag_current"/>
|
|
<!--module name="logger_file">
|
|
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
|
|
</module-->
|
|
<!--module name="bebop_cam">
|
|
<define name="VIDEO_THREAD_FPS" value="4"/>
|
|
<define name="VIDEO_THREAD_CAMERA" value="bottom_camera"/>
|
|
<define name="VIDEO_THREAD_SHOT_PATH" value="/data/ftp/internal_000/images"/>
|
|
</module-->
|
|
<!--module name="video_rtp_stream">
|
|
<define name="VIEWVIDEO_QUALITY_FACTOR" value="80"/>
|
|
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="1"/>
|
|
</module-->
|
|
<module name="temp_temod">
|
|
<define name="TEMOD_I2C_DEV" value="i2c3"/>
|
|
</module>
|
|
<!--module name="humid_sht_i2c">
|
|
<define name="SHT_I2C_DEV" value="i2c3"/>
|
|
</module-->
|
|
<!--module name="ir_mlx">
|
|
<define name="MLX_I2C_DEV" value="i2c3"/>
|
|
</module-->
|
|
</modules>
|
|
|
|
<commands>
|
|
<axis name="PITCH" failsafe_value="0"/>
|
|
<axis name="ROLL" failsafe_value="0"/>
|
|
<axis name="YAW" failsafe_value="0"/>
|
|
<axis name="THRUST" failsafe_value="6000"/>
|
|
</commands>
|
|
|
|
<servos driver="Default">
|
|
<servo name="TOP_RIGHT" no="0" min="3000" neutral="3000" max="12000"/>
|
|
<servo name="TOP_LEFT" no="1" min="3000" neutral="3000" max="12000"/>
|
|
<servo name="BOTTOM_LEFT" no="2" min="3000" neutral="3000" max="12000"/>
|
|
<servo name="BOTTOM_RIGHT" no="3" min="3000" neutral="3000" max="12000"/>
|
|
</servos>
|
|
|
|
<section name="MIXING" prefix="MOTOR_MIXING_">
|
|
<!-- Time cross layout (X), with order NW (CW), NE (CCW), SE (CW), SW (CCW) -->
|
|
<define name="TYPE" value="QUAD_X"/>
|
|
</section>
|
|
|
|
<command_laws>
|
|
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
|
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
|
|
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
|
|
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
|
|
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
|
|
</command_laws>
|
|
|
|
<section name="AIR_DATA" prefix="AIR_DATA_">
|
|
<define name="CALC_AIRSPEED" value="FALSE"/>
|
|
<define name="CALC_TAS_FACTOR" value="FALSE"/>
|
|
<define name="CALC_AMSL_BARO" value="TRUE"/>
|
|
</section>
|
|
|
|
<section name="IMU" prefix="IMU_">
|
|
<!-- Magneto calibration -->
|
|
<define name="MAG_X_NEUTRAL" value="18"/>
|
|
<define name="MAG_Y_NEUTRAL" value="157"/>
|
|
<define name="MAG_Z_NEUTRAL" value="49"/>
|
|
<define name="MAG_X_SENS" value="10.5007722373" integer="16"/>
|
|
<define name="MAG_Y_SENS" value="11.1147400462" integer="16"/>
|
|
<define name="MAG_Z_SENS" value="11.6479371722" integer="16"/>
|
|
|
|
<!-- Magneto current calibration -->
|
|
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
|
|
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
|
|
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
|
|
|
|
<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>
|
|
|
|
<!-- local magnetic field -->
|
|
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
|
|
<section name="AHRS" prefix="AHRS_">
|
|
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
|
|
<!-- Delft -->
|
|
<define name="H_X" value="0.3892503"/>
|
|
<define name="H_Y" value="0.0017972"/>
|
|
<define name="H_Z" value="0.9211303"/>
|
|
</section>
|
|
|
|
<section name="INS" prefix="INS_">
|
|
<define name="SONAR_MAX_RANGE" value="2.2"/>
|
|
</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="300" unit="deg/s"/>
|
|
<define name="DEADBAND_A" value="0"/>
|
|
<define name="DEADBAND_E" value="0"/>
|
|
<define name="DEADBAND_R" value="50"/>
|
|
|
|
<!-- reference -->
|
|
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
|
|
<define name="REF_ZETA_P" value="0.9"/>
|
|
<define name="REF_MAX_P" value="600." unit="deg/s"/>
|
|
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
|
|
|
|
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
|
|
<define name="REF_ZETA_Q" value="0.9"/>
|
|
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
|
|
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
|
|
|
|
<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
|
|
<define name="REF_ZETA_R" value="0.9"/>
|
|
<define name="REF_MAX_R" value="600." unit="deg/s"/>
|
|
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
|
|
|
|
<!-- feedback -->
|
|
<define name="PHI_PGAIN" value="920"/>
|
|
<define name="PHI_DGAIN" value="425"/>
|
|
<define name="PHI_IGAIN" value="0"/>
|
|
|
|
<define name="THETA_PGAIN" value="920"/>
|
|
<define name="THETA_DGAIN" value="425"/>
|
|
<define name="THETA_IGAIN" value="0"/>
|
|
|
|
<define name="PSI_PGAIN" value="8000"/>
|
|
<define name="PSI_DGAIN" value="700"/>
|
|
<define name="PSI_IGAIN" value="0"/>
|
|
|
|
<!-- feedforward -->
|
|
<define name="PHI_DDGAIN" value="0"/>
|
|
<define name="THETA_DDGAIN" value="0"/>
|
|
<define name="PSI_DDGAIN" value="0"/>
|
|
</section>
|
|
|
|
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
|
<define name="HOVER_KP" value="283"/>
|
|
<define name="HOVER_KD" value="82"/>
|
|
<define name="HOVER_KI" value="13"/>
|
|
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
|
|
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
|
|
</section>
|
|
|
|
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
|
<!-- Good weather -->
|
|
<define name="MAX_BANK" value="20" unit="deg"/>
|
|
<!-- Bad weather -->
|
|
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
|
|
<define name="PGAIN" value="79"/>
|
|
<define name="DGAIN" value="100"/>
|
|
<define name="IGAIN" value="30"/>
|
|
</section>
|
|
|
|
<section name="NAVIGATION" prefix="NAV_">
|
|
<define name="CLIMB_VSPEED" value="2.5" />
|
|
<define name="DESCEND_VSPEED" value="-1.0" />
|
|
</section>
|
|
|
|
<section name="SIMULATOR" prefix="NPS_">
|
|
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
|
|
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
|
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
|
</section>
|
|
|
|
<section name="AUTOPILOT">
|
|
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
|
|
<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_NAV"/>
|
|
</section>
|
|
|
|
<section name="BAT">
|
|
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
|
|
<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.6" unit="V"/>
|
|
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
|
</section>
|
|
</airframe>
|