6 changes: 3 additions & 3 deletions conf/airframes/tudelft/bebop_course_orangeavoid.xml
Expand Up @@ -8,12 +8,12 @@
<firmware name="rotorcraft">
<target name="ap" board="bebop">
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000/log"/>
<define name="MT9V117_TARGET_FPS" value="20"/>

<!-- Detect orange -->
<define name="COLOR_OBJECT_DETECTOR_LUM_MIN1" value="30"/>
<define name="COLOR_OBJECT_DETECTOR_LUM_MAX1" value="170"/>
<define name="COLOR_OBJECT_DETECTOR_LUM_MAX1" value="190"/>
<define name="COLOR_OBJECT_DETECTOR_CB_MIN1" value="70"/>
<define name="COLOR_OBJECT_DETECTOR_CB_MAX1" value="130"/>
<define name="COLOR_OBJECT_DETECTOR_CR_MIN1" value="150"/>
Expand All @@ -22,7 +22,7 @@
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
<define name="VIDEO_CAPTURE_PATH" value="/tmp/paparazzi/images"/>
<define name="FILE_LOGGER_PATH" value="/tmp/paparazzi/log"/>
<define name="LOGGER_FILE_PATH" value="/tmp/paparazzi/log"/>

<!-- Detect orange -->
<define name="COLOR_OBJECT_DETECTOR_LUM_MIN1" value="41"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/airframes/tudelft/bebop_course_orangeavoid_guided.xml
Expand Up @@ -7,7 +7,7 @@
<firmware name="rotorcraft">
<target name="ap" board="bebop">
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000/log"/>
<define name="MT9V117_TARGET_FPS" value="20"/>

<!-- Detect orange -->
Expand All @@ -29,7 +29,7 @@
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
<define name="VIDEO_CAPTURE_PATH" value="/tmp/paparazzi/images"/>
<define name="FILE_LOGGER_PATH" value="/tmp/paparazzi/log"/>
<define name="LOGGER_FILE_PATH" value="/tmp/paparazzi/log"/>

<!-- Detect orange -->
<define name="COLOR_OBJECT_DETECTOR_LUM_MIN1" value="41"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_flip.xml
Expand Up @@ -32,7 +32,7 @@
<module name="geo_mag"/>
<module name="air_data"/>
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module>
</firmware>

Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_indi.xml
Expand Up @@ -39,7 +39,7 @@
<module name="geo_mag"/>
<module name="air_data"/>
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module>
</firmware>

Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_indi_actuators.xml
Expand Up @@ -39,7 +39,7 @@
<module name="geo_mag"/>
<module name="air_data"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module-->
</firmware>

Expand Down
4 changes: 2 additions & 2 deletions conf/airframes/tudelft/bebop_mav_course_exercise.xml
Expand Up @@ -7,7 +7,7 @@
<firmware name="rotorcraft">
<target name="ap" board="bebop">
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000/log"/>
<define name="MT9V117_TARGET_FPS" value="20"/>

<!-- Detect orange -->
Expand All @@ -21,7 +21,7 @@
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
<define name="VIDEO_CAPTURE_PATH" value="/tmp/paparazzi/images"/>
<define name="FILE_LOGGER_PATH" value="/tmp/paparazzi/log"/>
<define name="LOGGER_FILE_PATH" value="/tmp/paparazzi/log"/>

<!-- Detect orange -->
<define name="COLOR_OBJECT_DETECTOR_LUM_MIN1" value="41"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_mavlink.xml
Expand Up @@ -36,7 +36,7 @@
<module name="geo_mag"/>
<module name="air_data"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module-->
<module name="bebop_cam"/>

Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_opticflow_indoor_2x_30hz.xml
Expand Up @@ -13,7 +13,7 @@ pyramid level 2: 21 fps average, min=11fps
<firmware name="rotorcraft">
<target name="ap" board="bebop"/>
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000/log"/>
<define name="USE_SONAR"/>
<!--target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/bebop_optitrack.xml
Expand Up @@ -27,7 +27,7 @@
</module>
<module name="ins" type="extended"/>
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module>
</firmware>

Expand Down
4 changes: 2 additions & 2 deletions conf/airframes/tudelft/bebop_ralphthesis2020_stereo.xml
Expand Up @@ -8,12 +8,12 @@
<firmware name="rotorcraft">
<target name="ap" board="bebop">
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000/log"/>
</target>
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
<define name="VIDEO_CAPTURE_PATH" value="/tmp/paparazzi/images"/>
<define name="FILE_LOGGER_PATH" value="/tmp/paparazzi/log"/>
<define name="LOGGER_FILE_PATH" value="/tmp/paparazzi/log"/>

</target>

Expand Down
21 changes: 13 additions & 8 deletions conf/airframes/tudelft/cyfoam.xml
@@ -1,6 +1,6 @@
<!--Mini-Cyclone EPP Airframe
Chimera AP
Xbee API
Xbee API
Ublox M8T
SBUS Futaba -->

Expand Down Expand Up @@ -66,6 +66,7 @@
<section name="BAT">
<define name="LOW_BAT_LEVEL" value="13.9" units="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="13.2" unit="V"/>
<define name="MAX_BAT_LEVEL" value="14.8" units="V"/>
</section>

<section name="ctrl_eff_scheduling" prefix="FWD_">
Expand Down Expand Up @@ -212,7 +213,7 @@
<module name="udp"/>
<module name="radio_control" type="datalink"/>
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/home/ewoud/Documents"/>
<define name="LOGGER_FILE_PATH" value="/home/ewoud/Documents"/>
</module>

<!--Switch advanced INDI scheduling functions on or off-->
Expand Down Expand Up @@ -296,21 +297,25 @@
<define name="GUIDANCE_INDI_SPEED_GAIN" value="1.0"/>
<define name="GUIDANCE_INDI_POS_GAINZ" value="0.5"/>
<define name="GUIDANCE_INDI_SPEED_GAINZ" value="1.8"/>
<define name="GUIDANCE_INDI_PITCH_LIFT_EFF" value="0.12"/>
<define name="GUIDANCE_INDI_LIFTD_ASQ" value="0.20"/>
<define name="GUIDANCE_INDI_PITCH_EFF_SCALING" value="1.0"/>
<define name="GUIDANCE_H_REF_MAX_SPEED" value="18.0"/> <!--not used-->
<define name="GUIDANCE_INDI_MIN_THROTTLE" value="3000"/>
<define name="GUIDANCE_INDI_MIN_THROTTLE_FWD" value="1500"/>
<define name="GUIDANCE_INDI_MAX_AIRSPEED" value="16.0"/>
<define name="GUIDANCE_HEADING_IS_FREE" value="FALSE"/> <!--heading can not be set by navigation-->
<define name="GUIDANCE_INDI_HEADING_BANK_GAIN" value="15.0"/>
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
<define name="GUIDANCE_INDI_THRUST_DYNAMICS" value="0.045"/>
<!--<define name="KNIFE_EDGE_TEST" value="TRUE"/>-->
<!--Flap effectiveness on lift-->
<define name="FE_LIFT_A_PITCH" value="0.00018"/>
<define name="FE_LIFT_B_PITCH" value="0.00072"/>
<define name="FE_LIFT_A_AS" value="0.0008"/>
<define name="FE_LIFT_B_AS" value="0.00009"/>
</module>
<module name="nav" type="hybrid">
<define name="GUIDANCE_H_USE_REF" value="FALSE"/>
</module>

<!--<module name="ahrs" type="int_cmpl_quat">-->
<!--<configure name="USE_MAGNETOMETER" value="TRUE"/>-->
Expand All @@ -319,11 +324,11 @@
<!--<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="TRUE"/>-->
<!--</module>-->

<!--<module name="ins"/>-->
<!-- <module name="ins" type="ekf2"/> -->
<module name="ins" type="float_invariant">
<!--module name="ins"/-->
<module name="ins" type="ekf2"/>
<!--module name="ins" type="float_invariant">
<define name="INS_PROPAGATE_FREQUENCY" value="500"/>
</module>
</module-->

</firmware>
</airframe>
276 changes: 276 additions & 0 deletions conf/airframes/tudelft/disco_rotorcraft_indi.xml
@@ -0,0 +1,276 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<!--
Parrot Disco
-->

<airframe name="Disco">

<firmware name="rotorcraft">
<configure name="PERIODIC_FREQUENCY" value="512"/>
<configure name="USE_MAGNETOMETER" value="TRUE"/>

<target name="ap" board="disco">

<module name="radio_control" type="sbus"/>
<module name="logger_file">
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module>
<module name="airspeed" type="ms45xx_i2c">
<define name="MS45XX_I2C_DEV" value="i2c1"/>
<define name="MS45XX_PRESSURE_RANVE" value="0.05"/>
<define name="USE_AIRSPEED_MS45XX" value="TRUE"/>
</module>

<define name="RADIO_TH_HOLD" value="RADIO_AUX1"/> <!-- Throttle hold in command laws -->
<define name="RADIO_FMODE" value="RADIO_AUX2"/> <!-- Throttle curve select -->
<define name="RADIO_FBW_MODE" value="RADIO_AUX3"/> <!-- Switch between AP and FBW control -->
<define name="RADIO_FLAPS" value="RADIO_AUX4"/> <!-- Flaps control -->
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
<define name="RADIO_BACK_THOLD" value="RADIO_AUX5"/>

</target>

<target name="nps" board="pc">
<define name="USE_AIRSPEED" value="TRUE"/>
<module name="fdm" type="jsbsim"/>
<module name="udp"/>
<module name="radio_control" type="datalink"/>


<!--Not dealing with these in the simulation-->
<define name="RADIO_TH_HOLD" value="0"/> <!-- Throttle hold in command laws -->
<define name="RADIO_FMODE" value="0"/> <!-- Throttle curve select -->
<define name="RADIO_FBW_MODE" value="0"/> <!-- Switch between AP and FBW control -->
<define name="RADIO_FLAPS" value="0"/> <!-- Flaps control -->
<define name="RADIO_KILL_SWITCH" value="0"/>
</target>

<module name="telemetry" type="transparent_udp"/>

<module name="imu" type="disco"/>
<!--<module name="ahrs" type="float_dcm"/>-->
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="ins" type="ekf2"/>

<module name="air_data"/>
<module name="actuators" type="disco"/>
<!--<module name="control" type="new"/>-->
<module name="stabilization" type="indi">
<configure name="INDI_NUM_ACT" value="3"/>
</module>
<module name="guidance" type="indi_hybrid"/>
<!--<module name="sonar_bebop">
<define name="USE_SONAR"/>
<define name="SENSOR_SYNC_SEND_SONAR"/>
</module>-->

<!--Switch advanced INDI scheduling functions on or off-->
<define name="INDI_FUNCTIONS_RC_CHANNEL" value="6"/>
</firmware>

<servos>
<servo name="MOTOR" no="0" min="1000" neutral="1000" max="12500"/> <!-- 12500 max -->
<servo name="AILEVON_RIGHT" no="6" min="1850" neutral="1450" max="1050"/>
<servo name="AILEVON_LEFT" no="1" min="1050" neutral="1450" max="1850"/>
</servos>

<commands>
<axis name="THRUST" 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="THRUST" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</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="th_hold" value="LessThan(RadioControlValues(RADIO_TH_HOLD), -4800)"/>
<let var="manual" value="LessThan(RadioControlValues(RADIO_MODE), -4800)"/>
<let var="autopil" value="(1-($manual))"/>

<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>

<let var="motor_thrust" value="$manual? @THRUST : actuators_pprz[2]"/>

<set servo="MOTOR" value="$th_hold? -9600 : $motor_thrust"/>
<set servo="AILEVON_LEFT" value="($elevator - $aileron) * $manual - actuators_pprz[0] * $autopil"/>
<set servo="AILEVON_RIGHT" value="($elevator + $aileron) * $manual + actuators_pprz[1] * $autopil"/>
</command_laws>

<section name="MISC">
<define name="NO_GPS_LOST_WITH_RC_VALID" value="TRUE"/>
<define name="NAV_CLIMB_VSPEED" value="3.5"/>
<define name="NAV_DESCEND_VSPEED" value="-1.0"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
<define name="ROTORCRAFT_COMMANDS_YAW_ALWAYS_ENABLED" value="TRUE"/>
<define name="VoltageOfAdc(adc)" value="((3.3f/4096.0f) * 12.0877510901 * adc)"/>
<!--<define name="USE_AIRSPEED" value="TRUE"/>-->
<define name="ARRIVED_AT_WAYPOINT" value="50.0"/>
</section>

<section name="FORWARD">
<!--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="-90.0" unit="deg"/>
<!-- For hybrid guidance by default set to 15-->
<!--<define name="MAX_AIRSPEED" value="20.0"/>-->
</section>

<!--<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>-->

<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="-164"/>
<define name="ACCEL_Y_NEUTRAL" value="-19"/>
<define name="ACCEL_Z_NEUTRAL" value="-302"/>
<define name="ACCEL_X_SENS" value="2.4353263325616896" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.430457186142149" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.4083032197503895" integer="16"/>

<define name="MAG_X_NEUTRAL" value="-195"/>
<define name="MAG_Y_NEUTRAL" value="-266"/>
<define name="MAG_Z_NEUTRAL" value="-806"/>
<define name="MAG_X_SENS" value="7.239846705729754" integer="16"/>
<define name="MAG_Y_SENS" value="7.037092768037254" integer="16"/>
<define name="MAG_Z_SENS" value="7.583294047780469" integer="16"/>

<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="AHRS" prefix="AHRS_">
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
</section>

<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness, scaled by INDI_G_SCALING (1000)-->
<define name="G1_ROLL" value="{ 0, 0, 0}"/>
<define name="G1_PITCH" value="{-8.79, 8.79, 0}"/>
<define name="G1_YAW" value="{-15.97, -15.97, 0}"/>
<define name="G1_THRUST" value="{ 0, 0, -1.8}"/>
<!--Counter torque effect of spinning up a rotor-->
<define name="G2" value="{0, 0, 0}"/>

<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="100.0"/>
<define name="REF_ERR_Q" value="100.0"/>
<define name="REF_ERR_R" value="100.0"/>
<define name="REF_RATE_P" value="14.0"/>
<define name="REF_RATE_Q" value="15.0"/>
<define name="REF_RATE_R" value="15.0"/>

<!--Maxium yaw rate, to avoid instability-->
<define name="MAX_R" value="100.0" unit="deg/s"/>

<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>

<!-- first order actuator dynamics -->
<define name="ACT_DYN" value="{0.1, 0.1, 0.045}"/>
<define name="ACT_RATE_LIMIT" value="{170, 170, 9600}"/>
<define name="ACT_IS_SERVO" value="{1, 1, 0}"/>

<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>

<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="40." unit="deg"/>
<define name="SP_MAX_THETA" value="25." 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="0.001" unit="deg"/>
</section>

<section name="ctrl_eff_scheduling" prefix="FWD_">
<!-- control effectiveness, scaled by INDI_G_SCALING (1000)-->
<define name="G1_ROLL" value="{ 0, 0, 0}"/>
<define name="G1_PITCH" value="{-8.79, 8.79, 0}"/>
<define name="G1_YAW" value="{-15.97, -15.97, 0}"/>
<define name="G1_THRUST" value="{ 0, 0, -0.7}"/>
</section>

<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="310"/>
<define name="HOVER_KD" value="130"/>
<define name="HOVER_KI" value="10"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="45" unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="60"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="0"/>
<define name="IGAIN" value="20"/>
</section>

<section name="GUIDANCE_INDI_HYBRID" prefix="GUIDANCE_INDI_">
<define name="POS_GAIN" value="0.2"/>
<define name="POS_GAINZ" value="0.2"/>
<define name="SPEED_GAIN" value="1.0"/>
<define name="SPEED_GAINZ" value="1.0"/>
<define name="MAX_AIRSPEED" value="12."/>
<define name="ZERO_AIRSPEED" value="FALSE"/>
<define name="NAV_SPEED_MARGIN" value="10.0"/>
<define name="PITCH_EFF_SCALING" value="1.0"/>
<define name="PITCH_LIFT_EFF" value="0.12"/>
<define name="HEADING_BANK_GAIN" value="15."/>
<!--define name="SPECIFIC_FORCE_GAIN" value="-1300."/-->
<!--define name="THRUST_DYNAMICS" value="0.04"/-->
<define name="MIN_THROTTLE" value="0.0"/>
<define name="MIN_THROTTLE_FWD" value="0.0"/>
<define name="MIN_PITCH" value="-115."/>
<define name="MAX_PITCH" value="-75."/>
</section>

<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>

<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.6" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/>

<define name="MilliAmpereOfAdc(_adc)" value="(_adc-632)*4.14"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="ele_left, ele_right, mot" type="string[]"/>
<define name="JSBSIM_MODEL" value="disco_rotorcraft" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="NO_MOTOR_MIXING" value="TRUE"/>
<define name="COMMANDS_NB" value="3"/>
</section>

</airframe>
2 changes: 1 addition & 1 deletion conf/airframes/tudelft/fan_demo.xml
Expand Up @@ -31,7 +31,7 @@
<module name="geo_mag"/>
<module name="air_data"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
<define name="LOGGER_FILE_PATH" value="/data/ftp/internal_000"/>
</module-->
</firmware>

Expand Down
264 changes: 175 additions & 89 deletions conf/airframes/tudelft/nederdrone4.xml

Large diffs are not rendered by default.

9 changes: 6 additions & 3 deletions conf/airframes/tudelft/nederdrone4_tem.xml
Expand Up @@ -52,7 +52,7 @@
<module name="scheduling_indi_simple"/>

<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/home/ewoud/Documents"/>
<define name="LOGGER_FILE_PATH" value="/home/ewoud/Documents"/>
</module>

<!--Not dealing with these in the simulation-->
Expand All @@ -77,7 +77,7 @@
<module name="stabilization" type="indi_simple"/>
<module name="stabilization" type="rate_indi"/>
<module name="ins" type="ekf2" />

<module name="air_data"/>

<!-- Internal MAG -->
Expand All @@ -97,6 +97,10 @@
<configure name="USE_TFMINI_AGL" value="FALSE"/>
</module-->

<module name="nav" type="hybrid">
<define name="GUIDANCE_H_USE_REF" value="FALSE"/>
</module>

<module name="guidance" type="indi_hybrid">
<define name="GUIDANCE_INDI_RC_DEBUG" value="FALSE"/>
<define name="GUIDANCE_INDI_POS_GAIN" value="0.2"/>
Expand All @@ -107,7 +111,6 @@
<define name="GUIDANCE_INDI_PITCH_EFF_SCALING" value="1.0"/>
<define name="GUIDANCE_H_REF_MAX_SPEED" value="18.0"/> <!--not used-->
<define name="GUIDANCE_INDI_MAX_AIRSPEED" value="16.0"/>
<define name="GUIDANCE_HEADING_IS_FREE" value="FALSE"/> <!--heading can not be set by navigation-->
<define name="GUIDANCE_INDI_HEADING_BANK_GAIN" value="5"/>
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-943.0"/>
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN_45" value="-500.0"/>
Expand Down

Large diffs are not rendered by default.

402 changes: 402 additions & 0 deletions conf/airframes/tudelft/nederdrone7.xml

Large diffs are not rendered by default.

407 changes: 407 additions & 0 deletions conf/airframes/tudelft/nederdrone8.xml

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion conf/airframes/tudelft/splash4.xml
Expand Up @@ -48,7 +48,7 @@
<module name="fdm" type="jsbsim"/>

<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/home/ewoud/Documents"/>
<define name="LOGGER_FILE_PATH" value="/home/ewoud/Documents"/>
</module>

<!--Not dealing with these in the simulation-->
Expand Down
@@ -1,60 +1,91 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<airframe name="bebop2_opticflow">
<description>?
</description>

<firmware name="rotorcraft">
<target name="ap" board="bebop2"/>
<define name="USE_SONAR"/>
<target name="ap" board="bebop">
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000/log"/> <!-- we did not include log before -->
</target>
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
<define name="VIDEO_CAPTURE_PATH" value="/home/guido/paparazzi/images"/>
<define name="FILE_LOGGER_PATH" value="/home/guido/paparazzi/log"/>
</target>

<define name="USE_SONAR"/>
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="datalink"/>
<module name="stabilization" type="indi_simple"/>

<!--
<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>
<module name="ins" type="hff_extended"/>
</module>
<module name="ins" type="extended"/> -->

<define name="AHRS_USE_GPS_HEADING" value="TRUE"/>
<module name="ins" type="flow"/>
<!-- These are already defined in fdm_gazebo
<define name="NPS_BYPASS_AHRS" value="FALSE"/>
<define name="NPS_BYPASS_INS" value="FALSE"/>
-->

<!-- Disable use of GPS: -->
<!-- <define name="INS_INT_GPS_ID" value="ABI_DISABLE"/>
</module> -->


<!-- <module name="geo_mag"/>
<module name="send_imu_mag_current"/> -->
<module name="air_data"/>
<!-- <module name="gps" type="ubx_ucenter"/> -->
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module>

<module name="bebop_cam"/>
<module name="video_thread"/>

<module name="pose_history"/>

<module name="logger_file">
<!-- <define name="FILE_LOGGER_PATH" value="/home/guido/paparazzi/log"/> -->
</module>

<module name="cv_opticflow">
<define name="OPTICFLOW_FPS" value="90"/>
<define name="OPTICFLOW_CAMERA" value="bottom_camera"/>
<define name="MAX_HORIZON" value="10"/>
<define name="OPTICFLOW_FX" value="347.22222222"/> <!-- 2.5 / (3.6 * 2.0) * 1000 -->
<define name="OPTICFLOW_FY" value="347.22222222"/> <!-- 2.5 / (3.6 * 2.0) * 1000 -->
<define name="OPTICFLOW_FOV_W" value="0.665499265"/> <!-- 2 * arctan(240 / (2*347.22222222)) -->
<define name="OPTICFLOW_FOV_H" value="0.665499265"/> <!-- 2 * arctan(240 / (2*347.22222222)) -->
<define name="OPTICFLOW_DEROTATION_CORRECTION_FACTOR_X" value="0.8"/> <!--Obtained from a linefit-->
<define name="OPTICFLOW_DEROTATION_CORRECTION_FACTOR_Y" value="0.85"/> <!--Obtained from a linefit-->
</module>

<module name="video_capture">
<define name="VIDEO_CAPTURE_CAMERA" value="bottom_camera"/>
<!-- <define name="VIDEO_CAPTURE_CAMERA" value="front_camera"/> -->
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images"/>
</module>

<module name="cv_textons.xml">
<define name="TEXTONS_FPS" value="1"/>
<define name="TEXTONS_CAMERA" value="bottom_camera"/>
<define name="TEXTONS_N_TEXTONS" value="20"/>
<define name="TEXTONS_DICTIONARY_PATH" value="./"/>
</module>

<module name="optical_flow_landing.xml"/>

<!-- <module name="video_rtp_stream">
<module name="video_rtp_stream">
<define name="VIEWVIDEO_CAMERA" value="bottom_camera"/>
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="1"/>
<define name="VIEWVIDEO_QUALITY_FACTOR" value="60"/>
</module> -->
</module>

</firmware>

<commands>
Expand Down Expand Up @@ -103,28 +134,28 @@
<define name="MAG_Z_SENS" value="7.57102035692" 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 -->
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
</section>
-->

<!--
<section name="INS" prefix="INS_">
<define name="USE_GPS_ALT" value="1"/>
<!-- trust GPS a lot: -->
<define name="VFF_R_GPS" value="0.01"/>
<define name="VFF_VZ_R_GPS" value="0.01"/>
<define name="SONAR_MIN_RANGE" value="0.0"/>
<define name="SONAR_MAX_RANGE" value="2.2"/>

<define name="SONAR_UPDATE_ON_AGL" value="FALSE"/>
</section>

-->

<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
Expand All @@ -136,6 +167,14 @@
<define name="DEADBAND_R" value="50"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="bebop" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="MT9F002_SENSOR_RES_DIVIDER" value="4"/>
</section>
<include href="conf/simulator/gazebo/airframes/bebop.xml"/>

<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
Expand All @@ -154,12 +193,14 @@
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>


<!-- SIMULATION SETTINGS -->
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness, can be obtained by switching on "adaptive" in the indi settings -->
<define name="G1_P" value="0.100"/>
<define name="G1_Q" value="0.050"/>
<define name="G1_R" value="0.0010"/>
<define name="G2_R" value="0.236"/>
<!-- control effectiveness -->
<define name="G1_P" value="0.0397"/>
<define name="G1_Q" value="0.0299"/>
<define name="G1_R" value="0.0014"/>
<define name="G2_R" value="0.1219"/>

<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="600.0"/>
Expand All @@ -169,12 +210,17 @@
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>

<define name="FILT_CUTOFF" value="3.2"/>
<!--Maxium yaw rate, to avoid instability-->
<define name="MAX_R" value="120.0" unit="deg/s"/>

<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="8.0"/>
<define name="ESTIMATION_FILT_CUTOFF" value="8.0"/>

<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<define name="ACT_DYN_P" value="0.1"/>
<define name="ACT_DYN_Q" value="0.1"/>
<define name="ACT_DYN_R" value="0.1"/>

<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
Expand Down Expand Up @@ -208,17 +254,21 @@
<define name="DESCEND_VSPEED" value="-0.75"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
</section>

<section name="AUTOPILOT">



<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_MODULE"/>
<define name="MODE_AUTO1" value="AP_MODE_MODULE"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>

<!--
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
-->
<!--
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_MANUAL" value="AP_MODE_MODULE"/>
Expand Down
21 changes: 12 additions & 9 deletions conf/autopilot/rotorcraft_autopilot.xml
Expand Up @@ -39,18 +39,19 @@

<control_block name="throttle_direct">
<call fun="guidance_v_read_rc()"/>
<call fun="guidance_v_z_sp = stateGetPositionNed_i()->z"/>
<call fun="stabilization_cmd[COMMAND_THRUST] = guidance_v_rc_delta_t"/>
<call fun="guidance_v_set_z(stateGetPositionNed_i()->z)"/>
<call fun="stabilization_cmd[COMMAND_THRUST] = guidance_v.rc_delta_t"/>
</control_block>

<control_block name="altitude_loop">
<call fun="gv_update_ref_from_z_sp(guidance_v_z_sp)"/>
<call fun="run_hover_loop(autopilot_in_flight())"/>
<call fun="gv_update_ref_from_z_sp(guidance_v.z_sp)"/>
<call fun="guidance_v.delta_t = guidance_v_run_pos(autopilot_in_flight(), &guidance_v)"/>
<call fun="stabilization_cmd[COMMAND_THRUST] = guidance_v.rc_delta_t"/>
<!--call fun="SaturateThrottle(rc_values)"/-->
</control_block>

<exceptions>
<exception cond="too_far_from_home" deroute="HOME"/>
<exception cond="nav.too_far_from_home" deroute="HOME"/>
<exception cond="kill_switch_is_on()" deroute="KILL"/>
</exceptions>

Expand Down Expand Up @@ -112,7 +113,7 @@
<on_enter>
<call fun="guidance_h_hover_enter()"/>
<call fun="stabilization_attitude_enter()"/>
<call fun="guidance_v_mode = GUIDANCE_V_MODE_GUIDED"/>
<call fun="guidance_v.mode = GUIDANCE_V_MODE_GUIDED"/>
<call fun="guidance_v_guided_enter()"/>
</on_enter>
<control freq="NAVIGATION_FREQUENCY">
Expand Down Expand Up @@ -152,13 +153,15 @@
<on_enter>
<call fun="stabilization_attitude_set_failsafe_setpoint()"/>
<call fun="guidance_v_mode_changed(GUIDANCE_V_MODE_CLIMB)"/>
<call fun="guidance_v_zd_sp = SPEED_BFP_OF_REAL(FAILSAFE_DESCENT_SPEED)"/>
<call fun="guidance_v_set_z(SPEED_BFP_OF_REAL(FAILSAFE_DESCENT_SPEED))"/>
</on_enter>
<control>
<call fun="stabilization_attitude_set_failsafe_setpoint()"/>
<call fun="stabilization_attitude_run(autopilot_in_flight())"/>
<call fun="gv_update_ref_from_zd_sp(guidance_v_zd_sp, stateGetPositionNed_i()->z)"/>
<call fun="run_hover_loop(autopilot_in_flight())"/>
<call fun="gv_update_ref_from_zd_sp(guidance_v.zd_sp, stateGetPositionNed_i()->z)"/>
<call fun="guidance_v_update_ref()"/>
<call fun="guidance_v.delta_t = guidance_v_run_speed(autopilot_in_flight(), &guidance_v)"/>
<call fun="stabilization_cmd[COMMAND_THRUST] = guidance_v.rc_delta_t"/>
<call_block name="set_commands"/>
</control>
<exception cond="!GpsIsLost()" deroute="$LAST_MODE"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/boards/cube_orange.makefile
Expand Up @@ -69,7 +69,7 @@ MODEM_PORT ?= UART2
MODEM_BAUD ?= B57600

# The GPS1 port (UART8 is GPS2)
GPS_PORT ?= UART1
GPS_PORT ?= UART4
GPS_BAUD ?= B57600

# InterMCU port connected to the IO processor
Expand Down
83 changes: 83 additions & 0 deletions conf/boards/matek_h743_slim.makefile
@@ -0,0 +1,83 @@
# Hey Emacs, this is a -*- makefile -*-
#
# matek_h743_slim.makefile
#
# This is for the Flight Controller Matek H743 SLIM
# See http://www.mateksys.com/?portfolio=h743-slim for details
#

BOARD=mateksys
BOARD_VERSION=FC-H743-SLIM
BOARD_DIR=$(BOARD)/$(BOARD_VERSION)
BOARD_CFG=\"arch/chibios/common_board.h\"

ARCH=chibios
$(TARGET).ARCHDIR = $(ARCH)

RTOS=chibios
MCU=cortex-m7

# FPU on H7
USE_FPU=hard
USE_FPU_OPT= -mfpu=fpv5-d16

USE_LTO ?= yes

$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD

##############################################################################
# Architecture or project specific options
#
# Define project name here (target)
PROJECT = $(TARGET)

# Project specific files and paths (see Makefile.chibios for details)
CHIBIOS_BOARD_PLATFORM = STM32H7xx/platform.mk
CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/
CHIBIOS_BOARD_LINKER = STM32H743xI_no_bl.ld
CHIBIOS_BOARD_STARTUP = startup_stm32h7xx.mk

##############################################################################
# Compiler settings
#

# default flash mode is the DFU
# possibilities: DFU-UTIL, SWD, PX4 bootloader
FLASH_MODE ?= DFU-UTIL
DFU_ADDR = 0x08000000
PX4_TARGET = "ap"
PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/matek_h743_slim.prototype"
PX4_BL_PORT ?= "/dev/serial/by-id/usb-*_MatekH743_*"

#
# default LED configuration
#
SDLOG_LED ?= none
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 2
GPS_LED ?= none
SYS_TIME_LED ?= 1

#
# default UART configuration (modem, gps, spektrum)
#
SBUS_PORT ?= UART6
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART6

MODEM_PORT ?= UART7
MODEM_BAUD ?= B57600

GPS_PORT ?= UART2
GPS_BAUD ?= B57600

#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm

36 changes: 18 additions & 18 deletions conf/conf_example.xml
Expand Up @@ -7,7 +7,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -18,7 +18,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -29,7 +29,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -40,7 +40,7 @@
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/versatile_airspeed.xml"
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffffffffff"
/>
<aircraft
Expand All @@ -51,7 +51,7 @@
telemetry="telemetry/default_fixedwing.xml"
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml"
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="#00009e93ffff"
/>
<aircraft
Expand All @@ -62,7 +62,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -73,7 +73,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -84,7 +84,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -95,7 +95,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
gui_color="red"
/>
<aircraft
Expand All @@ -106,7 +106,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
settings_modules="modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_rotorcraft.xml modules/stabilization_indi_simple.xml"
gui_color="red"
/>
<aircraft
Expand All @@ -117,19 +117,19 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_optitrack.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/bebop_cam.xml modules/cv_opticflow.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
settings_modules="modules/bebop_cam.xml modules/cv_opticflow.xml modules/cv_textons.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_flow.xml modules/nav_rotorcraft.xml modules/optical_flow_landing.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="blue"
/>
<aircraft
name="quadshot"
name="Cyfoam"
ac_id="37"
airframe="airframes/examples/quadshot_asp21_spektrum.xml"
radio="radios/dummy.xml"
airframe="airframes/tudelft/cyfoam.xml"
radio="radios/T10CG_SBUS.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
flight_plan="flight_plans/competitions/IMAV2022_falcon.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/guidance_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
gui_color="#5eb6d9dd4484"
/>
<aircraft
name="trashcan"
Expand All @@ -139,7 +139,7 @@
telemetry="telemetry/default_rotorcraft_slow.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="[modules/ahrs_float_cmpl_quat.xml] [modules/gps.xml] [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] [modules/ins_extended.xml] [modules/nav_basic_rotorcraft.xml] modules/radio_control_cc2500_frsky.xml [modules/stabilization_int_quat.xml]"
settings_modules="[modules/ahrs_float_cmpl_quat.xml] modules/electrical.xml [modules/gps.xml] modules/guidance_pid_rotorcraft.xml [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] [modules/ins_extended.xml] modules/nav_rotorcraft.xml modules/radio_control_cc2500_frsky.xml [modules/stabilization_int_quat.xml]"
gui_color="blue"
/>
</conf>
4 changes: 2 additions & 2 deletions conf/conf_tests.xml
Expand Up @@ -7,7 +7,7 @@
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_basic_rotorcraft.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_basic_rotorcraft.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
/>
<aircraft
Expand Down Expand Up @@ -84,7 +84,7 @@
telemetry="telemetry/default_rotorcraft_mavlink.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="blue"
/>
</conf>
38 changes: 19 additions & 19 deletions conf/conf_tests_coverity.xml
Expand Up @@ -7,7 +7,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="#ffff954c0000"
/>
<aircraft
Expand All @@ -18,7 +18,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -29,7 +29,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -40,7 +40,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_adaptive_fw.xml"
gui_color="#ffff7d7d0000"
/>
<aircraft
Expand All @@ -51,7 +51,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -62,7 +62,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -73,7 +73,7 @@
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/versatile_airspeed.xml"
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffffffffff"
/>
<aircraft
Expand All @@ -84,7 +84,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/nav_modules.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -95,7 +95,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -106,7 +106,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml"
settings_modules="modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -117,7 +117,7 @@
telemetry="telemetry/default_fixedwing.xml"
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml"
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="#00009e93ffff"
/>
<aircraft
Expand All @@ -128,7 +128,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -139,7 +139,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -150,7 +150,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="white"
/>
<aircraft
Expand All @@ -161,7 +161,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -172,7 +172,7 @@
telemetry="telemetry/fixedwing_flight_recorder.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/logger_sd_chibios.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -183,7 +183,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
gui_color="red"
/>
<aircraft
Expand All @@ -194,7 +194,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/cv_opticflow.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_int_quat.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/cv_opticflow.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_int_quat.xml"
gui_color="blue"
/>
<aircraft
Expand All @@ -205,7 +205,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/bebop_ae_awb.xml modules/bebop_cam.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/bebop_ae_awb.xml modules/bebop_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
gui_color="red"
/>
</conf>
2 changes: 1 addition & 1 deletion conf/firmwares/setup.makefile
Expand Up @@ -101,7 +101,7 @@ setup_actuators.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD)
SETUP_ACTUATORS_MODEM_PORT_LOWER=$(shell echo $(MODEM_PORT) | tr A-Z a-z)
setup_actuators.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=$(SETUP_ACTUATORS_MODEM_PORT_LOWER) -DPPRZ_UART=$(SETUP_ACTUATORS_MODEM_PORT_LOWER)
setup_actuators.CFLAGS += -DDOWNLINK_TRANSPORT=pprz_tp -DDATALINK=PPRZ
setup_actuators.srcs += modules/datalink/downlink.c pprzlink/src/pprz_transport.c modules/datalink/pprz_dl.c
setup_actuators.srcs += modules/datalink/downlink.c modules/datalink/datalink.c pprzlink/src/pprz_transport.c modules/datalink/pprz_dl.c

setup_actuators.srcs += modules/actuators/actuators.c
setup_actuators.srcs += $(SRC_FIRMWARE)/setup_actuators.c
Expand Down
2 changes: 1 addition & 1 deletion conf/firmwares/test_chibios.makefile
Expand Up @@ -67,7 +67,7 @@ COMMON_TEST_SRCS += $(SRC_ARCH)/mcu_periph/gpio_arch.c

# pprz downlink/datalink
COMMON_TELEMETRY_CFLAGS = -DDOWNLINK -DDOWNLINK_TRANSPORT=pprz_tp -DDATALINK=PPRZ
COMMON_TELEMETRY_SRCS = modules/datalink/downlink.c modules/datalink/pprz_transport.c modules/datalink/pprz_dl.c
COMMON_TELEMETRY_SRCS = modules/datalink/downlink.c modules/datalink/datalink.c modules/datalink/pprz_transport.c modules/datalink/pprz_dl.c

COMMON_TELEMETRY_MODEM_PORT_LOWER=$(shell echo $(MODEM_PORT) | tr A-Z a-z)
COMMON_TELEMETRY_CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD)
Expand Down
2 changes: 1 addition & 1 deletion conf/firmwares/test_progs.makefile
Expand Up @@ -68,7 +68,7 @@ endif

# pprz downlink/datalink
COMMON_TELEMETRY_CFLAGS = -DDOWNLINK -DDOWNLINK_TRANSPORT=pprz_tp -DDATALINK=PPRZ
COMMON_TELEMETRY_SRCS = modules/datalink/downlink.c pprzlink/src/pprz_transport.c modules/datalink/pprz_dl.c
COMMON_TELEMETRY_SRCS = modules/datalink/downlink.c modules/datalink/datalink.c pprzlink/src/pprz_transport.c modules/datalink/pprz_dl.c

# check if we are using UDP
ifneq (,$(findstring UDP, $(MODEM_DEV)))
Expand Down
1 change: 1 addition & 0 deletions conf/flash_modes.xml
Expand Up @@ -102,6 +102,7 @@
<board name="px4fmu_.*"/>
<board name="px4io_.*"/>
<board name="cube_.*"/>
<board name="matek_.*"/>
</boards>
</mode>
<mode name="JTAG (OpenOCD)">
Expand Down
4 changes: 2 additions & 2 deletions conf/flight_plans/AGGIEAIR/rotorcraft_opticlow_test.xml
Expand Up @@ -39,7 +39,7 @@
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="GetPosHeight() @GT 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -83,7 +83,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
8 changes: 4 additions & 4 deletions conf/flight_plans/ENAC/crazyflie_multi_ranger_test.xml
Expand Up @@ -78,7 +78,7 @@ static inline void obstacle_detection_cb(uint8_t sender_id __attribute__((unused
<block name="Take off" strip_button="Takeoff" strip_icon="takeoff.png" group="home">
<exception cond="GetPosHeight() @GT 0.6" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="STDBY"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<stay wp="STDBY"/>
Expand All @@ -103,11 +103,11 @@ static inline void obstacle_detection_cb(uint8_t sender_id __attribute__((unused
<block name="Land Target" strip_button="Land Target" group="target">
<exception cond="GetPosHeight() @LT 0.3" deroute="Ramp down"/>
<exception cond="!nav_is_in_flight()" deroute="Kill Engine"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Ramp down">
<exception cond="guidance_v_delta_t @LT 0.1*9600." deroute="Kill Engine"/>
<set var="fp_throttle" value="guidance_v_delta_t/9600."/>
<exception cond="guidance_v.delta_t @LT 0.1*9600." deroute="Kill Engine"/>
<set var="fp_throttle" value="guidance_v.delta_t/9600."/>
<stay throttle="fp_throttle-0.1*stage_time" vmode="throttle" wp="TD"/>
</block>
<block name="Kill Engine">
Expand Down
12 changes: 6 additions & 6 deletions conf/flight_plans/ENAC/demo_aruco_drop_indoor.xml
Expand Up @@ -98,7 +98,7 @@
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0.1" vmode="throttle" until="stage_time @GT 2"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="STDBY"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<call_once fun="jevois_stream(false)"/>
Expand Down Expand Up @@ -133,7 +133,7 @@
<call_once fun="jevois_stream(true)"/>
<go wp="TAG" height="search_height"/>
<stay wp="TAG" until="(stage_time @GT 3 @AND tag_tracking.status == TAG_TRACKING_RUNNING) @OR (stage_time @GT 15)" height="search_height"/>
<stay wp="TAG" climb="nav_descend_vspeed" vmode="climb" until="((tag_distance @LT drop_height) @AND tag_valid) @OR (GetPosHeight() @LT drop_height/2.)" post_call="tag_valid = false"/>
<stay wp="TAG" climb="nav.descend_vspeed" vmode="climb" until="((tag_distance @LT drop_height) @AND tag_valid) @OR (GetPosHeight() @LT drop_height/2.)" post_call="tag_valid = false"/>
<call_once fun="DropOpen()"/>
<stay wp="TAG" until="stage_time @GT 3" alt="search_height"/>
<set var="tag_tracking.motion_type" value="TAG_TRACKING_FIXED_POS"/>
Expand All @@ -153,7 +153,7 @@
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<exception cond="stateGetPositionEnu_f()->z @LT 0.2" deroute="Ramp down"/>
<call_once fun="jevois_stream(true)"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TAG"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TAG"/>
</block>

<block name="Land Here" strip_button="Land Here" group="home">
Expand All @@ -167,11 +167,11 @@
<!--exception cond="NavDetectGround()" deroute="Holding point"/-->
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<!--call_once fun="NavStartDetectGround()"/-->
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Ramp down">
<exception cond="guidance_v_delta_t @LT 0.05*9600." deroute="Kill landed"/>
<set var="fp_throttle" value="guidance_v_delta_t/9600."/>
<exception cond="guidance_v.delta_t @LT 0.05*9600." deroute="Kill landed"/>
<set var="fp_throttle" value="guidance_v.delta_t/9600."/>
<stay throttle="fp_throttle-0.02*stage_time" vmode="throttle" wp="TAG"/>
</block>
<block name="Kill landed">
Expand Down
8 changes: 4 additions & 4 deletions conf/flight_plans/ENAC/fish_outdoor.xml
Expand Up @@ -76,7 +76,7 @@
<attitude pitch="0" roll="0" throttle="0.1" until="stage_time>2" vmode="throttle"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<call_once fun="NavSetWaypointHere(WP_TD)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="STDBY"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<call_once fun="autopilot_set_mode(AP_MODE_NAV)"/>
Expand All @@ -96,11 +96,11 @@
<block name="flare">
<exception cond="GetPosHeight() @LT 0.3" deroute="Ramp down"/>
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Ramp down">
<exception cond="guidance_v_delta_t @LT 0.1*9600." deroute="Landed"/>
<set value="guidance_v_delta_t/9600." var="fp_throttle"/>
<exception cond="guidance_v.delta_t @LT 0.1*9600." deroute="Landed"/>
<set value="guidance_v.delta_t/9600." var="fp_throttle"/>
<stay throttle="fp_throttle-0.1*stage_time" vmode="throttle" wp="TD"/>
</block>
<block name="Landed">
Expand Down
8 changes: 4 additions & 4 deletions conf/flight_plans/ENAC/fish_voliere.xml
Expand Up @@ -60,7 +60,7 @@
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0.1" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="STDBY"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<call_once fun="autopilot_set_mode(AP_MODE_NAV)"/>
Expand All @@ -80,11 +80,11 @@
<block name="flare">
<exception cond="GetPosHeight() @LT 0.3" deroute="Ramp down"/>
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Ramp down">
<exception cond="guidance_v_delta_t @LT 0.1*9600." deroute="Landed"/>
<set var="fp_throttle" value="guidance_v_delta_t/9600."/>
<exception cond="guidance_v.delta_t @LT 0.1*9600." deroute="Landed"/>
<set var="fp_throttle" value="guidance_v.delta_t/9600."/>
<stay throttle="fp_throttle-0.1*stage_time" vmode="throttle" wp="TD"/>
</block>
<block name="Landed">
Expand Down
6 changes: 3 additions & 3 deletions conf/flight_plans/HOOPERFLY/hooperfly_gsa_one.xml
Expand Up @@ -38,7 +38,7 @@
<block group="init_control" name="Takeoff" strip_button="Takeoff" strip_icon="launch.png">
<exception cond="GetPosHeight() @GT 2.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB"/>
</block>
<block group="waypoint_control_col1" name="Standby" strip_button="Standby" strip_icon="standby.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -110,7 +110,7 @@
<deroute block="stay_p1"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
<circle radius="nav.radius" wp="CAM"/>
</block>
<block group="land_pattern" name="land here" strip_button="Land Here" strip_icon="land_here.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand All @@ -122,7 +122,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
Expand Down
Expand Up @@ -38,7 +38,7 @@
<block group="init_control" name="Takeoff" strip_button="Takeoff" strip_icon="launch.png">
<exception cond="GetPosHeight() @GT 2.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB"/>
</block>
<block group="waypoint_control_col1" name="Standby" strip_button="Standby" strip_icon="standby.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -165,7 +165,7 @@
<call fun="nav_survey_rectangle_rotorcraft_run(WP_S1, WP_S2)"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
<circle radius="nav.radius" wp="CAM"/>
</block>
<block group="land_pattern" name="land here" strip_button="Land Here" strip_icon="land_here.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand All @@ -177,7 +177,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
Expand Down
Expand Up @@ -38,7 +38,7 @@
<block group="init_control" name="Takeoff" strip_button="Takeoff" strip_icon="launch.png">
<exception cond="GetPosHeight() @GT 2.0" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB"/>
</block>
<block group="waypoint_control_col1" name="Standby" strip_button="Standby" strip_icon="standby.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -165,7 +165,7 @@
<call fun="nav_survey_rectangle_rotorcraft_run(WP_S1, WP_S2)"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
<circle radius="nav.radius" wp="CAM"/>
</block>
<block group="land_pattern" name="land here" strip_button="Land Here" strip_icon="land_here.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
Expand All @@ -177,7 +177,7 @@
<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"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/flight_plans/OPENUAS/openuas_rotorcraft_simple.xml
Expand Up @@ -81,7 +81,7 @@ Your safe aircraft operation is *your* responsibility
If the aircraft is later moved to a takeoff spot and the heading is changed it will try to rotate to the original heading as it is taking off which can make some motors spin too fast and cause a flip or other unwanted manovering.
Altough Switching the mode to auto2/NAV from any other mode will reset nav_heading to the current heading this is not enough therefore just befor takeo we set the nav heading to the current heading-->

<!-- old way <set var="nav_heading" value="stateGetNedToBodyEulers_i()->psi">--> <!-- make sure the current heading is set just befor takeoff as far as possible, MAGNETO anyone?-->
<!-- old way <set var="nav.heading" value="stateGetNedToBodyEulers_f()->psi">--> <!-- make sure the current heading is set just befor takeoff as far as possible, MAGNETO anyone?-->
<call_once fun="nav_set_heading_current()"/> <!-- make sure the current heading is set just befor takeoff as far as possible -->
<call_once fun="NavResurrect()"/>
<set value="0" var="autopilot.kill_throttle"/>
Expand Down
14 changes: 7 additions & 7 deletions conf/flight_plans/competitions/IMAV2019_drop.xml
Expand Up @@ -116,7 +116,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png" group="home">
<exception cond="GetPosHeight() @GT 2.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<call_once fun="jevois_stream(false)"/>
Expand All @@ -127,7 +127,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay wp="CLIMB" until="GetPosAlt() @GT GetAltRef() + WaypointAlt(WP_CLIMB) - 5.0"/>
</block>
<block name="Survey-WE SET" strip_button="Survey-WE" strip_icon="survey_we.png" group="survey">
Expand Down Expand Up @@ -157,7 +157,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay wp="CLIMB" until="GetPosAlt() @GT GetAltRef() + WaypointAlt(WP_CLIMB) - 5.0"/>
</block>
<block name="Drop RED" strip_button="RED" group="drop">
Expand Down Expand Up @@ -189,7 +189,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay wp="CLIMB" until="GetPosAlt() @GT GetAltRef() + WaypointAlt(WP_CLIMB) - 5.0"/>
</block>
<block name="Drop BLUE" strip_button="BLUE" group="drop">
Expand Down Expand Up @@ -221,7 +221,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay wp="CLIMB" until="GetPosAlt() @GT GetAltRef() + WaypointAlt(WP_CLIMB) - 5.0"/>
</block>
<block name="Drop YELLOW" strip_button="YELLOW" group="drop">
Expand Down Expand Up @@ -253,7 +253,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="stage_time>2"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB" until="GetPosHeight() @GT 2.0"/>
<stay wp="CLIMB" until="GetPosAlt() @GT GetAltRef() + WaypointAlt(WP_CLIMB) - 5.0"/>
</block>
<block name="Drop HOUSE" strip_button="HOUSE" group="drop">
Expand Down Expand Up @@ -287,7 +287,7 @@ static inline bool delay_test_gf(bool test, int delay) {
<!--exception cond="NavDetectGround()" deroute="Holding point"/-->
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<!--call_once fun="NavStartDetectGround()"/-->
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/flight_plans/competitions/IMAV2022_drop.xml
Expand Up @@ -214,7 +214,7 @@
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0.1" until="stage_time @GT 2" vmode="throttle"/>
<call_once fun="NavSetWaypointHere(WP_LANDPAD)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<set var="mission_nb" value="DROP_NONE"/>
Expand Down Expand Up @@ -458,7 +458,7 @@
</block>
<block name="Flare">
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Kill landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
6 changes: 3 additions & 3 deletions conf/flight_plans/competitions/IMAV2022_falcon.xml
Expand Up @@ -123,7 +123,7 @@
<set value="false" var="force_forward"/>
<attitude pitch="0" roll="0" throttle="0." until="stage_time @GT 2" vmode="throttle"/>
<call_once fun="NavSetWaypointHere(WP_LANDPAD)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<set value="false" var="force_forward"/>
Expand Down Expand Up @@ -181,7 +181,7 @@
</block>
<block name="Flare">
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Emergency Land" strip_button="Emergency Land" group="land">
<call_once fun="NavSetWaypointHere(WP__HERE)"/>
Expand All @@ -190,7 +190,7 @@
</block>
<block name="Emergency Flare">
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="EMERGENCY"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="EMERGENCY"/>
</block>
<block name="Kill landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/flight_plans/competitions/IMAV2022_search.xml
Expand Up @@ -146,7 +146,7 @@
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0.1" until="stage_time @GT 2" vmode="throttle"/>
<call_once fun="NavSetWaypointHere(WP_LANDPAD)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<set var="mission_nb" value="DROP_NONE"/>
Expand Down Expand Up @@ -207,7 +207,7 @@
</block>
<block name="Flare">
<exception cond="!nav_is_in_flight()" deroute="Kill landed"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="LANDPAD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="LANDPAD"/>
</block>
<block name="Kill landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
65 changes: 65 additions & 0 deletions conf/flight_plans/fixedwing_demo_takeoff_land.xml
@@ -0,0 +1,65 @@
<!DOCTYPE flight_plan SYSTEM "flight_plan.dtd">

<flight_plan alt="260" ground_alt="185" lat0="43.46223" lon0="1.27289" max_dist_from_home="1500" name="Fixedwing demo takeoff and land" security_height="25">
<header/>
<waypoints>
<waypoint name="HOME" x="0" y="0"/>
<waypoint name="STDBY" x="49.5" y="100.1"/>
<waypoint alt="215.0" name="AF" x="177.4" y="45.1"/>
<waypoint alt="185.0" name="TD" x="28.8" y="57.0"/>
<waypoint name="CLIMB" x="-114.5" y="162.3"/>
</waypoints>
<variables>
<variable var="land_dir" init="45." min="0." max="360." step="0.1"/>
<variable var="land_distance" init="200." min="0." max="300." step="0.1"/>
</variables>
<modules>
<module name="nav" type="takeoff_and_landing"/>
</modules>
<blocks>
<block name="Wait GPS">
<set value="1" var="autopilot.kill_throttle"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 1)"/>
<call_once fun="NavSetGroundReferenceHere()"/>
</block>
<block name="Holding point">
<call_once fun="autopilot_set_kill_throttle(true)"/>
<attitude roll="0" throttle="0" vmode="throttle"/>
</block>
<block name="Takeoff (WP)" strip_button="Takeoff (WP)" group="takeoff">
<set value="0" var="autopilot.flight_time"/>
<call fun="nav_takeoff_from_wp(WP_CLIMB)"/>
<deroute block="Standby"/>
</block>
<block name="Takeoff (Here)" strip_button="Takeoff (Here)" group="takeoff">
<set value="0" var="autopilot.flight_time"/>
<call fun="nav_takeoff_from_here()"/>
<deroute block="Standby"/>
</block>
<block key="Ctrl+a" name="Standby" strip_button="Standby" strip_icon="home.png" group="home">
<circle radius="nav_radius" wp="STDBY"/>
</block>
<block name="Land (WP)" strip_button="Land (WP)" group="land">
<call fun="nav_land_at_wp(WP_TD, WP_TD, nav_radius)"/>
<deroute block="Landed"/>
</block>
<block name="Land (WP-glide)" strip_button="Land (WP-glide)" group="land">
<call fun="nav_land_at_wp(WP_TD, WP_AF, nav_radius)"/>
<deroute block="Landed"/>
</block>
<block name="Land (Here)" strip_button="Land (Here)" group="land">
<call fun="nav_land_here(0., nav_radius)"/>
<deroute block="Landed"/>
</block>
<block name="Land (Loc)" strip_button="Land (Loc)" group="land">
<call fun="nav_land_at_loc(0., 43.4625, 1.27329, land_dir, land_distance, nav_radius)"/>
<deroute block="Landed"/>
</block>
<block name="Landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
</blocks>
</flight_plan>
6 changes: 3 additions & 3 deletions conf/flight_plans/rotorcraft_basic.xml
Expand Up @@ -36,7 +36,7 @@
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f() @DEREF z @GT 2.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -72,7 +72,7 @@
<deroute block="Standby"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
<circle radius="nav.radius" wp="CAM"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand All @@ -84,7 +84,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/flight_plans/rotorcraft_basic_geofence.xml
Expand Up @@ -85,7 +85,7 @@
<deroute block="stay_p1"/>
</block>
<block name="circle">
<circle radius="nav_radius" wp="p1"/>
<circle radius="nav.radius" wp="p1"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/flight_plans/rotorcraft_basic_safety.xml
Expand Up @@ -87,7 +87,7 @@
<deroute block="stay_p1"/>
</block>
<block name="circle">
<circle radius="nav_radius" wp="p1"/>
<circle radius="nav.radius" wp="p1"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/flight_plans/rotorcraft_basic_superbitrf.xml
Expand Up @@ -92,7 +92,7 @@
<deroute block="stay_p1"/>
</block>
<block name="circle">
<circle radius="nav_radius" wp="p1"/>
<circle radius="nav.radius" wp="p1"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand Down
6 changes: 3 additions & 3 deletions conf/flight_plans/rotorcraft_basic_superbitrf_from_hand.xml
Expand Up @@ -82,7 +82,7 @@ The goal of this flightplan is to have a safe, simple no-brainer flightplan for
<!-- To make sure that takoff is straight up -->
<attitude pitch="0" roll="0" throttle="0.90" until="stage_time @GT 1" vmode="throttle"/>
<!--Alternative <exception cond="WaypointAlt(WP_A) @GT GetPosHeight()" deroute="A_to_B_and_back"/>-->
<stay vmode="climb" climb="nav_climb_vspeed" until="WaypointAlt(WP_STDBY) @GT GetPosHeight()" wp="CLIMB"/>
<stay vmode="climb" climb="nav.climb_vspeed" until="WaypointAlt(WP_STDBY) @GT GetPosHeight()" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png" pre_call="if(!InsideKill(GetPosX(), GetPosY())) NavKillThrottle()">
<exception cond="block_time @GT 60" deroute="land"/>
Expand All @@ -109,7 +109,7 @@ The goal of this flightplan is to have a safe, simple no-brainer flightplan for
<deroute block="stay_p1"/>
</block>
<block name="circle">
<circle radius="nav_radius" wp="p1"/>
<circle radius="nav.radius" wp="p1"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
Expand All @@ -118,7 +118,7 @@ The goal of this flightplan is to have a safe, simple no-brainer flightplan for
<go wp="TD"/>
<exception cond="NavDetectGround()" deroute="landed"/>
<exception cond="!nav_is_in_flight()" deroute="Holding point"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="landed"/>
Expand Down
8 changes: 4 additions & 4 deletions conf/flight_plans/rotorcraft_cam.xml
Expand Up @@ -35,7 +35,7 @@
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="GetPosHeight() @GT 2.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -65,9 +65,9 @@
<deroute block="stay_p1"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<set value="25" var="nav_radius"/>
<set value="25" var="nav.radius"/>
<call_once fun="dc_Circle(30)"/>
<circle radius="nav_radius" until="NavCircleCount() @GT 1.0" wp="CAM"/>
<circle radius="nav.radius" until="NavCircleCount() @GT 1.0" wp="CAM"/>
<call_once fun="dc_stop()"/>
<deroute block="Standby"/>
</block>
Expand All @@ -81,7 +81,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
Expand Down
64 changes: 64 additions & 0 deletions conf/flight_plans/rotorcraft_demo_takeoff_land.xml
@@ -0,0 +1,64 @@
<!DOCTYPE flight_plan SYSTEM "flight_plan.dtd">

<flight_plan alt="157" ground_alt="147" lat0="43 33 50.83" lon0="1 28 52.61" max_dist_from_home="150" name="Rotorcraft demo takeoff and land" security_height="1">
<header/>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="CLIMB" x="0.0" y="5.0"/>
<waypoint name="STDBY" x="-2.0" y="-5.0"/>
<waypoint name="P1" x="3.6" y="-13.9"/>
<waypoint name="TD" x="5.6" y="-10.9" height="2."/>
</waypoints>
<variables>
<variable var="land_dir" init="45." min="0." max="360." step="0.1"/>
<variable var="land_distance" init="10." min="0." max="20." step="0.1"/>
</variables>
<modules>
<module name="nav" type="takeoff_and_landing"/>
</modules>
<blocks>
<block name="Wait GPS">
<call_once fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 1)"/>
<call_once fun="NavSetGroundReferenceHere()"/>
<!--<call_once fun="NavSetAltitudeReferenceHere()"/>-->
</block>
<block name="Holding point">
<call_once fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
<block name="Takeoff (WP)" strip_button="Takeoff (WP)" group="takeoff">
<call fun="nav_takeoff_from_wp(WP_CLIMB)"/>
<deroute block="Standby"/>
</block>
<block name="Takeoff (Here)" strip_button="Takeoff (Here)" group="takeoff">
<call fun="nav_takeoff_from_here()"/>
<deroute block="Standby"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
</block>
<block name="Land (WP)" strip_button="Land (WP)" group="land">
<call fun="nav_land_at_wp(WP_TD, WP_TD, 0.)"/>
<deroute block="Landed"/>
</block>
<block name="Land (WP-glide)" strip_button="Land (WP-glide)" group="land">
<call fun="nav_land_at_wp(WP_TD, WP_STDBY, 0.)"/>
<deroute block="Landed"/>
</block>
<block name="Land (Here)" strip_button="Land (Here)" group="land">
<call fun="nav_land_here(0., 0.)"/>
<deroute block="Landed"/>
</block>
<block name="Land (Loc)" strip_button="Land (Loc)" group="land">
<call fun="nav_land_at_loc(0., waypoint_get_lat_deg(WP_P1), waypoint_get_lon_deg(WP_P1), land_dir, land_distance, 0.)"/>
<deroute block="Landed"/>
</block>
<block name="Landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
</blocks>
</flight_plan>
4 changes: 2 additions & 2 deletions conf/flight_plans/rotorcraft_guido_optitrack.xml
Expand Up @@ -44,7 +44,7 @@
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="GetPosHeight() @GT 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -88,7 +88,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
12 changes: 6 additions & 6 deletions conf/flight_plans/rotorcraft_joystick_enac.xml
Expand Up @@ -7,10 +7,10 @@
#include "autopilot.h"
static inline void joystick_handler(uint8_t sender_id __attribute__((unused)), int16_t roll, int16_t pitch, int16_t yaw, int16_t throttle) {
if (And(autopilot_get_mode() == AP_MODE_NAV, nav_block == joystick_block)) {
nav_roll = ANGLE_BFP_OF_REAL(STABILIZATION_ATTITUDE_SP_MAX_PHI * roll / MAX_PPRZ);
nav_pitch = ANGLE_BFP_OF_REAL(STABILIZATION_ATTITUDE_SP_MAX_THETA * pitch / MAX_PPRZ);
nav_heading = ANGLE_BFP_OF_REAL(3.1416f * yaw / MAX_PPRZ);
nav_throttle = throttle;
nav.roll = (STABILIZATION_ATTITUDE_SP_MAX_PHI * (float)roll / MAX_PPRZ);
nav.pitch = (STABILIZATION_ATTITUDE_SP_MAX_THETA * (float)pitch / MAX_PPRZ);
nav.heading = (3.1416f * (float)yaw / MAX_PPRZ);
nav.throttle = throttle;
}
}
#endif
Expand Down Expand Up @@ -67,7 +67,7 @@ static inline void joystick_handler(uint8_t sender_id __attribute__((unused)), i
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="GetPosHeight() @GT 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="STDBY"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -106,7 +106,7 @@ static inline void joystick_handler(uint8_t sender_id __attribute__((unused)), i
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/flight_plans/rotorcraft_optitrack.xml
Expand Up @@ -43,7 +43,7 @@
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="GetPosHeight() @GT 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
Expand Down Expand Up @@ -87,7 +87,7 @@
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
Expand Down
8 changes: 4 additions & 4 deletions conf/flight_plans/rotorcraft_optitrack_stereoavoid.xml
Expand Up @@ -44,13 +44,13 @@
</block>
<block name="Start Engine" strip_button="Start" strip_icon="takeoff.png">
<call_once fun="NavResurrect()"/>
<set value="stateGetNedToBodyEulers_i()->psi" var="nav_heading"/>
<set value="stateGetNedToBodyEulers_f()->psi" var="nav.heading"/>
<attitude pitch="0" roll="0" throttle="0" until="stage_time @GT 1" vmode="throttle"/>
</block>
<block name="Takeoff">
<exception cond="GetPosHeight() @GT 0.5" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
<stay climb="nav.climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<exception cond="GpsIsLost()" deroute="attitude_land"/>
Expand All @@ -74,7 +74,7 @@
<call_once fun="NavCopyWaypoint(WP_last_wp,WP_GOAL)"/>
<deroute block="land here"/>
</block>
<block name="stay_W0" pre_call="increase_nav_heading(&nav_heading, 30)">
<block name="stay_W0" pre_call="increase_nav_heading(&nav.heading, RadOfDeg(0.5))">
<exception cond="obstacle_detected==0" deroute="route_to_W1"/>
<exception cond="GpsIsLost()" deroute="attitude_land"/>
<exception cond="electrical.bat_low" deroute="land here"/>
Expand Down Expand Up @@ -107,7 +107,7 @@
<exception cond="NavDetectGround()" deroute="landed"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" until="stage_time @GT 4" vmode="climb" wp="TD"/>
<stay climb="nav.descend_vspeed" until="stage_time @GT 4" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
Expand Down