280 changes: 280 additions & 0 deletions conf/airframes/esden/quady_ll11a2pwm.xml
@@ -0,0 +1,280 @@
<!-- this is a quadrocopter frame equiped with Lisa/L 1.1, Aspirin 2.1 and generic china pwm motor controllers -->

<!--
Applicable configuration:
airframe="airframes/esden/quady_ll11a2pwm.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml"
-->

<airframe name="quady_ll11a2pwm.xml">

<servos min="0" neutral="0" max="0xff">
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="BACK" no="1" min="1000" neutral="1000" max="2000"/>
<servo name="LEFT" no="2" min="1000" neutral="1000" max="2000"/>
<servo name="RIGHT" no="3" min="1000" neutral="1000" max="2000"/>
</servos>

<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>

<command_laws>
<!--<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/>
-->
<set servo="FRONT" value="0"/>
<set servo="BACK" value="1"/>
<set servo="LEFT" value="2"/>
<set servo="RIGHT" value="3"/>

</command_laws>

<!-- for the sim -->
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>


<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<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="{ 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="MOTOR_INERTIA_COMPENSATION_FACTOR" value="2"/-->
</section>

<include href="conf/airframes/esden/calib/asp21-001.xml"/>

<section name="IMU" prefix="IMU_">
<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( 225. )"/>
</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"/>
</section>


<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">

<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>

<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>

</section>

<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">

<!-- setpoints -->
<define name="SP_MAX_PHI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_PSI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="SP_MAX_P" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>

<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="RadOfDeg(400.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="RadOfDeg(400.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_R" value="RadOfDeg(500)"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="RadOfDeg(180.)"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>

<!-- simonk esc firmware gains light quad? -->
<!-- feedback -->
<define name="PHI_PGAIN" value="570"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="100"/>

<define name="THETA_PGAIN" value="570"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="100"/>

<define name="PSI_PGAIN" value="1300"/>
<define name="PSI_DGAIN" value="1000"/>
<define name="PSI_IGAIN" value="10"/>

<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 530"/>
<define name="THETA_DDGAIN" value=" 530"/>
<define name="PSI_DDGAIN" value=" 300"/>

<!-- simonk esc firmware gains light quad? -->
<!-- feedback -->
<!--define name="PHI_PGAIN" value="1300"/>
<define name="PHI_DGAIN" value="1000"/>
<define name="PHI_IGAIN" value="100"/>
<define name="THETA_PGAIN" value="1300"/>
<define name="THETA_DGAIN" value="1000"/>
<define name="THETA_IGAIN" value="100"/>
<define name="PSI_PGAIN" value="1300"/>
<define name="PSI_DGAIN" value="1000"/>
<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"/-->

<!-- stock china esc firmware gains -->
<!-- feedback -->
<!--define name="PHI_PGAIN" value="390"/>
<define name="PHI_DGAIN" value="260"/>
<define name="PHI_IGAIN" value="50"/>
<define name="THETA_PGAIN" value="390"/>
<define name="THETA_DGAIN" value="260"/>
<define name="THETA_IGAIN" value="50"/>
<define name="PSI_PGAIN" value="780"/>
<define name="PSI_DGAIN" value="520"/>
<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="INS" prefix="INS_">
<define name="BARO_SENS" value="10." integer="16"/>
</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="830"/>
<define name="HOVER_KD" value="650"/>
<define name="HOVER_KI" value="100"/>
<!-- 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"/>
<!--define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value ="0.9"/-->
</section>

<section name="AHRS" prefix="AHRS_">
<define name="PROPAGATE_FREQUENCY" value="512"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="0"/>
</section>

<section name="MISC">
<define name="FACE_REINJ_1" value="1024"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="INITIAL_CONDITITONS" value="&quot;reset00&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>

<modules main_freq="512">
<!--load name="vehicle_interface_overo_link.xml"/-->
<load name="gps_ubx_ucenter.xml"/>
</modules>

<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<!-- <define name="BOOZ_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="actuators" type="pwm_supervision"/>
<subsystem name="telemetry" type="transparent"/>
<define name="SERVO_HZ" value="400"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
<!--define name = "RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT" value = "UART5"/-->
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>

<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/-->
</firmware>


<firmware name="lisa_test_progs">
<target name="test_led" board="lisa_l_1.1">
<configure name="SYS_TIME_LED" value="none"/>
</target>
<target name="test_uart" board="lisa_l_1.1"/>
<target name="test_servos" board="lisa_l_1.1"/>
<target name="test_telemetry" board="lisa_l_1.1"/>
<target name="test_imu_aspirin" board="lisa_l_1.1"/>
<target name="test_rc_spektrum" board="lisa_l_1.1"/>
<target name="test_baro" board="lisa_l_1.1"/>
<!--<target name="test_imu" board="lisa_l_1.1"/>
<target name="test_rc_ppm" board="lisa_l_1.1"/>
<target name="test_adc" board="lisa_l_1.1"/>
<target name="test_hmc5843" board="lisa_l_1.1"/>
<target name="test_itg3200" board="lisa_l_1.1"/>
<target name="test_adxl345" board="lisa_l_1.1"/>
<target name="test_esc_mkk_simple" board="lisa_l_1.1"/>
<target name="test_esc_asctecv1_simple" board="lisa_l_1.1"/>
<target name="test_actuators_mkk" board="lisa_l_1.1"/>
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/-->
</firmware>
</airframe>
@@ -1,6 +1,15 @@
<!-- this is an asctec frame equiped with Lisa/M and generic china pwm motor controllers -->
<!-- this is a quadrocopter frame equiped with Lisa/M 1.0, Aspirin 1.0 and generic china pwm motor controllers -->

<airframe name="lisa_asctec">
<!--
Applicable configuration:
airframe="airframes/esden/quady_lm1a1pwm.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml"
-->

<airframe name="quady_lm1a1pwm">

<servos>
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/>
Expand Down Expand Up @@ -30,9 +39,16 @@

</command_laws>

<!-- for the sim -->
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>


<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1200"/>
<define name="MIN_MOTOR" value="1100"/>
<define name="MAX_MOTOR" value="1920"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
Expand All @@ -43,40 +59,15 @@
<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="MOTOR_INERTIA_COMPENSATION_FACTOR" value="10"/-->
</section>

<section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="27"/>
<define name="GYRO_Q_NEUTRAL" value="-10"/>
<define name="GYRO_R_NEUTRAL" value="20"/>
<define name="GYRO_P_SENS" value="5.0" integer="16"/>
<define name="GYRO_Q_SENS" value="5.0" integer="16"/>
<define name="GYRO_R_SENS" value="5.0" 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="4"/>
<define name="ACCEL_Y_NEUTRAL" value="-14"/>
<define name="ACCEL_Z_NEUTRAL" value="-5"/>
<define name="ACCEL_X_SENS" value="39" integer="16"/>
<define name="ACCEL_Y_SENS" value="39" integer="16"/>
<define name="ACCEL_Z_SENS" value="39" 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="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="1." integer="16"/>
<define name="MAG_Y_SENS" value="1." integer="16"/>
<define name="MAG_Z_SENS" value="1." 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="45. " unit="deg"/>
<include href="conf/airframes/esden/calib/asp21-018.xml"/>

<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="45." unit="deg"/>
</section>

<section name="AUTOPILOT">
Expand Down Expand Up @@ -107,8 +98,11 @@
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_PSI" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="SP_MAX_P" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>

<!-- reference -->
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
Expand All @@ -127,16 +121,16 @@
<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="PHI_PGAIN" value="1500"/>
<define name="PHI_DGAIN" value="1000"/>
<define name="PHI_IGAIN" value="100"/>

<define name="THETA_PGAIN" value="1000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="1500"/>
<define name="THETA_DGAIN" value="1000"/>
<define name="THETA_IGAIN" value="100"/>

<define name="PSI_PGAIN" value="1000"/>
<define name="PSI_DGAIN" value="400"/>
<define name="PSI_PGAIN" value="1500"/>
<define name="PSI_DGAIN" value="1000"/>
<define name="PSI_IGAIN" value="10"/>

<!-- feedforward -->
Expand All @@ -147,7 +141,7 @@
</section>

<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="3.3" integer="16"/>
<define name="BARO_SENS" value="22.4" integer="16"/>
</section>

<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
Expand All @@ -156,26 +150,26 @@
<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="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="HOVER_KP" value="400"/>
<define name="HOVER_KD" value="350"/>
<define name="HOVER_KI" value="144"/>
<!-- 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"/>
<define name="INV_M" value ="0.21"/>
<define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value ="0.9"/>
</section>

<section name="AHRS" prefix="AHRS_">
<define name="PROPAGATE_FREQUENCY" value="512"/>
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="100"/>
<define name="DGAIN" value="100"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="0"/>
</section>

Expand All @@ -189,43 +183,47 @@
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>

<!--
<modules main_freq="512">
<load name="vehicle_interface_overo_link.xml"/>
</modules>
-->
<!--load name="vehicle_interface_overo_link.xml"/-->
<load name="gps_ubx_ucenter.xml"/>
</modules>

<firmware name="rotorcraft">
<target name="ap" board="lisa_m_1.0">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<subsystem name="actuators" type="pwm_supervision"/>
<subsystem name="telemetry" type="transparent"/>
<define name="SERVO_HZ" value="400"/>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>

<subsystem name="actuators" type="pwm_supervision">
<define name="SERVO_HZ" value="400"/>
</subsystem>

<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v1.0"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="euler"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/-->
</firmware>


<firmware name="lisa_test_progs">
<target name="test_led" board="lisa_m_1.0"/>
<target name="test_uart_lisam" board="lisa_m_1.0"/>
<target name="test_led" board="lisa_m_1.0">
<configure name="SYS_TIME_LED" value="none"/>
</target>
<target name="test_uart" board="lisa_m_1.0"/>
<target name="test_servos" board="lisa_m_1.0"/>
<target name="test_telemetry" board="lisa_m_1.0"/>
<target name="test_imu_aspirin" board="lisa_m_1.0"/>
<target name="test_imu_aspirin" board="lisa_m_1.0"/>
<target name="test_rc_spektrum" board="lisa_m_1.0"/>
<target name="test_baro" board="lisa_m_1.0"/>
<!--<target name="test_imu" board="lisa_m_1.0"/>
Expand Down
Expand Up @@ -2,14 +2,14 @@

<!--
Applicable configuration:
airframe="airframes/esden/lisa_m_2_asp2_pwm.xml"
airframe="airframes/esden/quady_lm2a2pwm.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/telemetry_booz2.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/settings_booz2.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml"
-->

<airframe name="lisa_asctec">
<airframe name="quady_lm2a2pwm">

<servos>
<servo name="FRONT" no="0" min="1000" neutral="1000" max="2000"/>
Expand Down Expand Up @@ -39,6 +39,13 @@

</command_laws>

<!-- for the sim -->
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
</section>


<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="STOP_MOTOR" value="1000"/>
<define name="MIN_MOTOR" value="1100"/>
Expand All @@ -52,10 +59,16 @@
<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="MOTOR_INERTIA_COMPENSATION_FACTOR" value="10"/-->
</section>

<include href="conf/airframes/esden/calib/asp21-000.xml"/>
<include href="conf/airframes/esden/calib/asp21-018.xml"/>

<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="45." unit="deg"/>
</section>

<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
Expand Down Expand Up @@ -83,41 +96,41 @@
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">

<!-- setpoints -->
<define name="SP_MAX_PHI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_PSI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="SP_MAX_P" value="RadOfDeg(90.)"/>
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_PSI" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="SP_MAX_P" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>

<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="RadOfDeg(400.)"/>
<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(800)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="RadOfDeg(400.)"/>
<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(500)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="RadOfDeg(180.)"/>
<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="PHI_PGAIN" value="1500"/>
<define name="PHI_DGAIN" value="1000"/>
<define name="PHI_IGAIN" value="100"/>

<define name="THETA_PGAIN" value="1000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="1500"/>
<define name="THETA_DGAIN" value="1000"/>
<define name="THETA_IGAIN" value="100"/>

<define name="PSI_PGAIN" value="1000"/>
<define name="PSI_DGAIN" value="400"/>
<define name="PSI_PGAIN" value="1500"/>
<define name="PSI_DGAIN" value="1000"/>
<define name="PSI_IGAIN" value="10"/>

<!-- feedforward -->
Expand All @@ -128,7 +141,7 @@
</section>

<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="3.3" integer="16"/>
<define name="BARO_SENS" value="22.4" integer="16"/>
</section>

<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
Expand All @@ -137,26 +150,26 @@
<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="-150"/>
<define name="HOVER_KD" value="-80"/>
<define name="HOVER_KI" value="-20"/>
<define name="HOVER_KP" value="400"/>
<define name="HOVER_KD" value="350"/>
<define name="HOVER_KI" value="144"/>
<!-- 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"/>
<define name="INV_M" value ="0.21"/>
<define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value ="0.9"/>
</section>

<section name="AHRS" prefix="AHRS_">
<define name="PROPAGATE_FREQUENCY" value="512"/>
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="100"/>
<define name="DGAIN" value="100"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="0"/>
</section>

Expand All @@ -170,33 +183,34 @@
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>

<!--
<modules main_freq="512">
<load name="vehicle_interface_overo_link.xml"/>
</modules>
-->
<!--load name="vehicle_interface_overo_link.xml"/-->
<load name="gps_ubx_ucenter.xml"/>
</modules>

<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<!-- <define name="BOOZ_START_DELAY" value="1"/> -->
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="actuators" type="pwm_supervision"/>
<subsystem name="telemetry" type="transparent"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="SERVO_HZ" value="400"/>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<!--define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/-->
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>

<subsystem name="actuators" type="pwm_supervision">
<define name="SERVO_HZ" value="400"/>
</subsystem>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/-->
</firmware>
Expand Down
248 changes: 0 additions & 248 deletions conf/airframes/esden/synerani_4B.xml

This file was deleted.

259 changes: 259 additions & 0 deletions conf/airframes/examples/MentorEnergy.xml
@@ -0,0 +1,259 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!--
Lisa + Aspirin v2 using SPI only
-->

<airframe name="LisaAspirin2">

<firmware name="fixedwing">
<target name="ap" board="lisa_m_1.0">
<define name="LISA_M_LONGITUDINAL_X"/>
<define name="SENSOR_SYNC_SEND"/>

<configure name="PERIODIC_FREQUENCY" value="120"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<define name="AIRSPEED_ETS_I2C_DEV" value="i2c2"/>
<define name="USE_I2C2"/>

<define name="USE_AHRS_GPS_ACCELERATIONS"/>
</target>
<target name="sim" board="pc"/>

<define name="USE_AIRSPEED"/>
<define name="AGR_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="SENSOR_SYNC_SEND"/>
<!-- Sensors -->
<!--
<subsystem name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" />
</subsystem>
-->
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="ahrs" type="float_dcm">
<!-- <define name="USE_MAGNETOMETER" /> -->
</subsystem>
<subsystem name="ins" type="alt_float"/>


<subsystem name="radio_control" type="ppm"/>

<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART2"/>
</subsystem>

<!-- Actuators -->
<subsystem name="control" type="energy"/>
<!-- Sensors -->
<subsystem name="navigation"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART1"/>
</subsystem>
</firmware>

<modules>
<load name="gps_ubx_ucenter.xml"/>
<load name="airspeed_ets.xml"/>
<load name="adc_generic.xml">
<configure name="ADC_CHANNEL_GENERIC1" value="0"/>
<configure name="ADC_CHANNEL_GENERIC2" value="1"/>
</load>

<load name="light.xml">
<define name="LIGHT_LED_STROBE" value="2"/>
<define name="LIGHT_LED_NAV" value="3"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
</load>

<load name="digital_cam.xml">
<define name="DC_SHUTTER_LED" value="3"/>
</load>

<load name="nav_catapult.xml"/>
</modules>

<servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="1" min="1200" neutral="1500" max="1800"/>
<servo name="ELEVATOR" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
<servo name="AILEVON_RIGHT" no="4" min="1800" neutral="1500" max="1200"/>
</servos>

<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"/>
</commands>

<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</rc_commands>

<command_laws>
<set servo="AILEVON_LEFT" value="@ROLL"/>
<set servo="AILEVON_RIGHT" value="-@ROLL"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW"/>
</command_laws>

<!-- Local magnetic field -->
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value="0.85490967783446"/>
</section>

<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>

<!-- SENS = 16.4 LSB/(deg/sec) * 57.6 deg/rad = 939.650 LSB/rad/sec / 12bit FRAC: 4096 / 939.65 -->
<define name="GYRO_P_SENS" value="4.359" integer="16"/>
<define name="GYRO_Q_SENS" value="4.359" integer="16"/>
<define name="GYRO_R_SENS" value="4.359" integer="16"/>

<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>

<!-- SENS = 2048 LSB/g / 9.81 ms2/g = 208.766564729 LSB/ms2 / 10bit FRAC: 1024 / 208.7665 -->
<define name="ACCEL_X_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Y_SENS" value="9.81" integer="16"/>
<define name="ACCEL_Z_SENS" value="9.81" integer="16"/>

<define name="MAG_X_NEUTRAL" value="((-320+140)/2)"/>
<define name="MAG_Y_NEUTRAL" value="((-320+140)/2)"/>
<define name="MAG_Z_NEUTRAL" value="0"/>

<define name="MAG_X_SENS" value="1" integer="16"/>
<define name="MAG_Y_SENS" value="1" integer="16"/>
<define name="MAG_Z_SENS" value="1" integer="16"/>

<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>

<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0.0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="5.9" unit="deg"/>
</section>

<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0"/>
<define name="PITCH_TRIM" value="788."/>
</section>


<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.8"/>
<define name="MAX_PITCH" value="0.8"/>
</section>

<section name="BAT">
<define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/>

<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>

<section name="MISC">
<define name="CLIMB_AIRSPEED" value="14." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="12." unit="m/s"/>
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>

<define name="CARROT" value="5." unit="s"/>

<define name="ALT_KALMAN_ENABLED" value="TRUE"/>

<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>

<define name="NAV_GLIDE_PITCH_TRIM" value="0."/>
</section>

<section name="CATAPULT" prefix="NAV_CATAPULT_">
<define name="MOTOR_DELAY" value="45"/>
<define name="HEADING_DELAY" value="(60*3)"/>
<define name="ACCELERATION_THRESHOLD" value="1.75"/>
<define name="INITIAL_PITCH" value="(15.0/57.0)"/>
<define name="INITIAL_THROTTLE" value="1.0"/>
</section>

<section name="GLS_APPROACH" prefix="APP_">
<define name="ANGLE" value="5"/>
<define name="INTERCEPT_AF_TOD" value="10"/>
<define name="TARGET_SPEED" value="13"/>
</section>

<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.104999996722"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3."/>

<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.36700001359"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.626999974251"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.518000006676" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.307000011206"/>

<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
</section>

<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.89200001955"/>
<define name="COURSE_DGAIN" value="0.273000001907"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="1.00800001621"/>

<define name="ROLL_MAX_SETPOINT" value="33.57" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="28.65" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-28.65" unit="deg"/>

<define name="PITCH_PGAIN" value="12587.4130859"/>
<define name="PITCH_DGAIN" value="1.5"/>

<define name="ELEVATOR_OF_ROLL" value="1273.88500977"/>

<define name="ROLL_SLEW" value="1."/>

<define name="ROLL_ATTITUDE_GAIN" value="7972.02783203"/>
<define name="ROLL_RATE_GAIN" value="500."/>
</section>


<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="10.0" unit="deg"/>
<define name="DEFAULT_PITCH" value="5.0" unit="deg"/>

<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
</section>

<section name="DIGITAL_CAMERA" prefix="DC_">
<define name="AUTOSHOOT_QUARTERSEC_PERIOD" value="6" unit="quarter_second"/>
<define name="AUTOSHOOT_METER_GRID" value="50" unit="meter"/>
</section>

</airframe>
146 changes: 146 additions & 0 deletions conf/airframes/examples/bixler_lisa_m_2.xml
@@ -0,0 +1,146 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!-- this is a HobbyKing Bixler equiped with
* Autopilot: Lisa/M 2.0 http://paparazzi.enac.fr/wiki/Lisa/M_v20
* IMU: Aspirin 2.1 http://paparazzi.enac.fr/wiki/AspirinIMU
* GPS: Ublox http://paparazzi.enac.fr/wiki/Subsystem/gps
* RC: any PPM system http://paparazzi.enac.fr/wiki/Subsystem/radio_control#PPM
* Modem XBee in transparent mode at 57600 baud
-->

<airframe name="Bixler LisaM 2.0">

<firmware name="fixedwing">
<target name="ap" board="lisa_m_2.0">
<!-- higher frequency for aspirin imu, ouputs data at 100Hz -->
<configure name="PERIODIC_FREQUENCY" value="120"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
</target>

<target name="sim" board="pc"/>

<define name="USE_MAGNETOMETER" value="FALSE"/>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="control"/>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="ahrs" type="float_dcm"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<!-- commands section -->
<servos>
<servo name="THROTTLE" no="1" min="1120" neutral="1120" max="1920"/>
<servo name="ELEVATOR" no="2" min="1100" neutral="1515" max="1900"/>
<servo name="RUDDER" no="3" min="950" neutral="1440" max="2050"/>
<servo name="AILERON_RIGHT" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="AILERON_LEFT" no="5" min="1000" neutral="1500" max="2000"/>
</servos>

<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="2000"/>
</commands>

<rc_commands>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="YAW" value="@YAW"/>
</rc_commands>

<section name="MIXER">
<define name="COMBI_SWITCH" value="0.3"/>
</section>

<command_laws>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>
<set servo="AILERON_LEFT" value="@ROLL"/>
<set servo="AILERON_RIGHT" value="@ROLL"/>
</command_laws>

<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="50" unit="deg"/>
<define name="MAX_PITCH" value="40" unit="deg"/>
</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"/>
</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="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000" unit="mA"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.5" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.5" unit="V"/>
</section>

<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="4." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(2.0*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="100."/>
</section>

<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.0" unit="volt"/>
<!-- outer loop -->
<define name="ALTITUDE_PGAIN" value="0.075" unit="(m/s)/m"/>
<define name="ALTITUDE_MAX_CLIMB" value="4." unit="m/s"/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5" unit="%"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.2" unit="%"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="1.0" unit="%"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500" unit="pprz_t"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000" unit="pprz_t"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.02" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.03"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05" unit="rad/(m/s)"/>
<define name="AUTO_PITCH_PGAIN" value="0.125"/>
<define name="AUTO_PITCH_IGAIN" value="0.025"/>
<define name="AUTO_PITCH_MAX_PITCH" value="25" unit="deg"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-25" unit="deg"/>
<define name="THROTTLE_SLEW" value="1.0"/>
</section>

<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.0"/>
<define name="COURSE_DGAIN" value="0.4"/>
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="25" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-25" unit="deg"/>
<define name="PITCH_PGAIN" value="20000."/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="2500"/>
<define name="ROLL_ATTITUDE_GAIN" value="7400"/>
<define name="ROLL_RATE_GAIN" value="200"/>
</section>

<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.4" unit="%"/>
<define name="DEFAULT_ROLL" value="15" unit="deg"/>
<define name="DEFAULT_PITCH" value="0" unit="deg"/>
<define name="HOME_RADIUS" value="90" unit="m"/>
</section>

</airframe>
2 changes: 1 addition & 1 deletion conf/airframes/examples/booz2.xml
Expand Up @@ -195,7 +195,7 @@
<firmware name="rotorcraft">
<target name="ap" board="booz_1.0"/>
<target name="nps" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="fdm" type="jsbsim"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/airframes/examples/delta_wing_minimal.xml
Expand Up @@ -20,6 +20,7 @@
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="gps_passthrough"/>
</firmware>

<modules>
Expand Down Expand Up @@ -92,7 +93,7 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>

<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
</section>
Expand Down Expand Up @@ -137,7 +138,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down
212 changes: 0 additions & 212 deletions conf/airframes/examples/demo_module.xml

This file was deleted.

20 changes: 14 additions & 6 deletions conf/airframes/examples/easy_glider.xml
Expand Up @@ -16,28 +16,37 @@
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="BRAKE" failsafe_value="0"/>
</commands>

<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
<set command="BRAKE" value="@GAIN1"/>
</rc_commands>

<section name="MIXER">
<define name="AILERON_DIFF" value="0.66"/>
<define name="COMBI_SWITCH" value="1.0"/>

<define name="BRAKE_DEFLECTION_TIME" value="2.0" /> <!-- seconds -->
<define name="MAX_BRAKE_RATE" value="(MAX_PPRZ / (60 * BRAKE_DEFLECTION_TIME ))" />
<define name="BRAKE_AILEVON" value="-0.68f"/>
<define name="BRAKE_PITCH" value="0.01f"/>
</section>

<command_laws>
<ratelimit var="brake_value" value="Chop(@BRAKE, 0, MAX_PPRZ)" rate_min="-MAX_BRAKE_RATE" rate_max="MAX_BRAKE_RATE" />

<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="ELEVATOR" value="@PITCH + BRAKE_PITCH * $brake_value"/>
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>

<let var="roll" value="@ROLL"/>
<set servo="AILERON_LEFT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll"/>
<set servo="AILERON_RIGHT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll"/>
<set servo="AILERON_LEFT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll + BRAKE_AILEVON * $brake_value"/>
<set servo="AILERON_RIGHT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll + BRAKE_AILEVON * $brake_value"/>
</command_laws>

<section name="AUTO1" prefix="AUTO1_">
Expand Down Expand Up @@ -76,7 +85,7 @@
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>

<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
Expand Down Expand Up @@ -124,7 +133,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down Expand Up @@ -152,7 +160,6 @@

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />

<subsystem name="radio_control" type="ppm"/>

Expand All @@ -167,6 +174,7 @@
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox_utm"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<firmware name="setup">
Expand Down
15 changes: 5 additions & 10 deletions conf/airframes/examples/easystar.xml
Expand Up @@ -10,22 +10,18 @@
<airframe name="EasyStar TWOGv1">

<firmware name="fixedwing">
<target name="ap" board="twog_1.0">
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
</target>
<target name="ap" board="twog_1.0"/>
<target name="sim" board="pc"/>

<target name="sim" board="pc">
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
</target>
<define name="LOITER_TRIM"/>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="control"/>
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<firmware name="setup">
Expand Down Expand Up @@ -98,7 +94,7 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="4." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(2.0*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="NO_XBEE_API_INIT" value="TRUE"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
Expand Down Expand Up @@ -140,7 +136,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down
9 changes: 6 additions & 3 deletions conf/airframes/examples/easystar_ets.xml
Expand Up @@ -16,17 +16,18 @@
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="WIND_INFO"/>
<define name="ALT_KALMAN"/>
<define name="USE_I2C0"/>
<define name="USE_AIRSPEED"/>
<define name="USE_BARO_ETS"/>
<define name="INS_BARO_SENS" value="0.32"/>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="control"/>
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation" type="extra"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<firmware name="setup">
Expand All @@ -36,6 +37,9 @@
<modules>
<load name="airspeed_ets.xml"/>
<load name="baro_ets.xml"/>
<load name="baro_board.xml">
<define name="BARO_ABS_EVENT" value="BaroEtsUpdate"/>
</load>
<load name="infrared_adc.xml"/>
</modules>

Expand Down Expand Up @@ -104,7 +108,7 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="4." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(2.0*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="NO_XBEE_API_INIT" value="TRUE"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
Expand Down Expand Up @@ -153,7 +157,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down
6 changes: 2 additions & 4 deletions conf/airframes/examples/funjet.xml
Expand Up @@ -16,7 +16,6 @@

<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="joystick"/>
Expand All @@ -31,6 +30,7 @@
<subsystem name="gps" type="ublox"/>

<subsystem name="navigation"/>
<subsystem name="ins" type="gps_passthrough"/>
</firmware>

<modules>
Expand Down Expand Up @@ -110,8 +110,7 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="FALSE"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>

<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
Expand Down Expand Up @@ -159,7 +158,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down
13 changes: 5 additions & 8 deletions conf/airframes/examples/funjet_cam.xml
Expand Up @@ -16,7 +16,6 @@

<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="joystick"/>
Expand All @@ -27,10 +26,10 @@
<!-- Actuators are automatically chosen according to board-->
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox"/>

<subsystem name="navigation" type="extra"/>
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ins" type="gps_passthrough"/>
<subsystem name="navigation" type="extra"/>
</firmware>


Expand Down Expand Up @@ -119,8 +118,7 @@
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="FALSE"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>

<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
Expand Down Expand Up @@ -168,7 +166,6 @@
</section>

<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>

Expand Down
1 change: 1 addition & 0 deletions conf/airframes/examples/h_hex.xml
Expand Up @@ -180,6 +180,7 @@
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/>
<subsystem name="ins"/>
</firmware>


Expand Down
3 changes: 2 additions & 1 deletion conf/airframes/examples/lisa_asctec.xml
Expand Up @@ -190,7 +190,7 @@
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
Expand All @@ -199,6 +199,7 @@
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="euler"/>
<subsystem name="ahrs" type="int_cmpl_euler"/>
<subsystem name="ins"/>
</firmware>

<firmware name="lisa_test_progs">
Expand Down
160 changes: 160 additions & 0 deletions conf/airframes/examples/lisa_l_chimu.xml
@@ -0,0 +1,160 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<airframe name="LisaL Chimu">

<firmware name="fixedwing">
<target name="ap" board="lisa_l_1.0"/>
<target name="sim" board="pc">
<subsystem name="ahrs" type="int_cmpl_quat"/>
</target>
<target name="jsbsim" board="pc">
<subsystem name="ahrs" type="int_cmpl_quat"/>
</target>

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />

<subsystem name="radio_control" type="ppm"/>

<!-- Communication -->
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>

<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="gps" type="ublox"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<modules>
<load name="ahrs_chimu_uart.xml">
<configure name="CHIMU_UART_NR" value="3"/>
</load>
</modules>

<servos>
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
<servo name="AILEVON_LEFT" no="1" min="2000" neutral="1510" max="1000"/>
<servo name="AILEVON_RIGHT" no="2" min="1000" neutral="1535" max="2000"/>
</servos>

<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>

<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>

<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>

<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/>
</command_laws>

<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.7"/>
<define name="MAX_PITCH" value="0.6"/>
</section>

<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>

<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</section>

<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="XBEE_INIT" value="&quot;ATPL2\rATRN5\rATTT80\r&quot;"/>
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>

<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>

</section>

<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.03"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/>

<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
<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.15" 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.05"/>

<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
</section>

<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.4"/>

<define name="ROLL_MAX_SETPOINT" value="0.6" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>

<define name="PITCH_PGAIN" value="12000."/>
<define name="PITCH_DGAIN" value="1.5"/>

<define name="ELEVATOR_OF_ROLL" value="1250"/>

<define name="ROLL_SLEW" value="0.1"/>

<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
<define name="ROLL_RATE_GAIN" value="1500"/>
</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="1.00"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.25"/><!-- 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="2" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
</section>

<section name="SIMU">
<define name="JSBSIM_MODEL" value="&quot;Malolo1&quot;"/>
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="0." unit="deg"/>
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="0." unit="deg"/>
</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>

</airframe>
5 changes: 2 additions & 3 deletions conf/airframes/examples/microjet.xml
Expand Up @@ -89,7 +89,7 @@
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="XBEE_INIT" value="&quot;ATPL2\rATRN5\rATTT80\r&quot;"/>
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
Expand Down Expand Up @@ -170,7 +170,6 @@

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />

<subsystem name="radio_control" type="ppm"/>

Expand All @@ -187,7 +186,7 @@
<subsystem name="ahrs" type="infrared"/>
<subsystem name="gps" type="ublox_utm"/>
<subsystem name="navigation"/>

<subsystem name="ins" type="alt_float"/>
</firmware>

<modules>
Expand Down
203 changes: 203 additions & 0 deletions conf/airframes/examples/microjet_imu_xsens.xml
@@ -0,0 +1,203 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!-- Microjet Multiplex (http://www.multiplex-rc.de/)
Lisa/M v1.0 board (http://paparazzi.enac.fr/wiki/Lisa/M_v10)
Xsens running as IMU
Xbee modem in transparent mode
-->

<airframe name="Microjet Lisa/M 1.0">

<firmware name="fixedwing">
<target name="sim" board="pc"/>
<target name="ap" board="lisa_m_1.0"/>

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />

<subsystem name="radio_control" type="ppm"/>

<!-- Communication -->
<subsystem name="telemetry" type="transparent"/>

<!-- Sensors -->
<subsystem name="imu" type="xsens">
<configure name="XSENS_UART_NR" value="3"/>
<configure name="XSENS_UART_BAUD" value="B115200"/>
</subsystem>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="control"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<modules>
<load name="sys_mon.xml"/>
</modules>

<servos>
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
<servo name="AILEVON_LEFT" no="1" min="2000" neutral="1510" max="1000"/>
<servo name="AILEVON_RIGHT" no="3" min="1000" neutral="1535" max="2000"/>
</servos>

<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>

<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>

<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>

<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator - $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator + $aileron"/>
</command_laws>

<section name="IMU" prefix="IMU_">

<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="1"/>
<define name="GYRO_R_SIGN" value="1"/>

<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>

<define name="GYRO_P_SENS" value="1" integer="16"/>
<define name="GYRO_R_SENS" value="1" integer="16"/>
<define name="GYRO_Q_SENS" value="1" integer="16"/>

<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="1"/>
<define name="ACCEL_Z_SIGN" value="1"/>

<define name="ACCEL_X_SENS" value="1" integer="16"/>
<define name="ACCEL_Z_SENS" value="1" integer="16"/>
<define name="ACCEL_Y_SENS" value="1" integer="16"/>

<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>

<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>

<define name="MAG_X_NEUTRAL" value="-45"/>
<define name="MAG_Y_NEUTRAL" value="334"/>
<define name="MAG_Z_NEUTRAL" value="7"/>

<define name="MAG_X_SENS" value="4.47647816128" integer="16"/>
<define name="MAG_Y_SENS" value="4.71085671542" integer="16"/>
<define name="MAG_Z_SENS" value="4.41585354498" 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_">
<!-- replace this with your local magnetic field -->
<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="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
</section>

<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.03"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/>

<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
<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.15" 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.05"/>

<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
</section>

<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.0"/>
<define name="COURSE_DGAIN" value="0.3"/>

<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="30" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-30" unit="deg"/>

<define name="PITCH_PGAIN" value="12000."/>
<define name="PITCH_DGAIN" value="1.5"/>

<define name="ELEVATOR_OF_ROLL" value="1250"/>

<define name="ROLL_SLEW" value="0.1"/>

<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
<define name="ROLL_RATE_GAIN" value="1500"/>
</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="1.00"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.25"/><!-- 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="2" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
</section>

<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="40." unit="deg"/>
<define name="MAX_PITCH" value="35." unit="deg"/>
</section>

<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>
<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="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
</section>

</airframe>
9 changes: 5 additions & 4 deletions conf/airframes/examples/microjet_lisa_m.xml
Expand Up @@ -12,9 +12,9 @@
<target name="sim" board="pc"/>
<target name="ap" board="lisa_m_1.0"/>

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="STRONG_WIND"/>

<subsystem name="radio_control" type="ppm"/>

Expand All @@ -28,6 +28,7 @@
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="control"/>
<subsystem name="navigation"/>
<subsystem name="ins" type="alt_float"/>
</firmware>

<modules>
Expand Down Expand Up @@ -168,7 +169,7 @@
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
</section>
Expand Down
158 changes: 158 additions & 0 deletions conf/airframes/examples/microjet_lisa_m_xsens.xml
@@ -0,0 +1,158 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!-- Microjet Multiplex (http://www.multiplex-rc.de/)
Lisa/M v1.0 board (http://paparazzi.enac.fr/wiki/Lisa/M_v10)
Xsens as full INS
Xbee modem in transparent mode
-->

<airframe name="Microjet Lisa/M 1.0">

<firmware name="fixedwing">
<target name="sim" board="pc"/>
<target name="ap" board="lisa_m_1.0"/>

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />

<subsystem name="radio_control" type="ppm"/>

<!-- Communication -->
<subsystem name="telemetry" type="transparent"/>

<!-- Sensors -->
<subsystem name="ins" type="xsens">
<configure name="XSENS_UART_NR" value="3"/>
<configure name="XSENS_UART_BAUD" value="B115200"/>
</subsystem>

<subsystem name="control"/>
<subsystem name="navigation"/>
</firmware>

<modules>
<load name="sys_mon.xml"/>
</modules>

<servos>
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
<servo name="AILEVON_LEFT" no="1" min="2000" neutral="1510" max="1000"/>
<servo name="AILEVON_RIGHT" no="3" min="1000" neutral="1535" max="2000"/>
</servos>

<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>

<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>

<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>

<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator - $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator + $aileron"/>
</command_laws>

<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"/>
</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="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.03"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="2."/>

<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
<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.15" 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.05"/>

<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
</section>

<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="1.0"/>
<define name="COURSE_DGAIN" value="0.3"/>

<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="30" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-30" unit="deg"/>

<define name="PITCH_PGAIN" value="12000."/>
<define name="PITCH_DGAIN" value="1.5"/>

<define name="ELEVATOR_OF_ROLL" value="1250"/>

<define name="ROLL_SLEW" value="0.1"/>

<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
<define name="ROLL_RATE_GAIN" value="1500"/>
</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="1.00"/><!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="-0.25"/><!-- 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="2" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
</section>

<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="40." unit="deg"/>
<define name="MAX_PITCH" value="35." unit="deg"/>
</section>

<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>
<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="MISC">
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
</section>

</airframe>
@@ -1,26 +1,41 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!-- this is a quadrotor frame equiped with Lisa/M 2.0 and PWM motor controllers -->
<!-- this is a quadrotor frame equiped with
* Autopilot: Lisa/M 2.0 http://paparazzi.enac.fr/wiki/Lisa/M_v20
* IMU: Aspirin 2.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
* RC: two Spektrum sats http://paparazzi.enac.fr/wiki/Subsystem/radio_control#Spektrum
-->

<airframe name="fraser">
<airframe name="Quadrotor LisaM_2.0 pwm">

<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0"/>
<target name="ap" board="lisa_m_2.0">
<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</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="nps"/>
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>

<subsystem name="actuators" type="pwm_supervision">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</subsystem>

<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="aspirin_v2.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins"/>
</firmware>

<servos>
Expand Down Expand Up @@ -169,6 +184,8 @@
<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_">
Expand Down