GCS_MAVLink: added PID_TUNING message

This commit is contained in:
Andrew Tridgell 2015-05-23 08:14:52 +10:00
parent c31da93726
commit cc80fdf593
2 changed files with 19 additions and 0 deletions

View File

@ -58,6 +58,7 @@ enum ap_message {
MSG_GIMBAL_REPORT,
MSG_EKF_STATUS_REPORT,
MSG_LOCAL_POSITION,
MSG_PID_TUNING,
MSG_RETRY_DEFERRED // this must be last
};

View File

@ -258,6 +258,12 @@
<entry name="EKF_PRED_POS_HORIZ_ABS" value="512"> <description>set if EKF's predicted horizontal position (absolute) estimate is good</description></entry>
</enum>
<enum name="PID_TUNING_AXIS">
<entry name="PID_TUNING_ROLL" value="1"></entry>
<entry name="PID_TUNING_PITCH" value="2"></entry>
<entry name="PID_TUNING_YAW" value="3"></entry>
</enum>
</enums>
<messages>
@ -651,6 +657,18 @@
<field name="terrain_alt_variance" type="float">Terrain Altitude variance</field>
</message>
<!-- realtime PID tuning message -->
<message name="PID_TUNING" id="194">
<description>PID tuning information</description>
<field name="axis" type="uint8_t" enum="PID_TUNING_AXIS">axis</field>
<field name="desired" type="float">desired rate (degrees/s)</field>
<field name="achieved" type="float">achieved rate (degrees/s)</field>
<field name="FF" type="float">FF component</field>
<field name="P" type="float">P component</field>
<field name="I" type="float">I component</field>
<field name="D" type="float">D component</field>
</message>
<message name="GIMBAL_REPORT" id="200">
<description>3 axis gimbal mesuraments</description>
<field type="uint8_t" name="target_system">System ID</field>