<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<fieldtype="float"name="x">X Position in NED frame in meters</field>
<fieldtype="float"name="y">Y Position in NED frame in meters</field>
<fieldtype="float"name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
@ -1984,12 +1986,14 @@
@@ -1984,12 +1986,14 @@
<fieldtype="float"name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="yaw">yaw setpoint in rad</field>
<fieldtype="float"name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<messageid="85"name="POSITION_TARGET_LOCAL_NED">
<description>Set vehicle position, velocity and acceleration setpoint in local frame.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp in milliseconds since system boot</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<fieldtype="float"name="x">X Position in NED frame in meters</field>
<fieldtype="float"name="y">Y Position in NED frame in meters</field>
<fieldtype="float"name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
@ -1999,6 +2003,8 @@
@@ -1999,6 +2003,8 @@
<fieldtype="float"name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="yaw">yaw setpoint in rad</field>
<fieldtype="float"name="yaw_rate">yaw rate setpoint in rad/s</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<fieldtype="int32_t"name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
<fieldtype="int32_t"name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
<fieldtype="float"name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
@ -2016,12 +2022,14 @@
@@ -2016,12 +2022,14 @@
<fieldtype="float"name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="yaw">yaw setpoint in rad</field>
<fieldtype="float"name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<messageid="87"name="POSITION_TARGET_GLOBAL_INT">
<description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<fieldtype="uint16_t"name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<fieldtype="int32_t"name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
<fieldtype="int32_t"name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
<fieldtype="float"name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
@ -2031,6 +2039,8 @@
@@ -2031,6 +2039,8 @@
<fieldtype="float"name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<fieldtype="float"name="yaw">yaw setpoint in rad</field>
<fieldtype="float"name="yaw_rate">yaw rate setpoint in rad/s</field>
<description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
@ -2450,7 +2460,7 @@
@@ -2450,7 +2460,7 @@
<messageid="147"name="BATTERY_STATUS">
<description>Battery information</description>
<fieldtype="uint8_t"name="id">Battery ID</field>
<fieldtype="uint8_t"name="function"enum="MAV_BATTERY_FUNCTION">Function of the battery</field>
<fieldtype="uint8_t"name="battery_function"enum="MAV_BATTERY_FUNCTION">Function of the battery</field>
<fieldtype="uint8_t"name="type"enum="MAV_BATTERY_TYPE">Type (chemistry) of the battery</field>
<fieldtype="int16_t"name="temperature">Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.</field>
<fieldtype="uint16_t[10]"name="voltages">Battery voltage of cells, in millivolts (1 = 1 millivolt)</field>