cleaned up Delft airframes after IMAV and added delft_basic flight plan

This commit is contained in:
Ewoud Smeur
2015-10-23 16:01:17 +02:00
parent 7c776ed0c6
commit 7557579c57
5 changed files with 95 additions and 44 deletions
@@ -35,26 +35,6 @@
<!--load name="logger_file.xml">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</load-->
<load name="video_thread.xml">
<define name="VIDEO_THREAD_FPS" value="4"/>
<define name="VIDEO_THREAD_CAMERA" value="bottom_camera"/>
<define name="VIDEO_THREAD_SHOT_PATH" value="/data/ftp/internal_000/images"/>
</load>
<load name="cv_blob_locator.xml"/>
<load name="video_rtp_stream.xml">
<define name="VIEWVIDEO_QUALITY_FACTOR" value="80"/>
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="1"/>
</load>
<load name="nav_survey_rectangle_rotorcraft.xml">
<define name="RECTANGLE_SURVEY_DEFAULT_SWEEP" value="10"/>
</load>
<load name="nav_survey_poly_rotorcraft.xml">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="10"/>
</load>
<load name="digital_cam_video.xml">
<define name="DC_AUTOSHOOT_DISTANCE_INTERVAL" value="5"/>
</load>
<load name="video_exif.xml"/>
</modules>
<commands>
@@ -104,10 +84,6 @@
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- Toulouse -->
<!--define name="H_X" value="0.513081"/>
<define name="H_Y" value="-0.00242783"/>
<define name="H_Z" value="0.858336"/-->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
@@ -39,13 +39,6 @@
<load name="geo_mag.xml"/>
<load name="air_data.xml"/>
<load name="servo_switch.xml"/>
<load name="nav_survey_rectangle_rotorcraft.xml">
<define name="RECTANGLE_SURVEY_DEFAULT_SWEEP" value="10"/>
</load>
<load name="nav_survey_poly_rotorcraft.xml">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="10"/>
</load>
<load name="drop_zone.xml"/>
<!--load name="gps_ubx_ucenter.xml"/-->
</modules>
@@ -38,13 +38,6 @@
<load name="geo_mag.xml"/>
<load name="air_data.xml"/>
<load name="servo_switch.xml"/>
<load name="nav_survey_rectangle_rotorcraft.xml">
<define name="RECTANGLE_SURVEY_DEFAULT_SWEEP" value="10"/>
</load>
<load name="nav_survey_poly_rotorcraft.xml">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="10"/>
</load>
<load name="drop_zone.xml"/>
<load name="gps_ubx_ucenter.xml"/>
</modules>
+6 -6
View File
@@ -60,9 +60,9 @@
airframe="airframes/TUDelft/airframes/bebop_indi.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/Tudelft/rotorcraft_survey_competition.xml"
flight_plan="flight_plans/Tudelft/delft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_indi.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/geo_mag.xml modules/air_data.xml modules/video_thread.xml modules/cv_blob_locator.xml modules/video_rtp_stream.xml modules/nav_survey_rectangle_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/digital_cam_video.xml"
settings_modules="[modules/geo_mag.xml] modules/air_data.xml"
gui_color="red"
/>
<aircraft
@@ -104,9 +104,9 @@
airframe="airframes/TUDelft/airframes/mavtec4.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/Tudelft/rotorcraft_survey_competition.xml"
flight_plan="flight_plans/Tudelft/delft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml settings/modules/config_asctec_v2.xml settings/control/rotorcraft_guidance.xml"
settings_modules="[modules/geo_mag.xml] [modules/air_data.xml] modules/servo_switch.xml [modules/nav_survey_rectangle_rotorcraft.xml] [modules/nav_survey_poly_rotorcraft.xml] modules/drop_zone.xml"
settings_modules="[modules/geo_mag.xml] [modules/air_data.xml] modules/servo_switch.xml"
gui_color="blue"
/>
<aircraft
@@ -115,9 +115,9 @@
airframe="airframes/TUDelft/airframes/mavtec5.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/Tudelft/rotorcraft_survey_competition.xml"
flight_plan="flight_plans/Tudelft/delft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml settings/modules/config_asctec_v2.xml settings/control/rotorcraft_guidance.xml"
settings_modules="[modules/geo_mag.xml] [modules/air_data.xml] modules/servo_switch.xml [modules/nav_survey_rectangle_rotorcraft.xml] [modules/nav_survey_poly_rotorcraft.xml] modules/drop_zone.xml modules/gps_ubx_ucenter.xml"
settings_modules="[modules/geo_mag.xml] [modules/air_data.xml] modules/servo_switch.xml modules/gps_ubx_ucenter.xml"
gui_color="blue"
/>
<aircraft
+89
View File
@@ -0,0 +1,89 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="4" ground_alt="0" lat0="51 59 27.6" lon0="4 22 42.0" max_dist_from_home="60" name="Delft Basic" security_height="2">
<header>
#include "autopilot.h"
</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="-19.9" y="14.3"/>
<waypoint name="p2" x="-0.6" y="21.6"/>
<waypoint name="p3" x="22.2" y="-26.5"/>
<waypoint name="p4" x="4.9" y="-34.4"/>
<waypoint name="CAM" x="14.2" y="-29.4"/>
<waypoint name="TD" x="5.6" y="-10.9"/>
</waypoints>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 10)"/>
<call fun="NavSetGroundReferenceHere()"/>
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Start Engine">
<call fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 2.0" deroute="Standby"/>
<call fun="NavSetWaypointHere(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"/>
</block>
<block name="stay_p1">
<stay wp="p1"/>
</block>
<block name="go_p2">
<call fun="nav_set_heading_deg(90)"/>
<go wp="p2"/>
<deroute block="stay_p1"/>
</block>
<block name="line_p1_p2">
<go from="p1" hmode="route" wp="p2"/>
<stay until="stage_time>10" wp="p2"/>
<go from="p2" hmode="route" wp="p1"/>
<deroute block="stay_p1"/>
</block>
<block name="route">
<go from="p1" hmode="route" wp="p3"/>
<go from="p3" hmode="route" wp="p4"/>
<go from="p4" hmode="route" wp="p1"/>
<deroute block="stay_p1"/>
</block>
<block name="test yaw">
<go wp="p1"/>
<for from="1" to="16" var="i">
<heading alt="WaypointAlt(WP_p1)" course="90 * $i" until="stage_time > 3"/>
</for>
<deroute block="Standby"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="land">
<go wp="TD"/>
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>