mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-21 03:43:26 +08:00
[conf] Repair TUDelft telemetry and flight plans
This commit is contained in:
@@ -213,8 +213,8 @@
|
||||
ac_id="6"
|
||||
airframe="airframes/TUDELFT/tudelft_outback.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/rotorcraft_with_logger.xml"
|
||||
flight_plan="flight_plans/TUDELFT/tudelft_delft_basic.xml"
|
||||
telemetry="telemetry/TUDELFT/tudelft_outback.xml"
|
||||
flight_plan="flight_plans/TUDELFT/tudelft_delft_outback.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_rate.xml"
|
||||
settings_modules="modules/opa_controller.xml modules/air_data.xml modules/temp_adc.xml modules/logger_sd_spi_direct.xml modules/gps_ubx_ucenter.xml"
|
||||
gui_color="#ffffdffac31f"
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
<module name="imu" type="mpu6000"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="stabilization" type="int_quat"/>
|
||||
<module name="stabilization" type="rate"/>
|
||||
<module name="stabilization" type="rate"/>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" type="hff"/>
|
||||
<module name="guidance" type="indi"/>
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
|
||||
|
||||
<flight_plan alt="5" ground_alt="0" lat0="51 59 27.6" lon0="4 22 42.0" max_dist_from_home="60" name="Delft Basic" security_height="2">
|
||||
<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>
|
||||
@@ -12,12 +12,9 @@
|
||||
<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>
|
||||
<modules>
|
||||
<!-- extra navigation routines -->
|
||||
<module name="nav" type="heli_spinup"/>
|
||||
</modules>
|
||||
<blocks>
|
||||
<block name="Wait GPS">
|
||||
<call fun="NavKillThrottle()"/>
|
||||
@@ -26,30 +23,19 @@
|
||||
<block name="Geo init">
|
||||
<while cond="LessThan(NavBlockTime(), 10)"/>
|
||||
<call fun="NavSetGroundReferenceHere()"/>
|
||||
<call fun="nav_set_heading_current()"/>
|
||||
</block>
|
||||
<block name="Holding point">
|
||||
<call fun="NavKillThrottle()"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
<block name="Start Engine">
|
||||
<call fun="nav_throttle_curve_set(0)" loop="false"/>
|
||||
<call fun="nav_heli_spinup_setup(7, 0.15)" loop="false"/>
|
||||
<call fun="NavResurrect()"/>
|
||||
<call fun="nav_heli_spinup_run()"/>
|
||||
<call fun="nav_throttle_curve_set(1)" loop="false"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" until="stage_time>7" vmode="throttle"/>
|
||||
<call fun="nav_throttle_curve_set(2)" loop="false"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" until="stage_time>3" vmode="throttle"/>
|
||||
</block>
|
||||
<block name="Hold Attitude">
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" until="FALSE" vmode="throttle"/>
|
||||
<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="nav_set_heading_current()"/>
|
||||
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
|
||||
<stay vmode="climb" climb="nav_climb_vspeed" 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"/>
|
||||
@@ -63,7 +49,7 @@
|
||||
</block>
|
||||
<block name="line_p1_p2">
|
||||
<go from="p1" hmode="route" wp="p2"/>
|
||||
<stay wp="p2" until="stage_time>10"/>
|
||||
<stay until="stage_time>10" wp="p2"/>
|
||||
<go from="p2" hmode="route" wp="p1"/>
|
||||
<deroute block="stay_p1"/>
|
||||
</block>
|
||||
@@ -73,6 +59,16 @@
|
||||
<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>
|
||||
@@ -86,7 +82,7 @@
|
||||
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
|
||||
</block>
|
||||
<block name="landed">
|
||||
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
</blocks>
|
||||
</flight_plan>
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<!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">
|
||||
<flight_plan alt="5" 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>
|
||||
@@ -12,7 +12,6 @@
|
||||
<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>
|
||||
<modules>
|
||||
@@ -20,13 +19,14 @@
|
||||
<module name="nav" type="heli_spinup"/>
|
||||
</modules>
|
||||
<blocks>
|
||||
<!--block name="Wait GPS">
|
||||
<block name="Wait GPS">
|
||||
<call fun="NavKillThrottle()"/>
|
||||
<while cond="!GpsFixValid()"/>
|
||||
</block-->
|
||||
</block>
|
||||
<block name="Geo init">
|
||||
<while cond="LessThan(NavBlockTime(), 10)"/>
|
||||
<call fun="NavSetGroundReferenceHere()"/>
|
||||
<call fun="nav_set_heading_current()"/>
|
||||
</block>
|
||||
<block name="Holding point">
|
||||
<call fun="NavKillThrottle()"/>
|
||||
@@ -34,15 +34,20 @@
|
||||
</block>
|
||||
<block name="Start Engine">
|
||||
<call fun="nav_throttle_curve_set(0)" loop="false"/>
|
||||
<call fun="nav_heli_spinup_setup(10, 0.3)" loop="false"/>
|
||||
<call fun="nav_heli_spinup_setup(7, 0.15)" loop="false"/>
|
||||
<call fun="NavResurrect()"/>
|
||||
<call fun="nav_heli_spinup_run()"/>
|
||||
<call fun="nav_throttle_curve_set(1)" loop="false"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" until="stage_time>7" vmode="throttle"/>
|
||||
<call fun="nav_throttle_curve_set(2)" loop="false"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" until="stage_time>3" vmode="throttle"/>
|
||||
</block>
|
||||
<block name="Hold Attitude">
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.3" until="FALSE" vmode="throttle"/>
|
||||
<manual pitch="0" roll="0" yaw="0" throttle="0.15" 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="nav_set_heading_current()"/>
|
||||
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
|
||||
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
|
||||
</block>
|
||||
@@ -53,7 +58,6 @@
|
||||
<stay wp="p1"/>
|
||||
</block>
|
||||
<block name="go_p2">
|
||||
<call fun="nav_set_heading_deg(90)"/>
|
||||
<go wp="p2"/>
|
||||
<deroute block="stay_p1"/>
|
||||
</block>
|
||||
@@ -69,16 +73,6 @@
|
||||
<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>
|
||||
@@ -92,7 +86,7 @@
|
||||
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
|
||||
</block>
|
||||
<block name="landed">
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
|
||||
</block>
|
||||
</blocks>
|
||||
</flight_plan>
|
||||
|
||||
@@ -0,0 +1,162 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
|
||||
<telemetry>
|
||||
|
||||
|
||||
<process name="Main">
|
||||
|
||||
<mode name="default" key_press="d">
|
||||
<message name="AUTOPILOT_VERSION" period="11.1"/>
|
||||
<message name="DL_VALUE" period="1.1"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="ROTORCRAFT_FP" period="0.25"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
|
||||
<message name="WP_MOVED" period="1.3"/>
|
||||
<message name="ROTORCRAFT_CAM" period="1."/>
|
||||
<message name="GPS_INT" period=".25"/>
|
||||
<message name="INS" period=".25"/>
|
||||
<message name="I2C_ERRORS" period="4.1"/>
|
||||
<message name="UART_ERRORS" period="3.1"/>
|
||||
<message name="SUPERBITRF" period="3"/>
|
||||
<message name="ENERGY" period="2.5"/>
|
||||
<message name="DATALINK_REPORT" period="5.1"/>
|
||||
<message name="STATE_FILTER_STATUS" period="3.2"/>
|
||||
<message name="AIR_DATA" period="1.3"/>
|
||||
<message name="SURVEY" period="2.5"/>
|
||||
<message name="OPTIC_FLOW_EST" period="0.25"/>
|
||||
<message name="VECTORNAV_INFO" period="0.5"/>
|
||||
<message name="TEMP_ADC" period="3.0"/>
|
||||
<message name="FBW_STATUS" period="2.0"/>
|
||||
<message name="MOTOR" period="0.5"/>
|
||||
</mode>
|
||||
|
||||
<mode name="ppm">
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="ROTORCRAFT_CMD" period=".05"/>
|
||||
<message name="PPM" period="0.5"/>
|
||||
<message name="RC" period="0.5"/>
|
||||
<message name="ROTORCRAFT_RADIO_CONTROL" period="0.5"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1"/>
|
||||
<message name="BEBOP_ACTUATORS" period="0.2"/>
|
||||
</mode>
|
||||
|
||||
<mode name="raw_sensors">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="IMU_ACCEL_RAW" period=".05"/>
|
||||
<message name="IMU_GYRO_RAW" period=".05"/>
|
||||
<message name="IMU_MAG_RAW" period=".05"/>
|
||||
<message name="BARO_RAW" period=".1"/>
|
||||
<message name="ARDRONE_NAVDATA" period=".05"/>
|
||||
</mode>
|
||||
|
||||
<mode name="scaled_sensors">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="IMU_GYRO_SCALED" period=".075"/>
|
||||
<message name="IMU_ACCEL_SCALED" period=".075"/>
|
||||
<message name="IMU_MAG_SCALED" period=".1"/>
|
||||
</mode>
|
||||
|
||||
<mode name="ahrs">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="FILTER_ALIGNER" period="2.2"/>
|
||||
<message name="FILTER" period=".5"/>
|
||||
<message name="GEO_MAG" period="5."/>
|
||||
<message name="AHRS_GYRO_BIAS_INT" period="0.08"/>
|
||||
<message name="AHRS_QUAT_INT" period=".25"/>
|
||||
<message name="AHRS_EULER_INT" period=".1"/>
|
||||
<!-- <message name="AHRS_RMAT_INT" period=".5"/> -->
|
||||
</mode>
|
||||
|
||||
<mode name="rate_loop">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="RATE_LOOP" period=".02"/>
|
||||
</mode>
|
||||
|
||||
<mode name="attitude_setpoint_viz" key_press="v">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="0.9"/>
|
||||
<message name="ROTORCRAFT_RADIO_CONTROL" period="0.1"/>
|
||||
<message name="AHRS_REF_QUAT" period="0.05"/>
|
||||
</mode>
|
||||
|
||||
<mode name="attitude_loop" key_press="a">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="0.9"/>
|
||||
<message name="STAB_ATTITUDE_INT" period=".03"/>
|
||||
<message name="STAB_ATTITUDE_REF_INT" period=".03"/>
|
||||
<message name="STAB_ATTITUDE_INDI" period=".25"/>
|
||||
</mode>
|
||||
|
||||
<mode name="vert_loop" key_press="v">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="0.9"/>
|
||||
<message name="VFF" period=".05"/>
|
||||
<message name="VFF_EXTENDED" period=".05"/>
|
||||
<message name="VERT_LOOP" period=".05"/>
|
||||
<message name="INS_Z" period=".05"/>
|
||||
<message name="INS" period=".11"/>
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
</mode>
|
||||
|
||||
<mode name="h_loop" key_press="h">
|
||||
<message name="ALIVE" period="0.9"/>
|
||||
<message name="HOVER_LOOP" period="0.062"/>
|
||||
<message name="GUIDANCE_H_REF_INT" period="0.062"/>
|
||||
<message name="STAB_ATTITUDE_INT" period="0.4"/>
|
||||
<!--<message name="STAB_ATTITUDE_REF_INT" period="0.4"/>-->
|
||||
<message name="ROTORCRAFT_FP" period="0.8"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
<!-- HFF messages are only sent if USE_HFF -->
|
||||
<message name="HFF" period=".05"/>
|
||||
<message name="HFF_GPS" period=".03"/>
|
||||
<message name="HFF_DBG" period=".2"/>
|
||||
</mode>
|
||||
|
||||
<mode name="aligner">
|
||||
<message name="ALIVE" period="0.9"/>
|
||||
<message name="FILTER_ALIGNER" period="0.02"/>
|
||||
</mode>
|
||||
|
||||
<mode name="tune_hover">
|
||||
<message name="DL_VALUE" period="1.1"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="GUIDANCE_H_INT" period="0.05"/>
|
||||
<message name="ROTORCRAFT_TUNE_HOVER" period=".1"/>
|
||||
<!-- <message name="GPS_INT" period=".20"/> -->
|
||||
<!--<message name="INS2" period=".05"/>
|
||||
<message name="INS3" period=".20"/>-->
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
</mode>
|
||||
|
||||
<mode name="empty"></mode>
|
||||
|
||||
</process>
|
||||
<process name="Logger">
|
||||
<mode name="default">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="IMU_GYRO_SCALED" period=".002"/>
|
||||
<message name="IMU_MAG_SCALED" period=".1"/>
|
||||
<message name="ROTORCRAFT_CMD" period=".002"/>
|
||||
</mode>
|
||||
</process>
|
||||
|
||||
</telemetry>
|
||||
|
||||
@@ -29,7 +29,6 @@
|
||||
<message name="VECTORNAV_INFO" period="0.5"/>
|
||||
<message name="TEMP_ADC" period="3.0"/>
|
||||
<message name="FBW_STATUS" period="2.0"/>
|
||||
<message name="MOTOR" period="0.5"/>
|
||||
</mode>
|
||||
|
||||
<mode name="ppm">
|
||||
@@ -152,12 +151,11 @@
|
||||
<mode name="default">
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="IMU_GYRO_SCALED" period=".002"/>
|
||||
<!--message name="IMU_ACCEL_SCALED" period=".002"/-->
|
||||
<message name="IMU_ACCEL_SCALED" period=".002"/>
|
||||
<message name="IMU_MAG_SCALED" period=".1"/>
|
||||
<message name="ROTORCRAFT_CMD" period=".002"/>
|
||||
</mode>
|
||||
</process>
|
||||
|
||||
</telemetry>
|
||||
|
||||
|
||||
Reference in New Issue
Block a user