mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-23 13:24:03 +08:00
Added AggieAir airframes
This commit is contained in:
+15
-2
@@ -1,10 +1,10 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
ARK RT
|
||||
Aggie Air ARK
|
||||
-->
|
||||
|
||||
<airframe name="Quadrotor LisaMX_2.1 pwm">
|
||||
<airframe name="ARK Hexarotor 1.8">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -12,6 +12,8 @@ ARK RT
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART5"/>
|
||||
</module>
|
||||
<configure name="HAS_LUFTBOOT" value="1"/>
|
||||
<configure name="FLASH_MODE" value="DFU"/>
|
||||
</target>
|
||||
|
||||
<!-- NOTE: if you want to use extra_dl module for HITL
|
||||
@@ -49,12 +51,23 @@ ARK RT
|
||||
|
||||
<modules>
|
||||
<module name="sys_mon"/>
|
||||
<module name="copilot"/>
|
||||
<module name="extra_dl">
|
||||
<!-- in order to use uart1 without chibios we need to remap the peripheral-->
|
||||
<define name="REMAP_UART1" value="TRUE"/>
|
||||
<configure name="EXTRA_DL_PORT" value="UART1"/>
|
||||
<configure name="EXTRA_DL_BAUD" value="B921600"/>
|
||||
</module>
|
||||
<module name="lidar_sf11">
|
||||
<configure name="LIDAR_SF11_I2C_DEV" value="i2c2"/>
|
||||
</module>
|
||||
<!--module name="battery_monitor.xml">
|
||||
<define name="BATMON_REV4" value="1"/>
|
||||
<define name="BATMON_CURRENT_OFFSET" value="-120"/>
|
||||
<define name="BATMON_CURRENT_SENSITIVITY" value="25.6"/>
|
||||
<define name="BATMON_TEMP_OFFSET" value="250"/>
|
||||
<define name="BATMON_TEMP_SENSITIVITY" value="10"/>
|
||||
</module-->
|
||||
</modules>
|
||||
|
||||
<!--These values are set for the Castle Creations HV Lite 60A ESCs-->
|
||||
@@ -1,238 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="Quadrotor Lia pwm">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lia_1.1_chibios">
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART5"/>
|
||||
</module>
|
||||
</target>
|
||||
|
||||
<configure name="PERIODIC_FREQUENCY" value="160"/>
|
||||
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
<module name="radio_control" type="spektrum"/>
|
||||
<!--configure name="USE_HITL" value="1"/-->
|
||||
<configure name="INS_DEV" value="/dev/ttyUSB1"/>
|
||||
<configure name="INS_BAUD" value="B921600"/>
|
||||
<configure name="AP_DEV" value="/dev/ttyUSB2"/>
|
||||
<configure name="AP_BAUD" value="B921600"/>
|
||||
</target>
|
||||
|
||||
<module name="stabilization" type="int_quat"/>
|
||||
|
||||
<module name="motor_mixing"/>
|
||||
<module name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="PERIODIC_FREQUENCY"/>
|
||||
</module>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_PORT" value="UART3"/>
|
||||
<configure name="MODEM_BAUD" value="B57600"/>
|
||||
</module>
|
||||
|
||||
<module name="ins" type="vectornav">
|
||||
<configure name="VN_PORT" value="UART2"/>
|
||||
<configure name="VN_BAUD" value="B921600"/>
|
||||
</module>
|
||||
|
||||
<define name="GEOFENCE_DATALINK_LOST_TIME" value="45"/>
|
||||
</firmware>
|
||||
|
||||
|
||||
<modules>
|
||||
<module name="sys_mon"/>
|
||||
<module name="extra_dl">
|
||||
<!-- in order to use uart1 without chibios we need to remap the peripheral-->
|
||||
<define name="REMAP_UART1" value="TRUE"/>
|
||||
<configure name="EXTRA_DL_PORT" value="UART1"/>
|
||||
<configure name="EXTRA_DL_BAUD" value="B921600"/>
|
||||
</module>
|
||||
<module name="lidar_lite">
|
||||
<configure name="LIDAR_LITE_I2C_DEV" value="i2c2"/>
|
||||
</module>
|
||||
<module name="battery_monitor.xml">
|
||||
<define name="BATMON_CURRENT_OFFSET" value="-120"/>
|
||||
<define name="BATMON_CURRENT_SENSITIVITY" value="25.6"/>
|
||||
<define name="BATMON_TEMP_OFFSET" value="250"/>
|
||||
<define name="BATMON_TEMP_SENSITIVITY" value="10"/>
|
||||
</module>
|
||||
</modules>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="FL" no="0" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="FR" no="1" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="BR" no="2" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="BL" 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_">
|
||||
<!-- 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_get_motors_on(),FALSE,values)"/>
|
||||
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
|
||||
<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]"/>
|
||||
</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="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_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="140" unit="deg/s"/>
|
||||
<define name="SP_MAX_Q" value="140" unit="deg/s"/>
|
||||
<define name="SP_MAX_R" value="140" unit="deg/s"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="800"/>
|
||||
<define name="GAIN_Q" value="800"/>
|
||||
<define name="GAIN_R" value="700"/>
|
||||
|
||||
<define name="IGAIN_P" value="240"/>
|
||||
<define name="IGAIN_Q" value="240"/>
|
||||
<define name="IGAIN_R" value="160"/>
|
||||
</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="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"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_ROLL" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_PITCH" value="2"/>
|
||||
<define name="JS_AXIS_PITCH_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_YAW" value="3"/>
|
||||
<define name="JS_AXIS_YAW_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_MODE" value="7"/>
|
||||
</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">
|
||||
<!-- Flight values -->
|
||||
<!--
|
||||
<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"/>
|
||||
-->
|
||||
|
||||
<!-- Simulator values -->
|
||||
<define name="MAX_BAT_LEVEL" value="5.0" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="4.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="3.5" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="3.0" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,301 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
AggieAir Blujayujay
|
||||
-->
|
||||
|
||||
<airframe name="Bl">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="lisa_mx_2.1">
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART5"/>
|
||||
</module>
|
||||
<configure name="HAS_LUFTBOOT" value="1"/>
|
||||
<configure name="FLASH_MODE" value="DFU"/>
|
||||
</target>
|
||||
|
||||
<!-- NOTE: if you want to use extra_dl module for HITL
|
||||
you have to set TELEMETRY_FREQUENCY to CONTROL_FREQUENCY -->
|
||||
<configure name="PERIODIC_FREQUENCY" value="100"/>
|
||||
<define name="CONTROL_FREQUENCY" value="100"/>
|
||||
<configure name="TELEMETRY_FREQUENCY" value="100"/>
|
||||
<define name="SERVO_HZ" value="100"/>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
<module name="radio_control" type="spektrum"/>
|
||||
<configure name="USE_HITL" value="1"/>
|
||||
<configure name="INS_DEV" value="/dev/ttyUSB1"/>
|
||||
<configure name="INS_BAUD" value="B921600"/>
|
||||
<configure name="AP_DEV" value="/dev/ttyUSB2"/>
|
||||
<configure name="AP_BAUD" value="B921600"/>
|
||||
</target>
|
||||
|
||||
<module name="control"/>
|
||||
<module name="navigation"/>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_PORT" value="UART3"/>
|
||||
<configure name="MODEM_BAUD" value="B115200"/>
|
||||
</module>
|
||||
|
||||
<module name="ins" type="vectornav">
|
||||
<configure name="VN_PORT" value="UART2"/>
|
||||
<configure name="VN_BAUD" value="B921600"/>
|
||||
</module>
|
||||
|
||||
<define name="AGR_CLIMB" />
|
||||
<define name="POLY_OSAM_HALF_SWEEP_ENABLED" value="FALSE"/>
|
||||
<define name="GEOFENCE_DATALINK_LOST_TIME" value="45"/>
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="nav" type="line"/>
|
||||
<module name="nav" type="flower"/>
|
||||
<module name="nav" type="survey_poly_osam"/>
|
||||
<module name="nav" type="launcher"/>
|
||||
<module name="nav" type="skid_landing"/>
|
||||
<module name="sys_mon"/>
|
||||
<module name="copilot"/>
|
||||
<module name="extra_dl">
|
||||
<!-- in order to use uart1 without chibios we need to remap the peripheral-->
|
||||
<define name="REMAP_UART1" value="TRUE"/>
|
||||
<configure name="EXTRA_DL_PORT" value="UART1"/>
|
||||
<configure name="EXTRA_DL_BAUD" value="B921600"/>
|
||||
</module>
|
||||
<module name="lidar_sf11">
|
||||
<configure name="LIDAR_SF11_I2C_DEV" value="i2c2"/>
|
||||
</module>
|
||||
<!--module name="battery_monitor.xml">
|
||||
<define name="BATMON_REV4" value="1"/>
|
||||
<define name="BATMON_CURRENT_OFFSET" value="-120"/>
|
||||
<define name="BATMON_CURRENT_SENSITIVITY" value="25.6"/>
|
||||
<define name="BATMON_TEMP_OFFSET" value="250"/>
|
||||
<define name="BATMON_TEMP_SENSITIVITY" value="10"/>
|
||||
</module-->
|
||||
</modules>
|
||||
|
||||
<!-- commands section -->
|
||||
<!-- Servo Configuration -->
|
||||
<servos>
|
||||
<servo name="FLAP" no="0" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="AILERON_RIGHT" no="1" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="AILERON_LEFT" no="2" min="2100" neutral="1500" max="900"/>
|
||||
<servo name="ELEVATOR" no="3" min="2100" neutral="1500" max="900"/>
|
||||
<servo name="RUDDER" no="4" min="2100" neutral="1500" max="900"/>
|
||||
<servo name="THROTTLE" no="5" min="1100" neutral="1100" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<!-- Servo Command Structure -->
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="FLAP" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<!-- RC Command Structure -->
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="FLAP" value="@FLAP"/>
|
||||
</rc_commands>
|
||||
|
||||
<!-- Define RC commands to Servo in Auto Mode -->
|
||||
<auto_rc_commands>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="FLAP" value="@FLAP"/>
|
||||
</auto_rc_commands>
|
||||
|
||||
<!-- Define Mixing Parameters -->
|
||||
<section name="MIXER">
|
||||
<define name="AILERON_AILERON_RATE" value="0.9"/>
|
||||
<define name="ELEV_ELEV_RATE" value="0.8"/>
|
||||
</section>
|
||||
|
||||
<!-- Define RC commands to Servos in Manual -->
|
||||
<command_laws>
|
||||
<let var="aileron" value="@ROLL * AILERON_AILERON_RATE"/>
|
||||
<let var="elevator" value="@PITCH * ELEV_ELEV_RATE"/>
|
||||
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="AILERON_RIGHT" value="$aileron"/> <!--flip signs if necessary -->
|
||||
<set servo="AILERON_LEFT" value=" - $aileron"/>
|
||||
<set servo="ELEVATOR" value="$elevator"/>
|
||||
<set servo="RUDDER" value="@YAW"/>
|
||||
<set servo="FLAP" value="@FLAP"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- Define Max Roll and Pitch setpoints in Auto1 -->
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.7"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<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"/>
|
||||
|
||||
<!-- Dummy Mag values for NPS -
|
||||
replace with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/> <!-- GCS only -->
|
||||
<define name="CARROT" value="5." unit="s"/> <!-- GCS only -->
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="23.2" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.136"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.40"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.20"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.70"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.05" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.142"/>
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.1"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.025"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.31415" unit="rad"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.31415" unit="rad"/>
|
||||
|
||||
<!--New Landing V_CTL_loop -->
|
||||
<define name="LANDING_THROTTLE_PGAIN" value="600"/>
|
||||
<define name="LANDING_THROTTLE_IGAIN" value="30"/>
|
||||
<define name="LANDING_THROTTLE_MAX" value="0.60" unit="%"/>
|
||||
<define name="LANDING_DESIRED_SPEED" value="18.00" unit="(m/s)"/>
|
||||
<define name="LANDING_PITCH_PGAIN" value="0.3"/>
|
||||
<define name="LANDING_PITCH_IGAIN" value="0.0130"/>
|
||||
<define name="LANDING_PITCH_LIMITS" value="0.2000" unit="rad"/>
|
||||
<define name="LANDING_PITCH_FLARE" value="0.15000" unit="rad"/>
|
||||
<define name="LANDING_ALT_THROTTLE_KILL" value="6" unit="m"/>
|
||||
<define name="LANDING_ALT_FLARE" value="3" unit="m"/>
|
||||
<define name="USE_LIDAR" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.33"/>
|
||||
<define name="COURSE_DGAIN" value="0."/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.575959" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.35" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.2" unit="rad"/>
|
||||
<define name="PITCH_PGAIN" value="12900."/>
|
||||
|
||||
<!-- ORIGINAL GAIN-->
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<!-- SIMULATOR GAIN
|
||||
<define name="PITCH_DGAIN" value="151.5"/>
|
||||
-->
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="9000"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1600"/>
|
||||
<define name="ROLL_SLEW" value="0.1"/>
|
||||
<define name="ELE_IGAIN" value="0."/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.75"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.13"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.1"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="5" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="100" unit="m"/>
|
||||
</section>
|
||||
|
||||
<!-- Launcher Takeoff Configuration -->
|
||||
<section name="LAUNCHER" prefix="LAUNCHER_TAKEOFF_">
|
||||
<define name="PITCH" value="0.23" unit="rad"/>
|
||||
<define name="HEIGHT" value="70" unit="m"/>
|
||||
<define name="MIN_SPEED_CIRCLE" value="8" unit="m/s"/>
|
||||
<define name="DISTANCE" value="30" unit="m"/>
|
||||
<define name="MIN_SPEED_LINE" value="5" unit="m/s"/>
|
||||
</section>
|
||||
|
||||
<!-- Skid Landing Configuration -->
|
||||
<section name="LANDING" prefix="SKID_LANDING_">
|
||||
<define name="AF_HEIGHT" value="50" unit="m"/>
|
||||
<define name="FINAL_HEIGHT" value="50" unit="m"/>
|
||||
<define name="FINAL_STAGE_TIME" value="10" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_invariant.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_ROLL" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_PITCH" value="2"/>
|
||||
<define name="JS_AXIS_PITCH_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_YAW" value="3"/>
|
||||
<define name="JS_AXIS_YAW_REVERSED" value="1"/>
|
||||
|
||||
<define name="JS_AXIS_FLAPS" value="5"/>
|
||||
<define name="JS_AXIS_MODE" value="7"/>
|
||||
|
||||
<define name="JSBSIM_ROLL_TRIM" value="0.008"/>
|
||||
<define name="JSBSIM_PITCH_TRIM" value="0.0375"/>
|
||||
<define name="JSBSIM_YAW_TRIM" value="0.001"/>
|
||||
</section>
|
||||
|
||||
<!-- Define current estimator and Battery Level Warnings -->
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="50000"/>
|
||||
<define name="CURRENT_ESTIMATION_NONLINEARITY" value="1.3"/>
|
||||
|
||||
<!-- Flight values -->
|
||||
<!--
|
||||
<define name="MAX_BAT_LEVEL" value="16.5" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="14.1" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="13.8" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="13.5" unit="V"/>
|
||||
-->
|
||||
|
||||
<!-- Simulator values -->
|
||||
<define name="MAX_BAT_LEVEL" value="5.0" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="4.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="3.5" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="3.0" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,4 +1,15 @@
|
||||
<conf>
|
||||
<aircraft
|
||||
name="Ark_Hexa_1.8"
|
||||
ac_id="4"
|
||||
airframe="airframes/AGGIEAIR/aggieair_ark_hexa_1-8.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/lidar_sf11.xml modules/gps.xml modules/stabilization_float_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
name="Ark_Quad"
|
||||
ac_id="2"
|
||||
@@ -11,15 +22,15 @@
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
name="Ark_Quad_Lia"
|
||||
ac_id="4"
|
||||
airframe="airframes/AGGIEAIR/aggieair_ark_quad_lia.xml"
|
||||
name="Blujay"
|
||||
ac_id="6"
|
||||
airframe="airframes/AGGIEAIR/aggieair_blujay.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/lidar_sf11.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
name="ECU"
|
||||
@@ -34,7 +45,7 @@
|
||||
/>
|
||||
<aircraft
|
||||
name="Iris"
|
||||
ac_id="66"
|
||||
ac_id="5"
|
||||
airframe="airframes/AGGIEAIR/aggieair_iris_indi.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_FrSky3dr.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_iris.xml"
|
||||
@@ -44,9 +55,9 @@
|
||||
gui_color="#337e387bffff"
|
||||
/>
|
||||
<aircraft
|
||||
name="Minion_Lia"
|
||||
name="Minion_RP3"
|
||||
ac_id="1"
|
||||
airframe="airframes/AGGIEAIR/aggieair_rp3_lia.xml"
|
||||
airframe="airframes/AGGIEAIR/aggieair_minion_rp3_lia.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
|
||||
@@ -12,7 +12,7 @@
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
<target name="ap" board="px4fmu_2.4_chibios" />
|
||||
<target name="ap" board="px4fmu_2.4" />
|
||||
<configure name="PERIODIC_FREQUENCY" value="200"/>
|
||||
<configure name="TELEMETRY_FREQUENCY" value="60"/>
|
||||
|
||||
@@ -126,7 +126,7 @@
|
||||
|
||||
<modules main_freq="PERIODIC_FREQUENCY">
|
||||
<!-- allow flashing FBW target through AP -->
|
||||
<!--module name="px4_flash"/-->
|
||||
<module name="px4_flash"/>
|
||||
|
||||
<!-- CPU utilization monitor -->
|
||||
<module name="sys_mon"/>
|
||||
|
||||
+2
-2
@@ -1,10 +1,10 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
RP3 Lisa MX
|
||||
AggieAir RP3 Minion
|
||||
-->
|
||||
|
||||
<airframe name="RP3 Lisa MX">
|
||||
<airframe name="Minion PR3">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="lisa_mx_2.1">
|
||||
@@ -7,7 +7,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
settings_modules="modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -112,12 +112,12 @@
|
||||
<aircraft
|
||||
name="Minion_Lia"
|
||||
ac_id="42"
|
||||
airframe="airframes/AGGIEAIR/aggieair_rp3_lia.xml"
|
||||
airframe="airframes/AGGIEAIR/aggieair_minion_rp3_lia.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/lidar_sf11.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules=""
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
|
||||
+4
-4
@@ -2,12 +2,12 @@
|
||||
<aircraft
|
||||
name="Ark_Quad"
|
||||
ac_id="41"
|
||||
airframe="airframes/AGGIEAIR/ark_hexa_1-8.xml"
|
||||
airframe="airframes/AGGIEAIR/aggieair_ark_quad_lisa_mx.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/gps.xml modules/stabilization_float_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
settings_modules="modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -233,12 +233,12 @@
|
||||
<aircraft
|
||||
name="Minion_Lia"
|
||||
ac_id="42"
|
||||
airframe="airframes/AGGIEAIR/aggieair_rp3_lia.xml"
|
||||
airframe="airframes/AGGIEAIR/aggieair_minion_rp3_lia.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/AGGIEAIR/aggieair_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/lidar_sf11.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules=""
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
|
||||
@@ -211,12 +211,12 @@
|
||||
<aircraft
|
||||
name="Minion_Lia"
|
||||
ac_id="42"
|
||||
airframe="airframes/AGGIEAIR/aggieair_rp3_lia.xml"
|
||||
airframe="airframes/AGGIEAIR/aggieair_minion_rp3_lia.xml"
|
||||
radio="radios/AGGIEAIR/aggieair_taranis.xml"
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/lidar_lite.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules=""
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
|
||||
Reference in New Issue
Block a user