mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
[telemetry] cleanup
This commit is contained in:
@@ -0,0 +1,158 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
|
||||
<telemetry>
|
||||
|
||||
<process name="Mavlink" type="mavlink">
|
||||
<mode name="default">
|
||||
<message name="HEARTBEAT" period="1.0"/>
|
||||
<message name="SYS_STATUS" period="1.2"/>
|
||||
</mode>
|
||||
</process>
|
||||
|
||||
<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"/>
|
||||
</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_EULER" 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_FLOAT" period=".03"/>
|
||||
<message name="STAB_ATTITUDE_REF_FLOAT" 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_FLOAT" 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>
|
||||
|
||||
</process>
|
||||
|
||||
</telemetry>
|
||||
|
||||
@@ -131,7 +131,7 @@
|
||||
<message name="COMMANDS" period="0.05"/>
|
||||
<message name="ACTUATORS" period="0.05"/>
|
||||
<message name="PPRZ_MODE" period="1.0"/>
|
||||
<message name="FBW_MODE" period="1.0"/>
|
||||
<message name="FBW_STATUS" period="1.0"/>
|
||||
<message name="NAVIGATION" period="1.0"/>
|
||||
<message name="DATALINK_REPORT" period="1.0"/>
|
||||
</mode>
|
||||
|
||||
@@ -1,33 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
|
||||
<telemetry>
|
||||
<process name="Ap">
|
||||
<mode name="default">
|
||||
<message name="ALIVE" period="5"/>
|
||||
<message name="ATTITUDE" period="0.5"/>
|
||||
<message name="ESTIMATOR" period="0.5"/>
|
||||
<message name="WP_MOVED" period="0.5"/>
|
||||
<message name="CIRCLE" period="1.05"/>
|
||||
<message name="DESIRED" period="1.05"/>
|
||||
<message name="BAT" period="1.1"/>
|
||||
<message name="SEGMENT" period="1.2"/>
|
||||
<message name="CALIBRATION" period="2.1"/>
|
||||
<message name="NAVIGATION_REF" period="9."/>
|
||||
<message name="PPRZ_MODE" period="5."/>
|
||||
<message name="DATALINK_REPORT" period="5.1"/>
|
||||
<message name="DL_VALUE" period="1.5"/>
|
||||
<message name="IR_SENSORS" period="1.2"/>
|
||||
<message name="SURVEY" period="2.1"/>
|
||||
<message name="GPS_SOL" period="2.0"/>
|
||||
</mode>
|
||||
</process>
|
||||
<process name="Fbw">
|
||||
<mode name="default">
|
||||
<message name="COMMANDS" period="0.05"/> <!--High freq for sim -->
|
||||
<message name="PPM" period="0.5"/>
|
||||
<message name="RC" period="0.5"/>
|
||||
<message name="FBW_STATUS" period="1"/>
|
||||
<message name="ACTUATORS" period="5"/> <!-- For trimming -->
|
||||
</mode>
|
||||
</process>
|
||||
</telemetry>
|
||||
@@ -1,23 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
|
||||
<telemetry>
|
||||
|
||||
<process name="Main">
|
||||
<mode name="DefaultMode">
|
||||
<message name="ALIVE" period="1."/>
|
||||
<message name="TEST_PASSTHROUGH_STATUS" period="0.5"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
</mode>
|
||||
|
||||
<mode name="OtherMode">
|
||||
<message name="ALIVE" period="1."/>
|
||||
<message name="TEST_PASSTHROUGH_STATUS" period="0.5"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
<message name="IMU_GYRO" period="0.05"/>
|
||||
<message name="IMU_ACCEL" period="0.05"/>
|
||||
<message name="IMU_MAG" period="0.05"/>
|
||||
<message name="BARO_RAW" period="0.05"/>
|
||||
</mode>
|
||||
</process>
|
||||
|
||||
</telemetry>
|
||||
@@ -66,7 +66,7 @@ void actuators_bebop_init(void)
|
||||
actuators_bebop.led = 0;
|
||||
|
||||
#if PERIODIC_TELEMETRY
|
||||
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_BEBOP_ACTUATORS, send_actuators_bebop);
|
||||
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_BEBOP_ACTUATORS, send_bebop_actuators);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user