[xml] Flight plan and airframe file updates for outdoor testing with hybrid and Bebop2. (#1718)

* [xml] Bebop2 simple outdoor flight plan and flight testing. Added MavShot xml file. Added custom GCS layout in DB folder

* Removed deprecated file
This commit is contained in:
Deon Blaauw
2016-06-13 20:53:42 +02:00
committed by Felix Ruess
parent 09ed2e6595
commit 8f75e25129
7 changed files with 461 additions and 26 deletions
+31 -21
View File
@@ -4,6 +4,7 @@
<firmware name="rotorcraft">
<target name="ap" board="bebop2">
<define name="USE_SONAR" value="TRUE"/>
<define name="STABILIZATION_INDI_G2_R" value="0.20"/>
<!--define name="FAILSAFE_GROUND_DETECT"/-->
</target>
@@ -21,14 +22,21 @@
<module name="motor_mixing"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="datalink"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="indi"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/>
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
<module name="ahrs" type="float_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</module>
<!-- Enable the vertical estimator -->
<module name="ins" type="extended"/>
<!-- Enable the horizontal estimator -->
<!-- <module name="ins" type="hff"> -->
<!-- <define name="GPS_LAG" value="0.35"/> -->
<!-- </module> -->
<define name="KILL_ON_GROUND_DETECT" value="TRUE"/>
</firmware>
@@ -80,26 +88,28 @@
<section name="IMU" prefix="IMU_">
<!-- Magneto calibration -->
<define name="MAG_X_NEUTRAL" value="18"/>
<define name="MAG_Y_NEUTRAL" value="46"/>
<define name="MAG_Z_NEUTRAL" value="202"/>
<define name="MAG_X_SENS" value="8.32441255621" integer="16"/>
<define name="MAG_Y_SENS" value="8.25720085664" integer="16"/>
<define name="MAG_Z_SENS" value="8.60009819293" integer="16"/>
<define name="MAG_X_NEUTRAL" value="-74"/>
<define name="MAG_Y_NEUTRAL" value="33"/>
<define name="MAG_Z_NEUTRAL" value="-189"/>
<define name="MAG_X_SENS" value="7.32880539549" integer="16"/>
<define name="MAG_Y_SENS" value="7.38826972194" integer="16"/>
<define name="MAG_Z_SENS" value="7.71693452252" integer="16"/>
<!-- Accelerometer Calibration -->
<!-- <define name="ACCEL_X_NEUTRAL" value="72"/>
<define name="ACCEL_Y_NEUTRAL" value="-20"/>
<define name="ACCEL_Z_NEUTRAL" value="42"/>
<define name="ACCEL_X_SENS" value="2.44509248843" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44634245634" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.43962899631" integer="16"/>-->
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- Toulouse -->
<!--define name="H_X" value="0.513081"/>
<define name="H_Y" value="-0.00242783"/>
<define name="H_Z" value="0.858336"/-->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<define name="H_X" value="0.0"/>
<define name="H_Y" value="0.0"/>
<define name="H_Z" value="0.0"/>
</section>
<section name="INS" prefix="INS_">
@@ -197,7 +207,7 @@
<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" type="string"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
+14 -3
View File
@@ -5,9 +5,20 @@
airframe="airframes/DB/db_bebop2_indi.xml"
radio="radios/dummy.xml"
telemetry="telemetry/DB/db_default_rotorcraft.xml"
flight_plan="flight_plans/DB/db_cyberzoo.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/rotorcraft_speed.xml settings/control/stabilization_indi.xml"
flight_plan="flight_plans/DB/db_outdoors.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/rotorcraft_speed.xml settings/control/stabilization_indi.xml [settings/control/stabilization_rate.xml] [settings/control/stabilization_att_int.xml] [settings/control/stabilization_att_int_quat.xml] [settings/control/stabilization_att_float_euler.xml]"
settings_modules="modules/geo_mag.xml modules/air_data.xml"
gui_color="red"
gui_color="#0d890debf1c6"
/>
<aircraft
name="mavshot"
ac_id="52"
airframe="airframes/DB/db_mavshot.xml"
radio="radios/dummy.xml"
telemetry="telemetry/DB/db_default_rotorcraft.xml"
flight_plan="flight_plans/DB/db_outdoors.xml"
settings="settings/rotorcraft_basic.xml settings/modules/config_asctec_v2_new.xml"
settings_modules="modules/geo_mag.xml [modules/gps_ubx_ucenter.xml]"
gui_color="#ee1bf3780c03"
/>
</conf>
+294
View File
@@ -0,0 +1,294 @@
<!-- this is a quadshot vehicle equiped with Lisa/m2.0 and an aspirin 2.1
More information on the Quadshot can be found at transition-robotics.com -->
<airframe name="quadshot aspirin 2.1 spektrum">
<servos driver="Pwm">
<!-- <servo name="A1" no="0" min="1000" neutral="1100" max="2000"/>
<servo name="A2" no="1" min="1000" neutral="1100" max="2000"/>
<servo name="B1" no="2" min="1000" neutral="1100" max="2000"/>
<servo name="B2" no="3" min="1000" neutral="1100" max="2000"/>-->
<servo name="ELEVON_LEFT" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVON_RIGHT" no="5" min="1000" neutral="1500" max="2000"/>
</servos>
<servos driver="Asctec_v2_new">
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
<servo name="BACK" no="1" min="0" neutral="3" max="200"/>
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
</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>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[0]"/>
<set servo="BACK" value="motor_mixing.commands[1]"/>
<set servo="LEFT" value="motor_mixing.commands[2]"/>
<set servo="RIGHT" value="motor_mixing.commands[3]"/>
<!-- Mode dependent actuator laws for the elevons. The elevons act different in rc attitude flight mode-->
<!-- First the correct feedback is stored in variables -->
<let var="aileron_feedback_left" value="-@YAW"/>
<let var="aileron_feedback_right" value="-@YAW"/>
<let var="elevator_feedback_left" value="+@PITCH"/>
<let var="elevator_feedback_right" value="-@PITCH"/>
<!-- Here the gains are defined for the two feedback cases, hover and forward-->
<let var="hover_left" value="3*$aileron_feedback_left"/>
<let var="hover_right" value="3*$aileron_feedback_right"/>
<let var="forward_left" value="1*$aileron_feedback_left+4*$elevator_feedback_left"/>
<let var="forward_right" value="1*$aileron_feedback_right+4*$elevator_feedback_right"/>
<!-- This statement tells the autopilot to use the hover feedback if in mode attitude direct and to use the forward feedback in all other cases-->
<set servo="ELEVON_LEFT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_left : $forward_left" />
<set servo="ELEVON_RIGHT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_right : $forward_right" />
</command_laws>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="PITCH_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="ROLL_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="YAW_COEF" value="{ 256, -256, -128, 128 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<!-- If you got a caliberation XML document from your IMU supplier, import this in the IMU section -->
<!-- Note that is better to have *no* caliberation file at all, than a one with incorrect caliberation values.
The default factory values are most of the time perfectly acceptable, so by default we will not use the caliberation file -->
<section name="IMU" prefix="IMU_">
<!-- Use default driver values for gyro -->
<!-- IMU calibration, make sure to calibrate the IMU properly before flight, see the wiki for more info-->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<define name="ACCEL_X_SENS" value="4.86487566223" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.89957269597" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.82616398266" 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="4.19385009207" integer="16"/>
<define name="MAG_Y_SENS" value="4.32306399648" integer="16"/>
<define name="MAG_Z_SENS" value="4.63243801309" integer="16"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="90." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
<define name="MODE_AUTO2" value="AP_MODE_RATE_DIRECT"/>
<!-- <define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/> -->
</section>
<section name="BAT">
<define name="MIN_BAT_LEVEL" value="10.9" units="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="10.3" unit="V"/>
</section>
<!-- These gains are used when the gain scheduling module is enabled (by loading it in the modules section)-->
<section name ="GAIN_SETS">
<define name="NUMBER_OF_GAINSETS" value="2"/>
<define name="SCHEDULING_VARIABLE" value="(radio.values[COMMAND_THRUST]+ transition_status"/>
<define name="SCHEDULING_POINTS" value="{1000, 6000}"/>
<define name="SCHEDULING_VARIABLE_FRAC" value="0"/>
<define name="PHI_P" value="{230, 230}"/>
<define name="PHI_D" value="{170, 170}"/>
<define name="PHI_I" value="{30, 30}"/>
<define name="PHI_DD" value="{0, 0}"/>
<define name="THETA_P" value="{200, 300}"/>
<define name="THETA_D" value="{100, 50}"/>
<define name="THETA_I" value="{40, 40}"/>
<define name="THETA_DD" value="{0, 0}"/>
<define name="PSI_P" value="{300, 300}"/>
<define name="PSI_D" value="{150, 150}"/>
<define name="PSI_I" value="{0, 0}"/>
<define name="PSI_DD" value="{0, 0}"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="60." unit="deg"/>
<define name="SP_MAX_THETA" value="60." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>
<define name="SP_PSI_DELTA_LIMIT" value="90" unit="deg"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="1500" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="1500" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="1500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="90." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="170"/>
<define name="PHI_DGAIN" value="120"/>
<define name="PHI_IGAIN" value="30"/>
<define name="THETA_PGAIN" value="150"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="40"/>
<define name="PSI_PGAIN" value="300"/>
<define name="PSI_DGAIN" value="150"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 0"/>
<define name="THETA_DDGAIN" value=" 0"/>
<define name="PSI_DDGAIN" value=" 0"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.012"/>
<define name="G1_Q" value="0.04"/>
<define name="G1_R" value="0.004"/>
<define name="G2_R" value="0.0"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="70.0"/>
<define name="REF_ERR_Q" value="45.0"/>
<define name="REF_ERR_R" value="70.0"/>
<define name="REF_RATE_P" value="9.0"/>
<define name="REF_RATE_Q" value="16.0"/>
<define name="REF_RATE_R" value="12.0"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="50.0"/>
<define name="FILT_ZETA" value="0.7"/>
<define name="FILT_OMEGA_R" value="20.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.15"/>
<define name="ACT_DYN_Q" value="0.15"/>
<define name="ACT_DYN_R" value="0.15"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<!-- Gains for vertical navigation -->
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="200"/>
<define name="HOVER_KD" value="175"/>
<define name="HOVER_KI" value="72"/>
<define name="NOMINAL_HOVER_THROTTLE" value ="0.4"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>
<!-- Gains for horizontal navigation-->
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="100"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="0"/>
</section>
<section name="MISC">
<!-- <define name="REF_QUAT_INFINITESIMAL_STEP" value="TRUE"/> -->
<!--The Quadshot uses a slightly different axis system for the setpoint, to make both hovering and flying forward intuitive-->
<define name="USE_EARTH_BOUND_RC_SETPOINT" value="TRUE"/>
<!-- This is the pitch angle that the Quadshot will have in forward flight, where 0 degrees is hover-->
<define name="TRANSITION_MAX_OFFSET" value="-80.0" unit="deg"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="gps" type="ubx_ucenter"/>
<!-- The the led_safety_status module will make the Quadshot LEDs blink in certain patterns when there are safety violations-->
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
<!-- Load this module to use multiple gain sets, which have to be specified in the gain sets section -->
<!--module name="gain_scheduling"/-->
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
<!-- Put the mode on channel AUX1-->
<define name="RADIO_KILL_SWITCH" value="5"/>
<!-- <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/> -->
</module>
<configure name="FLASH_MODE" value="SWD"/>
<!-- on aspirin 2.1 the ms5611 baro is not connected via SPI, use BMP085 on Lisa/M board instead -->
<!-- <configure name="LISA_M_BARO" value="BARO_BOARD_BMP085"/> -->
<!-- If using aspirin 2.2, make sure to uncomment the following barometer configuration: -->
<configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
</module>
<module name="actuators" type="asctec_v2_new"/>
<module name="telemetry" type="transparent"/>
<!-- <module name="telemetry" type="transparent"/> -->
<module name="imu" type="aspirin_v2.2"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="indi"/>
<module name="stabilization" type="rate_indi"/>
<module name="logger_spi_link"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<!--define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/-->
</module>
<module name="ins"/>
</firmware>
</airframe>
+1 -1
View File
@@ -36,7 +36,7 @@
</sector>
</sectors>
<exceptions>
<exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>
<!-- <exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>-->
<!--<exception cond="datalink_time > 22" deroute="Land here"/>-->
<!-- <exception cond="electrical.bat_low && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land"/>
<exception cond="electrical.bat_critical && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land here"/>-->
+68
View File
@@ -0,0 +1,68 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="1.5" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="100" name="Outdoor basic flight plan" security_height="0.4">
<header>
#include "autopilot.h"
#include "subsystems/ahrs.h"
#include "subsystems/electrical.h"
#include "subsystems/datalink/datalink.h"
</header>
<waypoints>
<waypoint height="0" name="HOME" x="0.0" y="0.0"/>
<waypoint height="2.2" name="CLIMB" x="1.2" y="-0.6"/>
<waypoint height="1.0" name="STDBY" x="-0.7" y="-0.8"/>
<waypoint name="TD" x="0.8" y="-1.7"/>
</waypoints>
<exceptions>
<!-- <exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>-->
<!--<exception cond="datalink_time > 22" deroute="Land here"/>-->
<!-- <exception cond="electrical.bat_low && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land"/>
<exception cond="electrical.bat_critical && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land here"/>-->
</exceptions>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 2)"/>
<call fun="NavSetGroundReferenceHere()"/> <!-- This sets the altitude ref -->
<!-- <call fun="NavSetAltitudeReferenceHere()"/> -->
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="r" name="Start Engine">
<call fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="t" name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 0.9" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block key="s" name="Standby" strip_button="Standby" strip_icon="home.png">
<!-- <call fun="NavSetWaypointHere(WP_STDBY)"/>-->
<stay wp="STDBY"/>
</block>
<block key="l" name="Land here" strip_button="Land Here" strip_icon="land-right.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="Land">
<go wp="TD"/>
</block>
<block name="Flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
<call fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Landed">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
+52
View File
@@ -0,0 +1,52 @@
<!DOCTYPE layout SYSTEM "../layout.dtd">
<layout width="1301" height="744">
<columns>
<rows SIZE="400">
<widget NAME="strips" size="236"/>
<widget NAME="alarms" size="500"/>
</rows>
<rows>
<widget NAME="aircraft" size="258"/>
<widget NAME="altgraph" size="100"/>
<widget NAME="map2d" size="372">
<papget type="message_field" display="text" x="717" y="45">
<property name="scale" value="0.0000019"/>
<property name="field" value="ROTORCRAFT_FP:vup"/>
<property name="format" value="Climb Rate %.2f m/s"/>
<property name="size" value="15."/>
<property name="color" value="yellow"/>
</papget>
<papget type="message_field" display="text" x="756" y="315">
<property name="scale" value="0.01"/>
<property name="field" value="GPS_INT:pacc"/>
<property name="format" value="GPS Acc %.2f m"/>
<property name="size" value="15."/>
<property name="color" value="yellow"/>
</papget>
<papget type="message_field" display="text" x="644" y="317">
<property name="scale" value="1."/>
<property name="field" value="GPS_INT:numsv"/>
<property name="format" value="GPS SV %.0f"/>
<property name="size" value="15."/>
<property name="color" value="yellow"/>
</papget>
<papget type="message_field" display="gauge" x="41" y="291">
<property name="scale" value="1."/>
<property name="field" value="ROTORCRAFT_FP:thrust"/>
<property name="min" value="0."/>
<property name="max" value="100."/>
<property name="size" value="50."/>
<property name="text" value="Thrust"/>
</papget>
<papget type="message_field" display="text" x="675" y="13">
<property name="scale" value="0.0139882"/>
<property name="field" value="ROTORCRAFT_FP:psi"/>
<property name="format" value="Body Heading %.2f deg"/>
<property name="size" value="15."/>
<property name="color" value="yellow"/>
</papget>
</widget>
</rows>
</columns>
</layout>
+1 -1
View File
@@ -146,7 +146,7 @@
<message name="INS_REF" period="5.1"/>
</mode>
</process>
</process>
</telemetry>