GCS_MAVLink: home-position message defs from upstream

This commit is contained in:
Randy Mackay 2015-10-02 17:52:56 +09:00
parent 53716f9022
commit b84b069080

View File

@ -1088,6 +1088,16 @@
<param index="1">1 to arm, 0 to disarm</param>
<param index="2">0 to disarm if landed, 21196 to force disarm any time</param>
</entry>
<entry value="410" name="MAV_CMD_GET_HOME_POSITION">
<description>Request the home position from the vehicle.</description>
<param index="1">Reserved</param>
<param index="2">Reserved</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Reserved</param>
<param index="6">Reserved</param>
<param index="7">Reserved</param>
</entry>
<entry value="500" name="MAV_CMD_START_RX_PAIR">
<description>Starts receiver pairing</description>
<param index="1">0:Spektrum</param>
@ -2686,6 +2696,33 @@
<field type="uint32_t" name="clipping_1">second accelerometer clipping count</field>
<field type="uint32_t" name="clipping_2">third accelerometer clipping count</field>
</message>
<message id="242" name="HOME_POSITION">
<description>This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.</description>
<field type="int32_t" name="latitude">Latitude (WGS84), in degrees * 1E7</field>
<field type="int32_t" name="longitude">Longitude (WGS84, in degrees * 1E7</field>
<field type="int32_t" name="altitude">Altitude (AMSL), in meters * 1000 (positive for up)</field>
<field type="float" name="x">Local X position of this position in the local coordinate frame</field>
<field type="float" name="y">Local Y position of this position in the local coordinate frame</field>
<field type="float" name="z">Local Z position of this position in the local coordinate frame</field>
<field type="float[4]" name="q">World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground</field>
<field type="float" name="approach_x">Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
<field type="float" name="approach_y">Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
<field type="float" name="approach_z">Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
</message>
<message id="243" name="SET_HOME_POSITION">
<description>The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="int32_t" name="latitude">Latitude (WGS84), in degrees * 1E7</field>
<field type="int32_t" name="longitude">Longitude (WGS84, in degrees * 1E7</field>
<field type="int32_t" name="altitude">Altitude (AMSL), in meters * 1000 (positive for up)</field>
<field type="float" name="x">Local X position of this position in the local coordinate frame</field>
<field type="float" name="y">Local Y position of this position in the local coordinate frame</field>
<field type="float" name="z">Local Z position of this position in the local coordinate frame</field>
<field type="float[4]" name="q">World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground</field>
<field type="float" name="approach_x">Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
<field type="float" name="approach_y">Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
<field type="float" name="approach_z">Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.</field>
</message>
<message id="248" name="V2_EXTENSION">
<description>Message implementing parts of the V2 payload specs in V1 frames for transitional support.</description>
<field type="uint8_t" name="target_network">Network ID (0 for broadcast)</field>