1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 03:19:58 +03:00

[MAVLINK] Update mavlink library to latest v1.0 release

This commit is contained in:
Felipe Machado 2020-08-28 17:25:20 +01:00
parent 81f2e0c0c0
commit d8ac874087
149 changed files with 10247 additions and 5961 deletions

File diff suppressed because one or more lines are too long

View file

@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_IDX 1
#define MAVLINK_PRIMARY_XML_IDX 0
#ifndef MAVLINK_STX
#define MAVLINK_STX 254

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140
MAVPACKED(
typedef struct __mavlink_actuator_control_target_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/
uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/
}) mavlink_actuator_control_target_t;
} mavlink_actuator_control_target_t;
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41
@ -26,8 +26,8 @@ typedef struct __mavlink_actuator_control_target_t {
"ACTUATOR_CONTROL_TARGET", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
{ "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
} \
}
#else
@ -35,8 +35,8 @@ typedef struct __mavlink_actuator_control_target_t {
"ACTUATOR_CONTROL_TARGET", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
{ "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
} \
}
#endif
@ -47,7 +47,7 @@ typedef struct __mavlink_actuator_control_target_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
* @return length of the message in bytes (excluding serial stream start sign)
@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_i
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
* @return length of the message in bytes (excluding serial stream start sign)
@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t s
* @brief Send a actuator_control_target message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
*/
@ -208,7 +208,7 @@ static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_
/**
* @brief Get field time_usec from actuator_control_target message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg)
{

View file

@ -3,22 +3,22 @@
#define MAVLINK_MSG_ID_ADSB_VEHICLE 246
MAVPACKED(
typedef struct __mavlink_adsb_vehicle_t {
uint32_t ICAO_address; /*< ICAO address*/
int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
int32_t altitude; /*< Altitude(ASL) in millimeters*/
uint16_t heading; /*< Course over ground in centidegrees*/
uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/
int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/
uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
int32_t altitude; /*< [mm] Altitude(ASL)*/
uint16_t heading; /*< [cdeg] Course over ground*/
uint16_t hor_velocity; /*< [cm/s] The horizontal velocity*/
int16_t ver_velocity; /*< [cm/s] The vertical velocity. Positive is up*/
uint16_t flags; /*< Bitmap to indicate various statuses including valid data fields*/
uint16_t squawk; /*< Squawk code*/
uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/
uint8_t altitude_type; /*< ADSB altitude type.*/
char callsign[9]; /*< The callsign, 8+null*/
uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/
uint8_t tslc; /*< Time since last communication in seconds*/
}) mavlink_adsb_vehicle_t;
uint8_t emitter_type; /*< ADSB emitter type.*/
uint8_t tslc; /*< [s] Time since last communication in seconds*/
} mavlink_adsb_vehicle_t;
#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38
#define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38
@ -38,16 +38,16 @@ typedef struct __mavlink_adsb_vehicle_t {
{ { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
{ "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
{ "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
{ "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
} \
}
#else
@ -57,16 +57,16 @@ typedef struct __mavlink_adsb_vehicle_t {
{ { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
{ "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
{ "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
{ "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
} \
}
#endif
@ -78,17 +78,17 @@ typedef struct __mavlink_adsb_vehicle_t {
* @param msg The MAVLink message to compress the data into
*
* @param ICAO_address ICAO address
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param altitude_type Type from ADSB_ALTITUDE_TYPE enum
* @param altitude Altitude(ASL) in millimeters
* @param heading Course over ground in centidegrees
* @param hor_velocity The horizontal velocity in centimeters/second
* @param ver_velocity The vertical velocity in centimeters/second, positive is up
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type Type from ADSB_EMITTER_TYPE enum
* @param tslc Time since last communication in seconds
* @param flags Flags to indicate various statuses including valid data fields
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -140,17 +140,17 @@ static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param ICAO_address ICAO address
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param altitude_type Type from ADSB_ALTITUDE_TYPE enum
* @param altitude Altitude(ASL) in millimeters
* @param heading Course over ground in centidegrees
* @param hor_velocity The horizontal velocity in centimeters/second
* @param ver_velocity The vertical velocity in centimeters/second, positive is up
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type Type from ADSB_EMITTER_TYPE enum
* @param tslc Time since last communication in seconds
* @param flags Flags to indicate various statuses including valid data fields
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -228,17 +228,17 @@ static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, u
* @param chan MAVLink channel to send the message
*
* @param ICAO_address ICAO address
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param altitude_type Type from ADSB_ALTITUDE_TYPE enum
* @param altitude Altitude(ASL) in millimeters
* @param heading Course over ground in centidegrees
* @param hor_velocity The horizontal velocity in centimeters/second
* @param ver_velocity The vertical velocity in centimeters/second, positive is up
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type Type from ADSB_EMITTER_TYPE enum
* @param tslc Time since last communication in seconds
* @param flags Flags to indicate various statuses including valid data fields
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -358,7 +358,7 @@ static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_m
/**
* @brief Get field lat from adsb_vehicle message
*
* @return Latitude, expressed as degrees * 1E7
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg)
{
@ -368,7 +368,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t*
/**
* @brief Get field lon from adsb_vehicle message
*
* @return Longitude, expressed as degrees * 1E7
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg)
{
@ -378,7 +378,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t*
/**
* @brief Get field altitude_type from adsb_vehicle message
*
* @return Type from ADSB_ALTITUDE_TYPE enum
* @return ADSB altitude type.
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg)
{
@ -388,7 +388,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_m
/**
* @brief Get field altitude from adsb_vehicle message
*
* @return Altitude(ASL) in millimeters
* @return [mm] Altitude(ASL)
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg)
{
@ -398,7 +398,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_messag
/**
* @brief Get field heading from adsb_vehicle message
*
* @return Course over ground in centidegrees
* @return [cdeg] Course over ground
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg)
{
@ -408,7 +408,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_messag
/**
* @brief Get field hor_velocity from adsb_vehicle message
*
* @return The horizontal velocity in centimeters/second
* @return [cm/s] The horizontal velocity
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg)
{
@ -418,7 +418,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_m
/**
* @brief Get field ver_velocity from adsb_vehicle message
*
* @return The vertical velocity in centimeters/second, positive is up
* @return [cm/s] The vertical velocity. Positive is up
*/
static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg)
{
@ -438,7 +438,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_messa
/**
* @brief Get field emitter_type from adsb_vehicle message
*
* @return Type from ADSB_EMITTER_TYPE enum
* @return ADSB emitter type.
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg)
{
@ -448,7 +448,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_me
/**
* @brief Get field tslc from adsb_vehicle message
*
* @return Time since last communication in seconds
* @return [s] Time since last communication in seconds
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg)
{
@ -458,7 +458,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t*
/**
* @brief Get field flags from adsb_vehicle message
*
* @return Flags to indicate various statuses including valid data fields
* @return Bitmap to indicate various statuses including valid data fields
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_ALTITUDE 141
MAVPACKED(
typedef struct __mavlink_altitude_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/
float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/
float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/
float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/
float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/
float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/
}) mavlink_altitude_t;
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float altitude_monotonic; /*< [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/
float altitude_amsl; /*< [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.*/
float altitude_local; /*< [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/
float altitude_relative; /*< [m] This is the altitude above the home position. It resets on each change of the current home position.*/
float altitude_terrain; /*< [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/
float bottom_clearance; /*< [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/
} mavlink_altitude_t;
#define MAVLINK_MSG_ID_ALTITUDE_LEN 32
#define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32
@ -59,13 +59,13 @@ typedef struct __mavlink_altitude_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
* @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t comp
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
* @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8
* @brief Send a altitude message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
* @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavl
/**
* @brief Get field time_usec from altitude message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_
/**
* @brief Get field altitude_monotonic from altitude message
*
* @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @return [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
*/
static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_me
/**
* @brief Get field altitude_amsl from altitude message
*
* @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
* @return [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
*/
static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message
/**
* @brief Get field altitude_local from altitude message
*
* @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @return [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
*/
static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_messag
/**
* @brief Get field altitude_relative from altitude message
*
* @return This is the altitude above the home position. It resets on each change of the current home position.
* @return [m] This is the altitude above the home position. It resets on each change of the current home position.
*/
static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_mes
/**
* @brief Get field altitude_terrain from altitude message
*
* @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @return [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
*/
static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_mess
/**
* @brief Get field bottom_clearance from altitude message
*
* @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @return [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
*/
static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg)
{

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
MAVPACKED(
typedef struct __mavlink_att_pos_mocap_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
float x; /*< X position in meters (NED)*/
float y; /*< Y position in meters (NED)*/
float z; /*< Z position in meters (NED)*/
}) mavlink_att_pos_mocap_t;
float x; /*< [m] X position (NED)*/
float y; /*< [m] Y position (NED)*/
float z; /*< [m] Z position (NED)*/
} mavlink_att_pos_mocap_t;
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36
@ -53,11 +53,11 @@ typedef struct __mavlink_att_pos_mocap_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id,
* @brief Send a att_pos_mocap message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -236,7 +236,7 @@ static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field time_usec from att_pos_mocap message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg)
{
@ -256,7 +256,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t*
/**
* @brief Get field x from att_pos_mocap message
*
* @return X position in meters (NED)
* @return [m] X position (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg)
{
@ -266,7 +266,7 @@ static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg
/**
* @brief Get field y from att_pos_mocap message
*
* @return Y position in meters (NED)
* @return [m] Y position (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg)
{
@ -276,7 +276,7 @@ static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg
/**
* @brief Get field z from att_pos_mocap message
*
* @return Z position in meters (NED)
* @return [m] Z position (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_ATTITUDE 30
MAVPACKED(
typedef struct __mavlink_attitude_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
float roll; /*< Roll angle (rad, -pi..+pi)*/
float pitch; /*< Pitch angle (rad, -pi..+pi)*/
float yaw; /*< Yaw angle (rad, -pi..+pi)*/
float rollspeed; /*< Roll angular speed (rad/s)*/
float pitchspeed; /*< Pitch angular speed (rad/s)*/
float yawspeed; /*< Yaw angular speed (rad/s)*/
}) mavlink_attitude_t;
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float roll; /*< [rad] Roll angle (-pi..+pi)*/
float pitch; /*< [rad] Pitch angle (-pi..+pi)*/
float yaw; /*< [rad] Yaw angle (-pi..+pi)*/
float rollspeed; /*< [rad/s] Roll angular speed*/
float pitchspeed; /*< [rad/s] Pitch angular speed*/
float yawspeed; /*< [rad/s] Yaw angular speed*/
} mavlink_attitude_t;
#define MAVLINK_MSG_ID_ATTITUDE_LEN 28
#define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28
@ -59,13 +59,13 @@ typedef struct __mavlink_attitude_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad] Roll angle (-pi..+pi)
* @param pitch [rad] Pitch angle (-pi..+pi)
* @param yaw [rad] Yaw angle (-pi..+pi)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad] Roll angle (-pi..+pi)
* @param pitch [rad] Pitch angle (-pi..+pi)
* @param yaw [rad] Yaw angle (-pi..+pi)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad] Roll angle (-pi..+pi)
* @param pitch [rad] Pitch angle (-pi..+pi)
* @param yaw [rad] Yaw angle (-pi..+pi)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavl
/**
* @brief Get field time_boot_ms from attitude message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_messa
/**
* @brief Get field roll from attitude message
*
* @return Roll angle (rad, -pi..+pi)
* @return [rad] Roll angle (-pi..+pi)
*/
static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
/**
* @brief Get field pitch from attitude message
*
* @return Pitch angle (rad, -pi..+pi)
* @return [rad] Pitch angle (-pi..+pi)
*/
static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
/**
* @brief Get field yaw from attitude message
*
* @return Yaw angle (rad, -pi..+pi)
* @return [rad] Yaw angle (-pi..+pi)
*/
static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
/**
* @brief Get field rollspeed from attitude message
*
* @return Roll angular speed (rad/s)
* @return [rad/s] Roll angular speed
*/
static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t*
/**
* @brief Get field pitchspeed from attitude message
*
* @return Pitch angular speed (rad/s)
* @return [rad/s] Pitch angular speed
*/
static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t*
/**
* @brief Get field yawspeed from attitude message
*
* @return Yaw angular speed (rad/s)
* @return [rad/s] Yaw angular speed
*/
static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
{

View file

@ -3,17 +3,17 @@
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
MAVPACKED(
typedef struct __mavlink_attitude_quaternion_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float q1; /*< Quaternion component 1, w (1 in null-rotation)*/
float q2; /*< Quaternion component 2, x (0 in null-rotation)*/
float q3; /*< Quaternion component 3, y (0 in null-rotation)*/
float q4; /*< Quaternion component 4, z (0 in null-rotation)*/
float rollspeed; /*< Roll angular speed (rad/s)*/
float pitchspeed; /*< Pitch angular speed (rad/s)*/
float yawspeed; /*< Yaw angular speed (rad/s)*/
}) mavlink_attitude_quaternion_t;
float rollspeed; /*< [rad/s] Roll angular speed*/
float pitchspeed; /*< [rad/s] Pitch angular speed*/
float yawspeed; /*< [rad/s] Yaw angular speed*/
} mavlink_attitude_quaternion_t;
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
@ -62,14 +62,14 @@ typedef struct __mavlink_attitude_quaternion_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param q1 Quaternion component 1, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param q1 Quaternion component 1, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t syste
* @brief Send a attitude_quaternion message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param q1 Quaternion component 1, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -286,7 +286,7 @@ static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *m
/**
* @brief Get field time_boot_ms from attitude_quaternion message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message
/**
* @brief Get field rollspeed from attitude_quaternion message
*
* @return Roll angular speed (rad/s)
* @return [rad/s] Roll angular speed
*/
static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_
/**
* @brief Get field pitchspeed from attitude_quaternion message
*
* @return Pitch angular speed (rad/s)
* @return [rad/s] Pitch angular speed
*/
static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink
/**
* @brief Get field yawspeed from attitude_quaternion message
*
* @return Yaw angular speed (rad/s)
* @return [rad/s] Yaw angular speed
*/
static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
{

View file

@ -3,15 +3,15 @@
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
MAVPACKED(
typedef struct __mavlink_attitude_quaternion_cov_t {
uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/
float rollspeed; /*< Roll angular speed (rad/s)*/
float pitchspeed; /*< Pitch angular speed (rad/s)*/
float yawspeed; /*< Yaw angular speed (rad/s)*/
float covariance[9]; /*< Attitude covariance*/
}) mavlink_attitude_quaternion_cov_t;
float rollspeed; /*< [rad/s] Roll angular speed*/
float pitchspeed; /*< [rad/s] Pitch angular speed*/
float yawspeed; /*< [rad/s] Yaw angular speed*/
float covariance[9]; /*< Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
} mavlink_attitude_quaternion_cov_t;
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72
@ -57,12 +57,12 @@ typedef struct __mavlink_attitude_quaternion_cov_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -98,12 +98,12 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_i
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -165,12 +165,12 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t s
* @brief Send a attitude_quaternion_cov message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -251,7 +251,7 @@ static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_
/**
* @brief Get field time_usec from attitude_quaternion_cov message
*
* @return Timestamp (microseconds since system boot or since UNIX epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg)
{
@ -271,7 +271,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_m
/**
* @brief Get field rollspeed from attitude_quaternion_cov message
*
* @return Roll angular speed (rad/s)
* @return [rad/s] Roll angular speed
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg)
{
@ -281,7 +281,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavl
/**
* @brief Get field pitchspeed from attitude_quaternion_cov message
*
* @return Pitch angular speed (rad/s)
* @return [rad/s] Pitch angular speed
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg)
{
@ -291,7 +291,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mav
/**
* @brief Get field yawspeed from attitude_quaternion_cov message
*
* @return Yaw angular speed (rad/s)
* @return [rad/s] Yaw angular speed
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg)
{
@ -301,7 +301,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavli
/**
* @brief Get field covariance from attitude_quaternion_cov message
*
* @return Attitude covariance
* @return Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
MAVPACKED(
typedef struct __mavlink_attitude_target_t {
uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
float body_roll_rate; /*< Body roll rate in radians per second*/
float body_pitch_rate; /*< Body roll rate in radians per second*/
float body_yaw_rate; /*< Body roll rate in radians per second*/
float body_roll_rate; /*< [rad/s] Body roll rate*/
float body_pitch_rate; /*< [rad/s] Body pitch rate*/
float body_yaw_rate; /*< [rad/s] Body yaw rate*/
float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/
uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/
}) mavlink_attitude_target_t;
} mavlink_attitude_target_t;
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37
@ -30,12 +30,12 @@ typedef struct __mavlink_attitude_target_t {
"ATTITUDE_TARGET", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
{ "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
{ "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
{ "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
} \
}
#else
@ -43,12 +43,12 @@ typedef struct __mavlink_attitude_target_t {
"ATTITUDE_TARGET", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
{ "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
{ "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
{ "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
} \
}
#endif
@ -59,12 +59,12 @@ typedef struct __mavlink_attitude_target_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -103,12 +103,12 @@ static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -173,12 +173,12 @@ static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id
* @brief Send a attitude_target message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -264,7 +264,7 @@ static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbu
/**
* @brief Get field time_boot_ms from attitude_target message
*
* @return Timestamp in milliseconds since system boot
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -294,7 +294,7 @@ static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t
/**
* @brief Get field body_roll_rate from attitude_target message
*
* @return Body roll rate in radians per second
* @return [rad/s] Body roll rate
*/
static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
{
@ -304,7 +304,7 @@ static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink
/**
* @brief Get field body_pitch_rate from attitude_target message
*
* @return Body roll rate in radians per second
* @return [rad/s] Body pitch rate
*/
static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
{
@ -314,7 +314,7 @@ static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlin
/**
* @brief Get field body_yaw_rate from attitude_target message
*
* @return Body roll rate in radians per second
* @return [rad/s] Body yaw rate
*/
static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
{

View file

@ -3,10 +3,10 @@
#define MAVLINK_MSG_ID_AUTH_KEY 7
MAVPACKED(
typedef struct __mavlink_auth_key_t {
char key[32]; /*< key*/
}) mavlink_auth_key_t;
} mavlink_auth_key_t;
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32

View file

@ -3,10 +3,10 @@
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
MAVPACKED(
typedef struct __mavlink_autopilot_version_t {
uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/
uint64_t uid; /*< UID if provided by hardware*/
uint64_t capabilities; /*< Bitmap of capabilities*/
uint64_t uid; /*< UID if provided by hardware (see uid2)*/
uint32_t flight_sw_version; /*< Firmware version number*/
uint32_t middleware_sw_version; /*< Middleware version number*/
uint32_t os_sw_version; /*< Operating system version number*/
@ -16,7 +16,7 @@ typedef struct __mavlink_autopilot_version_t {
uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
}) mavlink_autopilot_version_t;
} mavlink_autopilot_version_t;
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60
@ -36,16 +36,16 @@ typedef struct __mavlink_autopilot_version_t {
"AUTOPILOT_VERSION", \
11, \
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
{ "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
{ "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
{ "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
{ "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
{ "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
{ "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
{ "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
{ "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
{ "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
{ "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
{ "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
} \
}
#else
@ -53,16 +53,16 @@ typedef struct __mavlink_autopilot_version_t {
"AUTOPILOT_VERSION", \
11, \
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
{ "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
{ "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
{ "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
{ "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
{ "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
{ "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
{ "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
{ "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
{ "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
{ "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
{ "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
} \
}
#endif
@ -73,7 +73,7 @@ typedef struct __mavlink_autopilot_version_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param capabilities Bitmap of capabilities
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
@ -83,7 +83,7 @@ typedef struct __mavlink_autopilot_version_t {
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
* @param uid UID if provided by hardware (see uid2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param capabilities Bitmap of capabilities
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
@ -139,7 +139,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
* @param uid UID if provided by hardware (see uid2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -211,7 +211,7 @@ static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_
* @brief Send a autopilot_version message
* @param chan MAVLink channel to send the message
*
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param capabilities Bitmap of capabilities
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
@ -221,7 +221,7 @@ static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
* @param uid UID if provided by hardware (see uid2)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -322,7 +322,7 @@ static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msg
/**
* @brief Get field capabilities from autopilot_version message
*
* @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @return Bitmap of capabilities
*/
static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
{
@ -422,7 +422,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlin
/**
* @brief Get field uid from autopilot_version message
*
* @return UID if provided by hardware
* @return UID if provided by hardware (see uid2)
*/
static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
{

View file

@ -3,18 +3,18 @@
#define MAVLINK_MSG_ID_BATTERY_STATUS 147
MAVPACKED(
typedef struct __mavlink_battery_status_t {
int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/
int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/
int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/
uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/
int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/
int32_t current_consumed; /*< [mAh] Consumed charge, -1: autopilot does not provide consumption estimate*/
int32_t energy_consumed; /*< [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate*/
int16_t temperature; /*< [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.*/
uint16_t voltages[10]; /*< [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).*/
int16_t current_battery; /*< [cA] Battery current, -1: autopilot does not measure the current*/
uint8_t id; /*< Battery ID*/
uint8_t battery_function; /*< Function of the battery*/
uint8_t type; /*< Type (chemistry) of the battery*/
int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/
}) mavlink_battery_status_t;
int8_t battery_remaining; /*< [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.*/
} mavlink_battery_status_t;
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
#define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36
@ -31,14 +31,14 @@ typedef struct __mavlink_battery_status_t {
147, \
"BATTERY_STATUS", \
9, \
{ { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
{ "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
} \
}
@ -46,14 +46,14 @@ typedef struct __mavlink_battery_status_t {
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
"BATTERY_STATUS", \
9, \
{ { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
{ "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
} \
}
@ -68,12 +68,12 @@ typedef struct __mavlink_battery_status_t {
* @param id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.
* @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -118,12 +118,12 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
* @param id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.
* @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -194,12 +194,12 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id,
* @param id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.
* @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -322,7 +322,7 @@ static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_
/**
* @brief Get field temperature from battery_status message
*
* @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @return [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.
*/
static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_m
/**
* @brief Get field voltages from battery_status message
*
* @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
* @return [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
*/
static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages)
{
@ -342,7 +342,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_mes
/**
* @brief Get field current_battery from battery_status message
*
* @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @return [cA] Battery current, -1: autopilot does not measure the current
*/
static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg)
{
@ -352,7 +352,7 @@ static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavli
/**
* @brief Get field current_consumed from battery_status message
*
* @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @return [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
*/
static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg)
{
@ -362,7 +362,7 @@ static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavl
/**
* @brief Get field energy_consumed from battery_status message
*
* @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @return [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
*/
static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg)
{
@ -372,7 +372,7 @@ static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavli
/**
* @brief Get field battery_remaining from battery_status message
*
* @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @return [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
*/
static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112
MAVPACKED(
typedef struct __mavlink_camera_trigger_t {
uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/
uint64_t time_usec; /*< [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t seq; /*< Image frame sequence*/
}) mavlink_camera_trigger_t;
} mavlink_camera_trigger_t;
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN 12
@ -44,7 +44,7 @@ typedef struct __mavlink_camera_trigger_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp for the image frame in microseconds
* @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq Image frame sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -75,7 +75,7 @@ static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp for the image frame in microseconds
* @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq Image frame sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -132,7 +132,7 @@ static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id,
* @brief Send a camera_trigger message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp for the image frame in microseconds
* @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq Image frame sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -202,7 +202,7 @@ static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf
/**
* @brief Get field time_usec from camera_trigger message
*
* @return Timestamp for the image frame in microseconds
* @return [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
MAVPACKED(
typedef struct __mavlink_change_operator_control_t {
uint8_t target_system; /*< System the GCS requests control for*/
uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/
uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/
uint8_t version; /*< [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/
char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/
}) mavlink_change_operator_control_t;
} mavlink_change_operator_control_t;
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN 28
@ -52,7 +52,7 @@ typedef struct __mavlink_change_operator_control_t {
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i
* @param msg The MAVLink message to compress the data into
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -148,7 +148,7 @@ static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t s
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(co
/**
* @brief Get field version from change_operator_control message
*
* @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @return [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
*/
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
MAVPACKED(
typedef struct __mavlink_change_operator_control_ack_t {
uint8_t gcs_system_id; /*< ID of the GCS this message */
uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/
uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/
}) mavlink_change_operator_control_ack_t;
} mavlink_change_operator_control_ack_t;
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN 3

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_COLLISION 247
MAVPACKED(
typedef struct __mavlink_collision_t {
uint32_t id; /*< Unique identifier, domain based on src field*/
float time_to_minimum_delta; /*< Estimated time until collision occurs (seconds)*/
float altitude_minimum_delta; /*< Closest vertical distance in meters between vehicle and object*/
float horizontal_minimum_delta; /*< Closest horizontal distance in meteres between vehicle and object*/
float time_to_minimum_delta; /*< [s] Estimated time until collision occurs*/
float altitude_minimum_delta; /*< [m] Closest vertical distance between vehicle and object*/
float horizontal_minimum_delta; /*< [m] Closest horizontal distance between vehicle and object*/
uint8_t src; /*< Collision data source*/
uint8_t action; /*< Action that is being taken to avoid this collision*/
uint8_t threat_level; /*< How concerned the aircraft is about this collision*/
}) mavlink_collision_t;
} mavlink_collision_t;
#define MAVLINK_MSG_ID_COLLISION_LEN 19
#define MAVLINK_MSG_ID_COLLISION_MIN_LEN 19
@ -29,26 +29,26 @@ typedef struct __mavlink_collision_t {
247, \
"COLLISION", \
7, \
{ { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \
{ { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \
{ "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \
{ "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \
{ "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \
{ "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \
{ "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \
{ "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \
{ "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \
{ "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \
{ "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COLLISION { \
"COLLISION", \
7, \
{ { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \
{ { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \
{ "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \
{ "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \
{ "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \
{ "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \
{ "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \
{ "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \
{ "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \
{ "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \
{ "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \
} \
}
#endif
@ -63,9 +63,9 @@ typedef struct __mavlink_collision_t {
* @param id Unique identifier, domain based on src field
* @param action Action that is being taken to avoid this collision
* @param threat_level How concerned the aircraft is about this collision
* @param time_to_minimum_delta Estimated time until collision occurs (seconds)
* @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object
* @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object
* @param time_to_minimum_delta [s] Estimated time until collision occurs
* @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object
* @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -109,9 +109,9 @@ static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t com
* @param id Unique identifier, domain based on src field
* @param action Action that is being taken to avoid this collision
* @param threat_level How concerned the aircraft is about this collision
* @param time_to_minimum_delta Estimated time until collision occurs (seconds)
* @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object
* @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object
* @param time_to_minimum_delta [s] Estimated time until collision occurs
* @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object
* @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_collision_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -181,9 +181,9 @@ static inline uint16_t mavlink_msg_collision_encode_chan(uint8_t system_id, uint
* @param id Unique identifier, domain based on src field
* @param action Action that is being taken to avoid this collision
* @param threat_level How concerned the aircraft is about this collision
* @param time_to_minimum_delta Estimated time until collision occurs (seconds)
* @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object
* @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object
* @param time_to_minimum_delta [s] Estimated time until collision occurs
* @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object
* @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_messa
/**
* @brief Get field time_to_minimum_delta from collision message
*
* @return Estimated time until collision occurs (seconds)
* @return [s] Estimated time until collision occurs
*/
static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlin
/**
* @brief Get field altitude_minimum_delta from collision message
*
* @return Closest vertical distance in meters between vehicle and object
* @return [m] Closest vertical distance between vehicle and object
*/
static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavli
/**
* @brief Get field horizontal_minimum_delta from collision message
*
* @return Closest horizontal distance in meteres between vehicle and object
* @return [m] Closest horizontal distance between vehicle and object
*/
static inline float mavlink_msg_collision_get_horizontal_minimum_delta(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_COMMAND_ACK 77
MAVPACKED(
typedef struct __mavlink_command_ack_t {
uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/
uint8_t result; /*< See MAV_RESULT enum*/
}) mavlink_command_ack_t;
uint16_t command; /*< Command ID (of acknowledged command).*/
uint8_t result; /*< Result of command.*/
} mavlink_command_ack_t;
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3
@ -44,8 +44,8 @@ typedef struct __mavlink_command_ack_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, ui
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
*
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
* @param command Command ID (of acknowledged command).
* @param result Result of command.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -202,7 +202,7 @@ static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, m
/**
* @brief Get field command from command_ack message
*
* @return Command ID, as defined by MAV_CMD enum.
* @return Command ID (of acknowledged command).
*/
static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{
@ -212,7 +212,7 @@ static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message
/**
* @brief Get field result from command_ack message
*
* @return See MAV_RESULT enum
* @return Result of command.
*/
static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,263 @@
#pragma once
// MESSAGE COMMAND_CANCEL PACKING
#define MAVLINK_MSG_ID_COMMAND_CANCEL 80
typedef struct __mavlink_command_cancel_t {
uint16_t command; /*< Command ID (of command to cancel).*/
uint8_t target_system; /*< System executing long running command. Should not be broadcast (0).*/
uint8_t target_component; /*< Component executing long running command.*/
} mavlink_command_cancel_t;
#define MAVLINK_MSG_ID_COMMAND_CANCEL_LEN 4
#define MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN 4
#define MAVLINK_MSG_ID_80_LEN 4
#define MAVLINK_MSG_ID_80_MIN_LEN 4
#define MAVLINK_MSG_ID_COMMAND_CANCEL_CRC 14
#define MAVLINK_MSG_ID_80_CRC 14
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \
80, \
"COMMAND_CANCEL", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \
"COMMAND_CANCEL", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \
} \
}
#endif
/**
* @brief Pack a command_cancel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System executing long running command. Should not be broadcast (0).
* @param target_component Component executing long running command.
* @param command Command ID (of command to cancel).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_cancel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t command)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN);
#else
mavlink_command_cancel_t packet;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
}
/**
* @brief Pack a command_cancel message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System executing long running command. Should not be broadcast (0).
* @param target_component Component executing long running command.
* @param command Command ID (of command to cancel).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_cancel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint16_t command)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN);
#else
mavlink_command_cancel_t packet;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
}
/**
* @brief Encode a command_cancel struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param command_cancel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_cancel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel)
{
return mavlink_msg_command_cancel_pack(system_id, component_id, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command);
}
/**
* @brief Encode a command_cancel struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param command_cancel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_cancel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel)
{
return mavlink_msg_command_cancel_pack_chan(system_id, component_id, chan, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command);
}
/**
* @brief Send a command_cancel message
* @param chan MAVLink channel to send the message
*
* @param target_system System executing long running command. Should not be broadcast (0).
* @param target_component Component executing long running command.
* @param command Command ID (of command to cancel).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_cancel_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
#else
mavlink_command_cancel_t packet;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
#endif
}
/**
* @brief Send a command_cancel message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_command_cancel_send_struct(mavlink_channel_t chan, const mavlink_command_cancel_t* command_cancel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_command_cancel_send(chan, command_cancel->target_system, command_cancel->target_component, command_cancel->command);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)command_cancel, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
#endif
}
#if MAVLINK_MSG_ID_COMMAND_CANCEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_command_cancel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
#else
mavlink_command_cancel_t *packet = (mavlink_command_cancel_t *)msgbuf;
packet->command = command;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC);
#endif
}
#endif
#endif
// MESSAGE COMMAND_CANCEL UNPACKING
/**
* @brief Get field target_system from command_cancel message
*
* @return System executing long running command. Should not be broadcast (0).
*/
static inline uint8_t mavlink_msg_command_cancel_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from command_cancel message
*
* @return Component executing long running command.
*/
static inline uint8_t mavlink_msg_command_cancel_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field command from command_cancel message
*
* @return Command ID (of command to cancel).
*/
static inline uint16_t mavlink_msg_command_cancel_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Decode a command_cancel message into a struct
*
* @param msg The message to decode
* @param command_cancel C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_cancel_decode(const mavlink_message_t* msg, mavlink_command_cancel_t* command_cancel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
command_cancel->command = mavlink_msg_command_cancel_get_command(msg);
command_cancel->target_system = mavlink_msg_command_cancel_get_target_system(msg);
command_cancel->target_component = mavlink_msg_command_cancel_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_CANCEL_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_CANCEL_LEN;
memset(command_cancel, 0, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN);
memcpy(command_cancel, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_COMMAND_INT 75
MAVPACKED(
typedef struct __mavlink_command_int_t {
float param1; /*< PARAM1, see MAV_CMD enum*/
float param2; /*< PARAM2, see MAV_CMD enum*/
@ -11,14 +11,14 @@ typedef struct __mavlink_command_int_t {
float param4; /*< PARAM4, see MAV_CMD enum*/
int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/
int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/
float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/
uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/
float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).*/
uint16_t command; /*< The scheduled action for the mission item.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/
uint8_t frame; /*< The coordinate system of the COMMAND.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< autocontinue to next wp*/
}) mavlink_command_int_t;
} mavlink_command_int_t;
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
#define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35
@ -35,38 +35,38 @@ typedef struct __mavlink_command_int_t {
75, \
"COMMAND_INT", \
13, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \
"COMMAND_INT", \
13, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
} \
}
#endif
@ -79,8 +79,8 @@ typedef struct __mavlink_command_int_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
@ -89,7 +89,7 @@ typedef struct __mavlink_command_int_t {
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -143,8 +143,8 @@ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t c
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -233,8 +233,8 @@ static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, ui
*
* @param target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
@ -243,7 +243,7 @@ static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, ui
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink
/**
* @brief Get field frame from command_int message
*
* @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @return The coordinate system of the COMMAND.
*/
static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t*
/**
* @brief Get field command from command_int message
*
* @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @return The scheduled action for the mission item.
*/
static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg)
{
@ -476,7 +476,7 @@ static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg
/**
* @brief Get field z from command_int message
*
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
*/
static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg)
{

View file

@ -3,20 +3,20 @@
#define MAVLINK_MSG_ID_COMMAND_LONG 76
MAVPACKED(
typedef struct __mavlink_command_long_t {
float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/
float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/
float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/
float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/
float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/
float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/
float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/
uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/
float param1; /*< Parameter 1 (for the specific command).*/
float param2; /*< Parameter 2 (for the specific command).*/
float param3; /*< Parameter 3 (for the specific command).*/
float param4; /*< Parameter 4 (for the specific command).*/
float param5; /*< Parameter 5 (for the specific command).*/
float param6; /*< Parameter 6 (for the specific command).*/
float param7; /*< Parameter 7 (for the specific command).*/
uint16_t command; /*< Command ID (of command to send).*/
uint8_t target_system; /*< System which should execute the command*/
uint8_t target_component; /*< Component which should execute the command, 0 for all components*/
uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/
}) mavlink_command_long_t;
} mavlink_command_long_t;
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
#define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33
@ -33,34 +33,34 @@ typedef struct __mavlink_command_long_t {
76, \
"COMMAND_LONG", \
11, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
"COMMAND_LONG", \
11, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
} \
}
#endif
@ -73,15 +73,15 @@ typedef struct __mavlink_command_long_t {
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param command Command ID (of command to send).
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
* @param param1 Parameter 1 (for the specific command).
* @param param2 Parameter 2 (for the specific command).
* @param param3 Parameter 3 (for the specific command).
* @param param4 Parameter 4 (for the specific command).
* @param param5 Parameter 5 (for the specific command).
* @param param6 Parameter 6 (for the specific command).
* @param param7 Parameter 7 (for the specific command).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -131,15 +131,15 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t
* @param msg The MAVLink message to compress the data into
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param command Command ID (of command to send).
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
* @param param1 Parameter 1 (for the specific command).
* @param param2 Parameter 2 (for the specific command).
* @param param3 Parameter 3 (for the specific command).
* @param param4 Parameter 4 (for the specific command).
* @param param5 Parameter 5 (for the specific command).
* @param param6 Parameter 6 (for the specific command).
* @param param7 Parameter 7 (for the specific command).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -215,15 +215,15 @@ static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, u
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param command Command ID (of command to send).
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
* @param param1 Parameter 1 (for the specific command).
* @param param2 Parameter 2 (for the specific command).
* @param param3 Parameter 3 (for the specific command).
* @param param4 Parameter 4 (for the specific command).
* @param param5 Parameter 5 (for the specific command).
* @param param6 Parameter 6 (for the specific command).
* @param param7 Parameter 7 (for the specific command).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -348,7 +348,7 @@ static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlin
/**
* @brief Get field command from command_long message
*
* @return Command ID, as defined by MAV_CMD enum.
* @return Command ID (of command to send).
*/
static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg)
{
@ -368,7 +368,7 @@ static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_me
/**
* @brief Get field param1 from command_long message
*
* @return Parameter 1, as defined by MAV_CMD enum.
* @return Parameter 1 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg)
{
@ -378,7 +378,7 @@ static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t*
/**
* @brief Get field param2 from command_long message
*
* @return Parameter 2, as defined by MAV_CMD enum.
* @return Parameter 2 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg)
{
@ -388,7 +388,7 @@ static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t*
/**
* @brief Get field param3 from command_long message
*
* @return Parameter 3, as defined by MAV_CMD enum.
* @return Parameter 3 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg)
{
@ -398,7 +398,7 @@ static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t*
/**
* @brief Get field param4 from command_long message
*
* @return Parameter 4, as defined by MAV_CMD enum.
* @return Parameter 4 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg)
{
@ -408,7 +408,7 @@ static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t*
/**
* @brief Get field param5 from command_long message
*
* @return Parameter 5, as defined by MAV_CMD enum.
* @return Parameter 5 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg)
{
@ -418,7 +418,7 @@ static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t*
/**
* @brief Get field param6 from command_long message
*
* @return Parameter 6, as defined by MAV_CMD enum.
* @return Parameter 6 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg)
{
@ -428,7 +428,7 @@ static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t*
/**
* @brief Get field param7 from command_long message
*
* @return Parameter 7, as defined by MAV_CMD enum.
* @return Parameter 7 (for the specific command).
*/
static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg)
{

View file

@ -3,26 +3,26 @@
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146
MAVPACKED(
typedef struct __mavlink_control_system_state_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
float x_acc; /*< X acceleration in body frame*/
float y_acc; /*< Y acceleration in body frame*/
float z_acc; /*< Z acceleration in body frame*/
float x_vel; /*< X velocity in body frame*/
float y_vel; /*< Y velocity in body frame*/
float z_vel; /*< Z velocity in body frame*/
float x_pos; /*< X position in local frame*/
float y_pos; /*< Y position in local frame*/
float z_pos; /*< Z position in local frame*/
float airspeed; /*< Airspeed, set to -1 if unknown*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float x_acc; /*< [m/s/s] X acceleration in body frame*/
float y_acc; /*< [m/s/s] Y acceleration in body frame*/
float z_acc; /*< [m/s/s] Z acceleration in body frame*/
float x_vel; /*< [m/s] X velocity in body frame*/
float y_vel; /*< [m/s] Y velocity in body frame*/
float z_vel; /*< [m/s] Z velocity in body frame*/
float x_pos; /*< [m] X position in local frame*/
float y_pos; /*< [m] Y position in local frame*/
float z_pos; /*< [m] Z position in local frame*/
float airspeed; /*< [m/s] Airspeed, set to -1 if unknown*/
float vel_variance[3]; /*< Variance of body velocity estimate*/
float pos_variance[3]; /*< Variance in local position*/
float q[4]; /*< The attitude, represented as Quaternion*/
float roll_rate; /*< Angular rate in roll axis*/
float pitch_rate; /*< Angular rate in pitch axis*/
float yaw_rate; /*< Angular rate in yaw axis*/
}) mavlink_control_system_state_t;
float roll_rate; /*< [rad/s] Angular rate in roll axis*/
float pitch_rate; /*< [rad/s] Angular rate in pitch axis*/
float yaw_rate; /*< [rad/s] Angular rate in yaw axis*/
} mavlink_control_system_state_t;
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100
@ -91,23 +91,23 @@ typedef struct __mavlink_control_system_state_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param x_acc X acceleration in body frame
* @param y_acc Y acceleration in body frame
* @param z_acc Z acceleration in body frame
* @param x_vel X velocity in body frame
* @param y_vel Y velocity in body frame
* @param z_vel Z velocity in body frame
* @param x_pos X position in local frame
* @param y_pos Y position in local frame
* @param z_pos Z position in local frame
* @param airspeed Airspeed, set to -1 if unknown
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x_acc [m/s/s] X acceleration in body frame
* @param y_acc [m/s/s] Y acceleration in body frame
* @param z_acc [m/s/s] Z acceleration in body frame
* @param x_vel [m/s] X velocity in body frame
* @param y_vel [m/s] Y velocity in body frame
* @param z_vel [m/s] Z velocity in body frame
* @param x_pos [m] X position in local frame
* @param y_pos [m] Y position in local frame
* @param z_pos [m] Z position in local frame
* @param airspeed [m/s] Airspeed, set to -1 if unknown
* @param vel_variance Variance of body velocity estimate
* @param pos_variance Variance in local position
* @param q The attitude, represented as Quaternion
* @param roll_rate Angular rate in roll axis
* @param pitch_rate Angular rate in pitch axis
* @param yaw_rate Angular rate in yaw axis
* @param roll_rate [rad/s] Angular rate in roll axis
* @param pitch_rate [rad/s] Angular rate in pitch axis
* @param yaw_rate [rad/s] Angular rate in yaw axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -165,23 +165,23 @@ static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id,
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param x_acc X acceleration in body frame
* @param y_acc Y acceleration in body frame
* @param z_acc Z acceleration in body frame
* @param x_vel X velocity in body frame
* @param y_vel Y velocity in body frame
* @param z_vel Z velocity in body frame
* @param x_pos X position in local frame
* @param y_pos Y position in local frame
* @param z_pos Z position in local frame
* @param airspeed Airspeed, set to -1 if unknown
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x_acc [m/s/s] X acceleration in body frame
* @param y_acc [m/s/s] Y acceleration in body frame
* @param z_acc [m/s/s] Z acceleration in body frame
* @param x_vel [m/s] X velocity in body frame
* @param y_vel [m/s] Y velocity in body frame
* @param z_vel [m/s] Z velocity in body frame
* @param x_pos [m] X position in local frame
* @param y_pos [m] Y position in local frame
* @param z_pos [m] Z position in local frame
* @param airspeed [m/s] Airspeed, set to -1 if unknown
* @param vel_variance Variance of body velocity estimate
* @param pos_variance Variance in local position
* @param q The attitude, represented as Quaternion
* @param roll_rate Angular rate in roll axis
* @param pitch_rate Angular rate in pitch axis
* @param yaw_rate Angular rate in yaw axis
* @param roll_rate [rad/s] Angular rate in roll axis
* @param pitch_rate [rad/s] Angular rate in pitch axis
* @param yaw_rate [rad/s] Angular rate in yaw axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -265,23 +265,23 @@ static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t syst
* @brief Send a control_system_state message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param x_acc X acceleration in body frame
* @param y_acc Y acceleration in body frame
* @param z_acc Z acceleration in body frame
* @param x_vel X velocity in body frame
* @param y_vel Y velocity in body frame
* @param z_vel Z velocity in body frame
* @param x_pos X position in local frame
* @param y_pos Y position in local frame
* @param z_pos Z position in local frame
* @param airspeed Airspeed, set to -1 if unknown
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x_acc [m/s/s] X acceleration in body frame
* @param y_acc [m/s/s] Y acceleration in body frame
* @param z_acc [m/s/s] Z acceleration in body frame
* @param x_vel [m/s] X velocity in body frame
* @param y_vel [m/s] Y velocity in body frame
* @param z_vel [m/s] Z velocity in body frame
* @param x_pos [m] X position in local frame
* @param y_pos [m] Y position in local frame
* @param z_pos [m] Z position in local frame
* @param airspeed [m/s] Airspeed, set to -1 if unknown
* @param vel_variance Variance of body velocity estimate
* @param pos_variance Variance in local position
* @param q The attitude, represented as Quaternion
* @param roll_rate Angular rate in roll axis
* @param pitch_rate Angular rate in pitch axis
* @param yaw_rate Angular rate in yaw axis
* @param roll_rate [rad/s] Angular rate in roll axis
* @param pitch_rate [rad/s] Angular rate in pitch axis
* @param yaw_rate [rad/s] Angular rate in yaw axis
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -406,7 +406,7 @@ static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *
/**
* @brief Get field time_usec from control_system_state message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg)
{
@ -416,7 +416,7 @@ static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavl
/**
* @brief Get field x_acc from control_system_state message
*
* @return X acceleration in body frame
* @return [m/s/s] X acceleration in body frame
*/
static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg)
{
@ -426,7 +426,7 @@ static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_mes
/**
* @brief Get field y_acc from control_system_state message
*
* @return Y acceleration in body frame
* @return [m/s/s] Y acceleration in body frame
*/
static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg)
{
@ -436,7 +436,7 @@ static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_mes
/**
* @brief Get field z_acc from control_system_state message
*
* @return Z acceleration in body frame
* @return [m/s/s] Z acceleration in body frame
*/
static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg)
{
@ -446,7 +446,7 @@ static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_mes
/**
* @brief Get field x_vel from control_system_state message
*
* @return X velocity in body frame
* @return [m/s] X velocity in body frame
*/
static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg)
{
@ -456,7 +456,7 @@ static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_mes
/**
* @brief Get field y_vel from control_system_state message
*
* @return Y velocity in body frame
* @return [m/s] Y velocity in body frame
*/
static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg)
{
@ -466,7 +466,7 @@ static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_mes
/**
* @brief Get field z_vel from control_system_state message
*
* @return Z velocity in body frame
* @return [m/s] Z velocity in body frame
*/
static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg)
{
@ -476,7 +476,7 @@ static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_mes
/**
* @brief Get field x_pos from control_system_state message
*
* @return X position in local frame
* @return [m] X position in local frame
*/
static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg)
{
@ -486,7 +486,7 @@ static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_mes
/**
* @brief Get field y_pos from control_system_state message
*
* @return Y position in local frame
* @return [m] Y position in local frame
*/
static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg)
{
@ -496,7 +496,7 @@ static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_mes
/**
* @brief Get field z_pos from control_system_state message
*
* @return Z position in local frame
* @return [m] Z position in local frame
*/
static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg)
{
@ -506,7 +506,7 @@ static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_mes
/**
* @brief Get field airspeed from control_system_state message
*
* @return Airspeed, set to -1 if unknown
* @return [m/s] Airspeed, set to -1 if unknown
*/
static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg)
{
@ -546,7 +546,7 @@ static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_mess
/**
* @brief Get field roll_rate from control_system_state message
*
* @return Angular rate in roll axis
* @return [rad/s] Angular rate in roll axis
*/
static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg)
{
@ -556,7 +556,7 @@ static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink
/**
* @brief Get field pitch_rate from control_system_state message
*
* @return Angular rate in pitch axis
* @return [rad/s] Angular rate in pitch axis
*/
static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg)
{
@ -566,7 +566,7 @@ static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlin
/**
* @brief Get field yaw_rate from control_system_state message
*
* @return Angular rate in yaw axis
* @return [rad/s] Angular rate in yaw axis
*/
static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_DATA_STREAM 67
MAVPACKED(
typedef struct __mavlink_data_stream_t {
uint16_t message_rate; /*< The message rate*/
uint16_t message_rate; /*< [Hz] The message rate*/
uint8_t stream_id; /*< The ID of the requested data stream*/
uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/
}) mavlink_data_stream_t;
} mavlink_data_stream_t;
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
#define MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN 4
@ -25,8 +25,8 @@ typedef struct __mavlink_data_stream_t {
67, \
"DATA_STREAM", \
3, \
{ { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \
} \
}
@ -34,8 +34,8 @@ typedef struct __mavlink_data_stream_t {
#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \
"DATA_STREAM", \
3, \
{ { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \
} \
}
@ -48,7 +48,7 @@ typedef struct __mavlink_data_stream_t {
* @param msg The MAVLink message to compress the data into
*
* @param stream_id The ID of the requested data stream
* @param message_rate The message rate
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -82,7 +82,7 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param stream_id The ID of the requested data stream
* @param message_rate The message rate
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, ui
* @param chan MAVLink channel to send the message
*
* @param stream_id The ID of the requested data stream
* @param message_rate The message rate
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_messag
/**
* @brief Get field message_rate from data_stream message
*
* @return The message rate
* @return [Hz] The message rate
*/
static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
MAVPACKED(
typedef struct __mavlink_data_transmission_handshake_t {
uint32_t size; /*< total data size in bytes (set on ACK only)*/
uint16_t width; /*< Width of a matrix or image*/
uint16_t height; /*< Height of a matrix or image*/
uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/
uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/
uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/
uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/
}) mavlink_data_transmission_handshake_t;
uint32_t size; /*< [bytes] total data size (set on ACK only).*/
uint16_t width; /*< Width of a matrix or image.*/
uint16_t height; /*< Height of a matrix or image.*/
uint16_t packets; /*< Number of packets being sent (set on ACK only).*/
uint8_t type; /*< Type of requested/acknowledged data.*/
uint8_t payload; /*< [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).*/
uint8_t jpg_quality; /*< [%] JPEG quality. Values: [1-100].*/
} mavlink_data_transmission_handshake_t;
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN 13
@ -29,11 +29,11 @@ typedef struct __mavlink_data_transmission_handshake_t {
130, \
"DATA_TRANSMISSION_HANDSHAKE", \
7, \
{ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
{ "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
{ "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
} \
@ -42,11 +42,11 @@ typedef struct __mavlink_data_transmission_handshake_t {
#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \
"DATA_TRANSMISSION_HANDSHAKE", \
7, \
{ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
{ "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
{ "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
} \
@ -59,13 +59,13 @@ typedef struct __mavlink_data_transmission_handshake_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @param type Type of requested/acknowledged data.
* @param size [bytes] total data size (set on ACK only).
* @param width Width of a matrix or image.
* @param height Height of a matrix or image.
* @param packets Number of packets being sent (set on ACK only).
* @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
* @param jpg_quality [%] JPEG quality. Values: [1-100].
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @param type Type of requested/acknowledged data.
* @param size [bytes] total data size (set on ACK only).
* @param width Width of a matrix or image.
* @param height Height of a matrix or image.
* @param packets Number of packets being sent (set on ACK only).
* @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
* @param jpg_quality [%] JPEG quality. Values: [1-100].
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8
* @brief Send a data_transmission_handshake message
* @param chan MAVLink channel to send the message
*
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @param type Type of requested/acknowledged data.
* @param size [bytes] total data size (set on ACK only).
* @param width Width of a matrix or image.
* @param height Height of a matrix or image.
* @param packets Number of packets being sent (set on ACK only).
* @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
* @param jpg_quality [%] JPEG quality. Values: [1-100].
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_mess
/**
* @brief Get field type from data_transmission_handshake message
*
* @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @return Type of requested/acknowledged data.
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mav
/**
* @brief Get field size from data_transmission_handshake message
*
* @return total data size in bytes (set on ACK only)
* @return [bytes] total data size (set on ACK only).
*/
static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const ma
/**
* @brief Get field width from data_transmission_handshake message
*
* @return Width of a matrix or image
* @return Width of a matrix or image.
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const m
/**
* @brief Get field height from data_transmission_handshake message
*
* @return Height of a matrix or image
* @return Height of a matrix or image.
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const
/**
* @brief Get field packets from data_transmission_handshake message
*
* @return number of packets beeing sent (set on ACK only)
* @return Number of packets being sent (set on ACK only).
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const
/**
* @brief Get field payload from data_transmission_handshake message
*
* @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @return [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const
/**
* @brief Get field jpg_quality from data_transmission_handshake message
*
* @return JPEG quality out of [1,100]
* @return [%] JPEG quality. Values: [1-100].
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_DEBUG 254
MAVPACKED(
typedef struct __mavlink_debug_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float value; /*< DEBUG value*/
uint8_t ind; /*< index of debug variable*/
}) mavlink_debug_t;
} mavlink_debug_t;
#define MAVLINK_MSG_ID_DEBUG_LEN 9
#define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9
@ -26,8 +26,8 @@ typedef struct __mavlink_debug_t {
"DEBUG", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
{ "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
} \
}
#else
@ -35,8 +35,8 @@ typedef struct __mavlink_debug_t {
"DEBUG", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
{ "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
} \
}
#endif
@ -47,7 +47,7 @@ typedef struct __mavlink_debug_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
@ -141,7 +141,7 @@ static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t
* @brief Send a debug message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param ind index of debug variable
* @param value DEBUG value
*/
@ -216,7 +216,7 @@ static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink
/**
* @brief Get field time_boot_ms from debug message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg)
{

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_DEBUG_VECT 250
MAVPACKED(
typedef struct __mavlink_debug_vect_t {
uint64_t time_usec; /*< Timestamp*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float x; /*< x*/
float y; /*< y*/
float z; /*< z*/
char name[10]; /*< Name*/
}) mavlink_debug_vect_t;
} mavlink_debug_vect_t;
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30
@ -27,22 +27,22 @@ typedef struct __mavlink_debug_vect_t {
250, \
"DEBUG_VECT", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
} \
}
#endif
@ -54,7 +54,7 @@ typedef struct __mavlink_debug_vect_t {
* @param msg The MAVLink message to compress the data into
*
* @param name Name
* @param time_usec Timestamp
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x x
* @param y y
* @param z z
@ -92,7 +92,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param time_usec Timestamp
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x x
* @param y y
* @param z z
@ -156,7 +156,7 @@ static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uin
* @param chan MAVLink channel to send the message
*
* @param name Name
* @param time_usec Timestamp
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param x x
* @param y y
* @param z z
@ -246,7 +246,7 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t*
/**
* @brief Get field time_usec from debug_vect message
*
* @return Timestamp
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
{

View file

@ -3,17 +3,17 @@
#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
MAVPACKED(
typedef struct __mavlink_distance_sensor_t {
uint32_t time_boot_ms; /*< Time since system boot*/
uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/
uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/
uint16_t current_distance; /*< Current distance reading*/
uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure*/
uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure*/
uint16_t current_distance; /*< [cm] Current distance reading*/
uint8_t type; /*< Type of distance sensor.*/
uint8_t id; /*< Onboard ID of the sensor*/
uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/
uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/
}) mavlink_distance_sensor_t;
uint8_t orientation; /*< Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270*/
uint8_t covariance; /*< [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.*/
} mavlink_distance_sensor_t;
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14
@ -62,14 +62,14 @@ typedef struct __mavlink_distance_sensor_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param min_distance [cm] Minimum distance the sensor can measure
* @param max_distance [cm] Maximum distance the sensor can measure
* @param current_distance [cm] Current distance reading
* @param type Type of distance sensor.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param min_distance [cm] Minimum distance the sensor can measure
* @param max_distance [cm] Maximum distance the sensor can measure
* @param current_distance [cm] Current distance reading
* @param type Type of distance sensor.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id
* @brief Send a distance_sensor message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param min_distance [cm] Minimum distance the sensor can measure
* @param max_distance [cm] Maximum distance the sensor can measure
* @param current_distance [cm] Current distance reading
* @param type Type of distance sensor.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -286,7 +286,7 @@ static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbu
/**
* @brief Get field time_boot_ms from distance_sensor message
*
* @return Time since system boot
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -296,7 +296,7 @@ static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlin
/**
* @brief Get field min_distance from distance_sensor message
*
* @return Minimum distance the sensor can measure in centimeters
* @return [cm] Minimum distance the sensor can measure
*/
static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
{
@ -306,7 +306,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlin
/**
* @brief Get field max_distance from distance_sensor message
*
* @return Maximum distance the sensor can measure in centimeters
* @return [cm] Maximum distance the sensor can measure
*/
static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
{
@ -316,7 +316,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlin
/**
* @brief Get field current_distance from distance_sensor message
*
* @return Current distance reading
* @return [cm] Current distance reading
*/
static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const ma
/**
* @brief Get field type from distance_sensor message
*
* @return Type from MAV_DISTANCE_SENSOR enum.
* @return Type of distance sensor.
*/
static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t
/**
* @brief Get field orientation from distance_sensor message
*
* @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.
* @return Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
*/
static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_
/**
* @brief Get field covariance from distance_sensor message
*
* @return Measurement covariance in centimeters, 0 for unknown / invalid readings
* @return [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
*/
static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131
MAVPACKED(
typedef struct __mavlink_encapsulated_data_t {
uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/
uint8_t data[253]; /*< image data bytes*/
}) mavlink_encapsulated_data_t;
} mavlink_encapsulated_data_t;
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN 255

View file

@ -3,19 +3,19 @@
#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230
MAVPACKED(
typedef struct __mavlink_estimator_status_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float vel_ratio; /*< Velocity innovation test ratio*/
float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
float pos_vert_ratio; /*< Vertical position innovation test ratio*/
float mag_ratio; /*< Magnetometer innovation test ratio*/
float hagl_ratio; /*< Height above terrain innovation test ratio*/
float tas_ratio; /*< True airspeed innovation test ratio*/
float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
}) mavlink_estimator_status_t;
float pos_horiz_accuracy; /*< [m] Horizontal position 1-STD accuracy relative to the EKF local origin*/
float pos_vert_accuracy; /*< [m] Vertical position 1-STD accuracy relative to the EKF local origin*/
uint16_t flags; /*< Bitmap indicating which EKF outputs are valid.*/
} mavlink_estimator_status_t;
#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42
#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN 42
@ -33,6 +33,7 @@ typedef struct __mavlink_estimator_status_t {
"ESTIMATOR_STATUS", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \
{ "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \
{ "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \
{ "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \
@ -41,7 +42,6 @@ typedef struct __mavlink_estimator_status_t {
{ "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \
{ "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \
{ "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \
} \
}
#else
@ -49,6 +49,7 @@ typedef struct __mavlink_estimator_status_t {
"ESTIMATOR_STATUS", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \
{ "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \
{ "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \
{ "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \
@ -57,7 +58,6 @@ typedef struct __mavlink_estimator_status_t {
{ "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \
{ "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \
{ "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \
} \
}
#endif
@ -68,16 +68,16 @@ typedef struct __mavlink_estimator_status_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param flags Bitmap indicating which EKF outputs are valid.
* @param vel_ratio Velocity innovation test ratio
* @param pos_horiz_ratio Horizontal position innovation test ratio
* @param pos_vert_ratio Vertical position innovation test ratio
* @param mag_ratio Magnetometer innovation test ratio
* @param hagl_ratio Height above terrain innovation test ratio
* @param tas_ratio True airspeed innovation test ratio
* @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin
* @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param flags Bitmap indicating which EKF outputs are valid.
* @param vel_ratio Velocity innovation test ratio
* @param pos_horiz_ratio Horizontal position innovation test ratio
* @param pos_vert_ratio Vertical position innovation test ratio
* @param mag_ratio Magnetometer innovation test ratio
* @param hagl_ratio Height above terrain innovation test ratio
* @param tas_ratio True airspeed innovation test ratio
* @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin
* @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_i
* @brief Send a estimator_status message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param flags Bitmap indicating which EKF outputs are valid.
* @param vel_ratio Velocity innovation test ratio
* @param pos_horiz_ratio Horizontal position innovation test ratio
* @param pos_vert_ratio Vertical position innovation test ratio
* @param mag_ratio Magnetometer innovation test ratio
* @param hagl_ratio Height above terrain innovation test ratio
* @param tas_ratio True airspeed innovation test ratio
* @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m)
* @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin
* @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -314,7 +314,7 @@ static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgb
/**
* @brief Get field time_usec from estimator_status message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg)
{
@ -324,7 +324,7 @@ static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_
/**
* @brief Get field flags from estimator_status message
*
* @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.
* @return Bitmap indicating which EKF outputs are valid.
*/
static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg)
{
@ -394,7 +394,7 @@ static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_mes
/**
* @brief Get field pos_horiz_accuracy from estimator_status message
*
* @return Horizontal position 1-STD accuracy relative to the EKF local origin (m)
* @return [m] Horizontal position 1-STD accuracy relative to the EKF local origin
*/
static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg)
{
@ -404,7 +404,7 @@ static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const ma
/**
* @brief Get field pos_vert_accuracy from estimator_status message
*
* @return Vertical position 1-STD accuracy relative to the EKF local origin (m)
* @return [m] Vertical position 1-STD accuracy relative to the EKF local origin
*/
static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245
MAVPACKED(
typedef struct __mavlink_extended_sys_state_t {
uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/
uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/
}) mavlink_extended_sys_state_t;
} mavlink_extended_sys_state_t;
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN 2

View file

@ -0,0 +1,288 @@
#pragma once
// MESSAGE FENCE_STATUS PACKING
#define MAVLINK_MSG_ID_FENCE_STATUS 162
typedef struct __mavlink_fence_status_t {
uint32_t breach_time; /*< [ms] Time (since boot) of last breach.*/
uint16_t breach_count; /*< Number of fence breaches.*/
uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/
uint8_t breach_type; /*< Last breach type.*/
} mavlink_fence_status_t;
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8
#define MAVLINK_MSG_ID_162_LEN 8
#define MAVLINK_MSG_ID_162_MIN_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189
#define MAVLINK_MSG_ID_162_CRC 189
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
162, \
"FENCE_STATUS", \
4, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
"FENCE_STATUS", \
4, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
} \
}
#endif
/**
* @brief Pack a fence_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
}
/**
* @brief Pack a fence_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
}
/**
* @brief Encode a fence_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
/**
* @brief Encode a fence_status struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
*
* @param breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf;
packet->breach_time = breach_time;
packet->breach_count = breach_count;
packet->breach_status = breach_status;
packet->breach_type = breach_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE FENCE_STATUS UNPACKING
/**
* @brief Get field breach_status from fence_status message
*
* @return Breach status (0 if currently inside fence, 1 if outside).
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field breach_count from fence_status message
*
* @return Number of fence breaches.
*/
static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field breach_type from fence_status message
*
* @return Last breach type.
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field breach_time from fence_status message
*
* @return [ms] Time (since boot) of last breach.
*/
static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Decode a fence_status message into a struct
*
* @param msg The message to decode
* @param fence_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN;
memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
memcpy(fence_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110
MAVPACKED(
typedef struct __mavlink_file_transfer_protocol_t {
uint8_t target_network; /*< Network ID (0 for broadcast)*/
uint8_t target_system; /*< System ID (0 for broadcast)*/
uint8_t target_component; /*< Component ID (0 for broadcast)*/
uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/
}) mavlink_file_transfer_protocol_t;
} mavlink_file_transfer_protocol_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN 254

View file

@ -3,20 +3,20 @@
#define MAVLINK_MSG_ID_FOLLOW_TARGET 144
MAVPACKED(
typedef struct __mavlink_follow_target_t {
uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/
uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/
uint64_t custom_state; /*< button states or switches of a tracker device*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
float alt; /*< AMSL, in meters*/
float vel[3]; /*< target velocity (0,0,0) for unknown*/
float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
float alt; /*< [m] Altitude (MSL)*/
float vel[3]; /*< [m/s] target velocity (0,0,0) for unknown*/
float acc[3]; /*< [m/s/s] linear target acceleration (0,0,0) for unknown*/
float attitude_q[4]; /*< (1 0 0 0 for unknown)*/
float rates[3]; /*< (0 0 0 for unknown)*/
float position_cov[3]; /*< eph epv*/
uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/
}) mavlink_follow_target_t;
} mavlink_follow_target_t;
#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93
#define MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN 93
@ -38,7 +38,7 @@ typedef struct __mavlink_follow_target_t {
"FOLLOW_TARGET", \
11, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \
{ "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \
{ "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \
@ -47,7 +47,7 @@ typedef struct __mavlink_follow_target_t {
{ "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \
{ "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \
{ "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \
{ "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \
{ "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \
} \
}
#else
@ -55,7 +55,7 @@ typedef struct __mavlink_follow_target_t {
"FOLLOW_TARGET", \
11, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \
{ "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \
{ "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \
@ -64,7 +64,7 @@ typedef struct __mavlink_follow_target_t {
{ "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \
{ "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \
{ "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \
{ "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \
{ "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \
} \
}
#endif
@ -75,13 +75,13 @@ typedef struct __mavlink_follow_target_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param timestamp Timestamp in milliseconds since system boot
* @param timestamp [ms] Timestamp (time since system boot).
* @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt AMSL, in meters
* @param vel target velocity (0,0,0) for unknown
* @param acc linear target acceleration (0,0,0) for unknown
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL)
* @param vel [m/s] target velocity (0,0,0) for unknown
* @param acc [m/s/s] linear target acceleration (0,0,0) for unknown
* @param attitude_q (1 0 0 0 for unknown)
* @param rates (0 0 0 for unknown)
* @param position_cov eph epv
@ -131,13 +131,13 @@ static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param timestamp Timestamp in milliseconds since system boot
* @param timestamp [ms] Timestamp (time since system boot).
* @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt AMSL, in meters
* @param vel target velocity (0,0,0) for unknown
* @param acc linear target acceleration (0,0,0) for unknown
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL)
* @param vel [m/s] target velocity (0,0,0) for unknown
* @param acc [m/s/s] linear target acceleration (0,0,0) for unknown
* @param attitude_q (1 0 0 0 for unknown)
* @param rates (0 0 0 for unknown)
* @param position_cov eph epv
@ -213,13 +213,13 @@ static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id,
* @brief Send a follow_target message
* @param chan MAVLink channel to send the message
*
* @param timestamp Timestamp in milliseconds since system boot
* @param timestamp [ms] Timestamp (time since system boot).
* @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt AMSL, in meters
* @param vel target velocity (0,0,0) for unknown
* @param acc linear target acceleration (0,0,0) for unknown
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL)
* @param vel [m/s] target velocity (0,0,0) for unknown
* @param acc [m/s/s] linear target acceleration (0,0,0) for unknown
* @param attitude_q (1 0 0 0 for unknown)
* @param rates (0 0 0 for unknown)
* @param position_cov eph epv
@ -324,7 +324,7 @@ static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field timestamp from follow_target message
*
* @return Timestamp in milliseconds since system boot
* @return [ms] Timestamp (time since system boot).
*/
static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg)
{
@ -344,7 +344,7 @@ static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavli
/**
* @brief Get field lat from follow_target message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg)
{
@ -354,7 +354,7 @@ static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t*
/**
* @brief Get field lon from follow_target message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg)
{
@ -364,7 +364,7 @@ static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t*
/**
* @brief Get field alt from follow_target message
*
* @return AMSL, in meters
* @return [m] Altitude (MSL)
*/
static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg)
{
@ -374,7 +374,7 @@ static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* m
/**
* @brief Get field vel from follow_target message
*
* @return target velocity (0,0,0) for unknown
* @return [m/s] target velocity (0,0,0) for unknown
*/
static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel)
{
@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t
/**
* @brief Get field acc from follow_target message
*
* @return linear target acceleration (0,0,0) for unknown
* @return [m/s/s] linear target acceleration (0,0,0) for unknown
*/
static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc)
{

View file

@ -3,18 +3,18 @@
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
MAVPACKED(
typedef struct __mavlink_global_position_int_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/
int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/
int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/
int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/
uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
}) mavlink_global_position_int_t;
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
int32_t lat; /*< [degE7] Latitude, expressed*/
int32_t lon; /*< [degE7] Longitude, expressed*/
int32_t alt; /*< [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.*/
int32_t relative_alt; /*< [mm] Altitude above ground*/
int16_t vx; /*< [cm/s] Ground X Speed (Latitude, positive north)*/
int16_t vy; /*< [cm/s] Ground Y Speed (Longitude, positive east)*/
int16_t vz; /*< [cm/s] Ground Z Speed (Altitude, positive down)*/
uint16_t hdg; /*< [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
} mavlink_global_position_int_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28
@ -65,15 +65,15 @@ typedef struct __mavlink_global_position_int_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
* @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param lat [degE7] Latitude, expressed
* @param lon [degE7] Longitude, expressed
* @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
* @param relative_alt [mm] Altitude above ground
* @param vx [cm/s] Ground X Speed (Latitude, positive north)
* @param vy [cm/s] Ground Y Speed (Longitude, positive east)
* @param vz [cm/s] Ground Z Speed (Altitude, positive down)
* @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -117,15 +117,15 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
* @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param lat [degE7] Latitude, expressed
* @param lon [degE7] Longitude, expressed
* @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
* @param relative_alt [mm] Altitude above ground
* @param vx [cm/s] Ground X Speed (Latitude, positive north)
* @param vy [cm/s] Ground Y Speed (Longitude, positive east)
* @param vz [cm/s] Ground Z Speed (Altitude, positive down)
* @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -195,15 +195,15 @@ static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t syste
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
* @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param lat [degE7] Latitude, expressed
* @param lon [degE7] Longitude, expressed
* @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
* @param relative_alt [mm] Altitude above ground
* @param vx [cm/s] Ground X Speed (Latitude, positive north)
* @param vy [cm/s] Ground Y Speed (Longitude, positive east)
* @param vz [cm/s] Ground Z Speed (Altitude, positive down)
* @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -300,7 +300,7 @@ static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *m
/**
* @brief Get field time_boot_ms from global_position_int message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -310,7 +310,7 @@ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const ma
/**
* @brief Get field lat from global_position_int message
*
* @return Latitude, expressed as degrees * 1E7
* @return [degE7] Latitude, expressed
*/
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
@ -320,7 +320,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess
/**
* @brief Get field lon from global_position_int message
*
* @return Longitude, expressed as degrees * 1E7
* @return [degE7] Longitude, expressed
*/
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
@ -330,7 +330,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @return [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
@ -340,7 +340,7 @@ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_mess
/**
* @brief Get field relative_alt from global_position_int message
*
* @return Altitude above ground in meters, expressed as * 1000 (millimeters)
* @return [mm] Altitude above ground
*/
static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
{
@ -350,7 +350,7 @@ static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mav
/**
* @brief Get field vx from global_position_int message
*
* @return Ground X Speed (Latitude, positive north), expressed as m/s * 100
* @return [cm/s] Ground X Speed (Latitude, positive north)
*/
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{
@ -360,7 +360,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_messa
/**
* @brief Get field vy from global_position_int message
*
* @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100
* @return [cm/s] Ground Y Speed (Longitude, positive east)
*/
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{
@ -370,7 +370,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_messa
/**
* @brief Get field vz from global_position_int message
*
* @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100
* @return [cm/s] Ground Z Speed (Altitude, positive down)
*/
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{
@ -380,7 +380,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa
/**
* @brief Get field hdg from global_position_int message
*
* @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{

View file

@ -3,19 +3,19 @@
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
MAVPACKED(
typedef struct __mavlink_global_position_int_cov_t {
uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/
int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/
int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
float vx; /*< Ground X Speed (Latitude), expressed as m/s*/
float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/
float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/
float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
int32_t alt; /*< [mm] Altitude in meters above MSL*/
int32_t relative_alt; /*< [mm] Altitude above ground*/
float vx; /*< [m/s] Ground X Speed (Latitude)*/
float vy; /*< [m/s] Ground Y Speed (Longitude)*/
float vz; /*< [m/s] Ground Z Speed (Altitude)*/
float covariance[36]; /*< Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
}) mavlink_global_position_int_cov_t;
} mavlink_global_position_int_cov_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181
@ -33,6 +33,7 @@ typedef struct __mavlink_global_position_int_cov_t {
"GLOBAL_POSITION_INT_COV", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \
@ -41,7 +42,6 @@ typedef struct __mavlink_global_position_int_cov_t {
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
} \
}
#else
@ -49,6 +49,7 @@ typedef struct __mavlink_global_position_int_cov_t {
"GLOBAL_POSITION_INT_COV", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \
@ -57,7 +58,6 @@ typedef struct __mavlink_global_position_int_cov_t {
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
} \
}
#endif
@ -68,16 +68,16 @@ typedef struct __mavlink_global_position_int_cov_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude in meters above MSL
* @param relative_alt [mm] Altitude above ground
* @param vx [m/s] Ground X Speed (Latitude)
* @param vy [m/s] Ground Y Speed (Longitude)
* @param vz [m/s] Ground Z Speed (Altitude)
* @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -121,16 +121,16 @@ static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_i
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude in meters above MSL
* @param relative_alt [mm] Altitude above ground
* @param vx [m/s] Ground X Speed (Latitude)
* @param vy [m/s] Ground Y Speed (Longitude)
* @param vz [m/s] Ground Z Speed (Altitude)
* @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -200,16 +200,16 @@ static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t s
* @brief Send a global_position_int_cov message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude in meters above MSL
* @param relative_alt [mm] Altitude above ground
* @param vx [m/s] Ground X Speed (Latitude)
* @param vy [m/s] Ground Y Speed (Longitude)
* @param vz [m/s] Ground Z Speed (Altitude)
* @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -306,7 +306,7 @@ static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_
/**
* @brief Get field time_usec from global_position_int_cov message
*
* @return Timestamp (microseconds since system boot or since UNIX epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(con
/**
* @brief Get field lat from global_position_int_cov message
*
* @return Latitude, expressed as degrees * 1E7
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_
/**
* @brief Get field lon from global_position_int_cov message
*
* @return Longitude, expressed as degrees * 1E7
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_
/**
* @brief Get field alt from global_position_int_cov message
*
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @return [mm] Altitude in meters above MSL
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_
/**
* @brief Get field relative_alt from global_position_int_cov message
*
* @return Altitude above ground in meters, expressed as * 1000 (millimeters)
* @return [mm] Altitude above ground
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
{
@ -366,7 +366,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const
/**
* @brief Get field vx from global_position_int_cov message
*
* @return Ground X Speed (Latitude), expressed as m/s
* @return [m/s] Ground X Speed (Latitude)
*/
static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
{
@ -376,7 +376,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_mes
/**
* @brief Get field vy from global_position_int_cov message
*
* @return Ground Y Speed (Longitude), expressed as m/s
* @return [m/s] Ground Y Speed (Longitude)
*/
static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_mes
/**
* @brief Get field vz from global_position_int_cov message
*
* @return Ground Z Speed (Altitude), expressed as m/s
* @return [m/s] Ground Z Speed (Altitude)
*/
static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
{
@ -396,7 +396,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_mes
/**
* @brief Get field covariance from global_position_int_cov message
*
* @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @return Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101
MAVPACKED(
typedef struct __mavlink_global_vision_position_estimate_t {
uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
float x; /*< Global X position*/
float y; /*< Global Y position*/
float z; /*< Global Z position*/
float roll; /*< Roll angle in rad*/
float pitch; /*< Pitch angle in rad*/
float yaw; /*< Yaw angle in rad*/
}) mavlink_global_vision_position_estimate_t;
uint64_t usec; /*< [us] Timestamp (UNIX time or since system boot)*/
float x; /*< [m] Global X position*/
float y; /*< [m] Global Y position*/
float z; /*< [m] Global Z position*/
float roll; /*< [rad] Roll angle*/
float pitch; /*< [rad] Pitch angle*/
float yaw; /*< [rad] Yaw angle*/
} mavlink_global_vision_position_estimate_t;
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32
@ -59,13 +59,13 @@ typedef struct __mavlink_global_vision_position_estimate_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param usec [us] Timestamp (UNIX time or since system boot)
* @param x [m] Global X position
* @param y [m] Global Y position
* @param z [m] Global Z position
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param usec [us] Timestamp (UNIX time or since system boot)
* @param x [m] Global X position
* @param y [m] Global Y position
* @param z [m] Global Z position
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(u
* @brief Send a global_vision_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param usec [us] Timestamp (UNIX time or since system boot)
* @param x [m] Global X position
* @param y [m] Global Y position
* @param z [m] Global Z position
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_
/**
* @brief Get field usec from global_vision_position_estimate message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
* @return [us] Timestamp (UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(cons
/**
* @brief Get field x from global_vision_position_estimate message
*
* @return Global X position
* @return [m] Global X position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavl
/**
* @brief Get field y from global_vision_position_estimate message
*
* @return Global Y position
* @return [m] Global Y position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavl
/**
* @brief Get field z from global_vision_position_estimate message
*
* @return Global Z position
* @return [m] Global Z position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavl
/**
* @brief Get field roll from global_vision_position_estimate message
*
* @return Roll angle in rad
* @return [rad] Roll angle
*/
static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_roll(const m
/**
* @brief Get field pitch from global_vision_position_estimate message
*
* @return Pitch angle in rad
* @return [rad] Pitch angle
*/
static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const
/**
* @brief Get field yaw from global_vision_position_estimate message
*
* @return Yaw angle in rad
* @return [rad] Yaw angle
*/
static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
{

View file

@ -3,21 +3,21 @@
#define MAVLINK_MSG_ID_GPS2_RAW 124
MAVPACKED(
typedef struct __mavlink_gps2_raw_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/
uint32_t dgps_age; /*< Age of DGPS info*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/
uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/
uint32_t dgps_age; /*< [ms] Age of DGPS info*/
uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX*/
uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< GPS fix type.*/
uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
uint8_t dgps_numch; /*< Number of DGPS satellites*/
}) mavlink_gps2_raw_t;
} mavlink_gps2_raw_t;
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
#define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35
@ -35,17 +35,17 @@ typedef struct __mavlink_gps2_raw_t {
"GPS2_RAW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
{ "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
} \
}
#else
@ -53,17 +53,17 @@ typedef struct __mavlink_gps2_raw_t {
"GPS2_RAW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
{ "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
} \
}
#endif
@ -74,18 +74,18 @@ typedef struct __mavlink_gps2_raw_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
* @param dgps_age [ms] Age of DGPS info
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
* @param dgps_age [ms] Age of DGPS info
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8
* @brief Send a gps2_raw message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
* @param dgps_age [ms] Age of DGPS info
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -342,7 +342,7 @@ static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavl
/**
* @brief Get field time_usec from gps2_raw message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
{
@ -352,7 +352,7 @@ static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_
/**
* @brief Get field fix_type from gps2_raw message
*
* @return See the GPS_FIX_TYPE enum.
* @return GPS fix type.
*/
static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
{
@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t*
/**
* @brief Get field lat from gps2_raw message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
{
@ -372,7 +372,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
/**
* @brief Get field lon from gps2_raw message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
{
@ -382,7 +382,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
/**
* @brief Get field alt from gps2_raw message
*
* @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @return [mm] Altitude (MSL). Positive for up.
*/
static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
{
@ -392,7 +392,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field eph from gps2_raw message
*
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
{
@ -402,7 +402,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg
/**
* @brief Get field epv from gps2_raw message
*
* @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
{
@ -412,7 +412,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg
/**
* @brief Get field vel from gps2_raw message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
{
@ -422,7 +422,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg
/**
* @brief Get field cog from gps2_raw message
*
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
{
@ -452,7 +452,7 @@ static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_
/**
* @brief Get field dgps_age from gps2_raw message
*
* @return Age of DGPS info
* @return [ms] Age of DGPS info
*/
static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
{

View file

@ -3,22 +3,22 @@
#define MAVLINK_MSG_ID_GPS2_RTK 128
MAVPACKED(
typedef struct __mavlink_gps2_rtk_t {
uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/
uint32_t tow; /*< GPS Time of Week of last baseline*/
int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/
int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/
int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/
uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/
uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/
int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/
int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/
int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/
uint32_t accuracy; /*< Current estimate of baseline accuracy.*/
int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/
uint16_t wn; /*< GPS Week Number of last baseline*/
uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/
uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/
uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/
uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/
uint8_t nsats; /*< Current number of sats used for RTK calculation.*/
uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/
}) mavlink_gps2_rtk_t;
uint8_t baseline_coords_type; /*< Coordinate system of baseline*/
} mavlink_gps2_rtk_t;
#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35
#define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35
@ -36,18 +36,18 @@ typedef struct __mavlink_gps2_rtk_t {
"GPS2_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
} \
}
#else
@ -55,18 +55,18 @@ typedef struct __mavlink_gps2_rtk_t {
"GPS2_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
} \
}
#endif
@ -77,17 +77,17 @@ typedef struct __mavlink_gps2_rtk_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
@ -141,17 +141,17 @@ static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t comp
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
@ -231,17 +231,17 @@ static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8
* @brief Send a gps2_rtk message
* @param chan MAVLink channel to send the message
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
*/
@ -356,7 +356,7 @@ static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavl
/**
* @brief Get field time_last_baseline_ms from gps2_rtk message
*
* @return Time since boot of last baseline message received in ms.
* @return [ms] Time since boot of last baseline message received.
*/
static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg)
/**
* @brief Get field tow from gps2_rtk message
*
* @return GPS Time of Week of last baseline
* @return [ms] GPS Time of Week of last baseline
*/
static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg)
{
@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_
/**
* @brief Get field rtk_rate from gps2_rtk message
*
* @return Rate of baseline messages being received by GPS, in HZ
* @return [Hz] Rate of baseline messages being received by GPS
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg)
{
@ -426,7 +426,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* ms
/**
* @brief Get field baseline_coords_type from gps2_rtk message
*
* @return Coordinate system of baseline. 0 == ECEF, 1 == NED
* @return Coordinate system of baseline
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg)
{
@ -436,7 +436,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlin
/**
* @brief Get field baseline_a_mm from gps2_rtk message
*
* @return Current baseline in ECEF x or NED north component in mm.
* @return [mm] Current baseline in ECEF x or NED north component.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg)
{
@ -446,7 +446,7 @@ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_messa
/**
* @brief Get field baseline_b_mm from gps2_rtk message
*
* @return Current baseline in ECEF y or NED east component in mm.
* @return [mm] Current baseline in ECEF y or NED east component.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg)
{
@ -456,7 +456,7 @@ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_messa
/**
* @brief Get field baseline_c_mm from gps2_rtk message
*
* @return Current baseline in ECEF z or NED down component in mm.
* @return [mm] Current baseline in ECEF z or NED down component.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
MAVPACKED(
typedef struct __mavlink_gps_global_origin_t {
int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/
int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
}) mavlink_gps_global_origin_t;
int32_t latitude; /*< [degE7] Latitude (WGS84)*/
int32_t longitude; /*< [degE7] Longitude (WGS84)*/
int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/
} mavlink_gps_global_origin_t;
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12
@ -47,9 +47,9 @@ typedef struct __mavlink_gps_global_origin_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_
* @brief Send a gps_global_origin message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -216,7 +216,7 @@ static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msg
/**
* @brief Get field latitude from gps_global_origin message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg)
{
@ -226,7 +226,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_m
/**
* @brief Get field longitude from gps_global_origin message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg)
{
@ -236,7 +236,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_
/**
* @brief Get field altitude from gps_global_origin message
*
* @return Altitude (AMSL), in meters * 1000 (positive for up)
* @return [mm] Altitude (MSL). Positive for up.
*/
static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123
MAVPACKED(
typedef struct __mavlink_gps_inject_data_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t len; /*< data length*/
uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/
}) mavlink_gps_inject_data_t;
uint8_t len; /*< [bytes] Data length*/
uint8_t data[110]; /*< Raw data (110 is enough for 12 satellites of RTCMv2)*/
} mavlink_gps_inject_data_t;
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN 113
@ -52,8 +52,8 @@ typedef struct __mavlink_gps_inject_data_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
* @param len [bytes] Data length
* @param data Raw data (110 is enough for 12 satellites of RTCMv2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -87,8 +87,8 @@ static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
* @param len [bytes] Data length
* @param data Raw data (110 is enough for 12 satellites of RTCMv2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -148,8 +148,8 @@ static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id
*
* @param target_system System ID
* @param target_component Component ID
* @param len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
* @param len [bytes] Data length
* @param data Raw data (110 is enough for 12 satellites of RTCMv2)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mav
/**
* @brief Get field len from gps_inject_data message
*
* @return data length
* @return [bytes] Data length
*/
static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg)
{
@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_
/**
* @brief Get field data from gps_inject_data message
*
* @return raw data (110 is enough for 12 satellites of RTCMv2)
* @return Raw data (110 is enough for 12 satellites of RTCMv2)
*/
static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data)
{

View file

@ -3,27 +3,27 @@
#define MAVLINK_MSG_ID_GPS_INPUT 232
MAVPACKED(
typedef struct __mavlink_gps_input_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
uint32_t time_week_ms; /*< GPS time (milliseconds from start of GPS week)*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
float alt; /*< Altitude (AMSL, not WGS84), in m (positive for up)*/
float hdop; /*< GPS HDOP horizontal dilution of position in m*/
float vdop; /*< GPS VDOP vertical dilution of position in m*/
float vn; /*< GPS velocity in m/s in NORTH direction in earth-fixed NED frame*/
float ve; /*< GPS velocity in m/s in EAST direction in earth-fixed NED frame*/
float vd; /*< GPS velocity in m/s in DOWN direction in earth-fixed NED frame*/
float speed_accuracy; /*< GPS speed accuracy in m/s*/
float horiz_accuracy; /*< GPS horizontal accuracy in m*/
float vert_accuracy; /*< GPS vertical accuracy in m*/
uint16_t ignore_flags; /*< Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
float alt; /*< [m] Altitude (MSL). Positive for up.*/
float hdop; /*< [m] GPS HDOP horizontal dilution of position*/
float vdop; /*< [m] GPS VDOP vertical dilution of position*/
float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/
float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/
float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/
float speed_accuracy; /*< [m/s] GPS speed accuracy*/
float horiz_accuracy; /*< [m] GPS horizontal accuracy*/
float vert_accuracy; /*< [m] GPS vertical accuracy*/
uint16_t ignore_flags; /*< Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.*/
uint16_t time_week; /*< GPS week number*/
uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/
uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/
uint8_t satellites_visible; /*< Number of satellites visible.*/
}) mavlink_gps_input_t;
} mavlink_gps_input_t;
#define MAVLINK_MSG_ID_GPS_INPUT_LEN 63
#define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63
@ -41,7 +41,11 @@ typedef struct __mavlink_gps_input_t {
"GPS_INPUT", \
18, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
{ "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
{ "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
@ -53,10 +57,6 @@ typedef struct __mavlink_gps_input_t {
{ "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
{ "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
{ "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
{ "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
} \
}
@ -65,7 +65,11 @@ typedef struct __mavlink_gps_input_t {
"GPS_INPUT", \
18, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
{ "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
{ "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
@ -77,10 +81,6 @@ typedef struct __mavlink_gps_input_t {
{ "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
{ "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
{ "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
{ "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
} \
}
@ -92,23 +92,23 @@ typedef struct __mavlink_gps_input_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param gps_id ID of the GPS for multiple GPS inputs
* @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.
* @param time_week_ms GPS time (milliseconds from start of GPS week)
* @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
* @param time_week_ms [ms] GPS time (from start of GPS week)
* @param time_week GPS week number
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in m (positive for up)
* @param hdop GPS HDOP horizontal dilution of position in m
* @param vdop GPS VDOP vertical dilution of position in m
* @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame
* @param speed_accuracy GPS speed accuracy in m/s
* @param horiz_accuracy GPS horizontal accuracy in m
* @param vert_accuracy GPS vertical accuracy in m
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
* @param speed_accuracy [m/s] GPS speed accuracy
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -171,23 +171,23 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param gps_id ID of the GPS for multiple GPS inputs
* @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.
* @param time_week_ms GPS time (milliseconds from start of GPS week)
* @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
* @param time_week_ms [ms] GPS time (from start of GPS week)
* @param time_week GPS week number
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in m (positive for up)
* @param hdop GPS HDOP horizontal dilution of position in m
* @param vdop GPS VDOP vertical dilution of position in m
* @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame
* @param speed_accuracy GPS speed accuracy in m/s
* @param horiz_accuracy GPS horizontal accuracy in m
* @param vert_accuracy GPS vertical accuracy in m
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
* @param speed_accuracy [m/s] GPS speed accuracy
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -276,23 +276,23 @@ static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint
* @brief Send a gps_input message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param gps_id ID of the GPS for multiple GPS inputs
* @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.
* @param time_week_ms GPS time (milliseconds from start of GPS week)
* @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
* @param time_week_ms [ms] GPS time (from start of GPS week)
* @param time_week GPS week number
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in m (positive for up)
* @param hdop GPS HDOP horizontal dilution of position in m
* @param vdop GPS VDOP vertical dilution of position in m
* @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame
* @param speed_accuracy GPS speed accuracy in m/s
* @param horiz_accuracy GPS horizontal accuracy in m
* @param vert_accuracy GPS vertical accuracy in m
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
* @param speed_accuracy [m/s] GPS speed accuracy
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -426,7 +426,7 @@ static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mav
/**
* @brief Get field time_usec from gps_input message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg)
{
@ -446,7 +446,7 @@ static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t*
/**
* @brief Get field ignore_flags from gps_input message
*
* @return Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.
* @return Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
*/
static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg)
{
@ -456,7 +456,7 @@ static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_mess
/**
* @brief Get field time_week_ms from gps_input message
*
* @return GPS time (milliseconds from start of GPS week)
* @return [ms] GPS time (from start of GPS week)
*/
static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg)
{
@ -486,7 +486,7 @@ static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t
/**
* @brief Get field lat from gps_input message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg)
{
@ -496,7 +496,7 @@ static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg
/**
* @brief Get field lon from gps_input message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg)
{
@ -506,7 +506,7 @@ static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg
/**
* @brief Get field alt from gps_input message
*
* @return Altitude (AMSL, not WGS84), in m (positive for up)
* @return [m] Altitude (MSL). Positive for up.
*/
static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg)
{
@ -516,7 +516,7 @@ static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field hdop from gps_input message
*
* @return GPS HDOP horizontal dilution of position in m
* @return [m] GPS HDOP horizontal dilution of position
*/
static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
{
@ -526,7 +526,7 @@ static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
/**
* @brief Get field vdop from gps_input message
*
* @return GPS VDOP vertical dilution of position in m
* @return [m] GPS VDOP vertical dilution of position
*/
static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg)
{
@ -536,7 +536,7 @@ static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg)
/**
* @brief Get field vn from gps_input message
*
* @return GPS velocity in m/s in NORTH direction in earth-fixed NED frame
* @return [m/s] GPS velocity in north direction in earth-fixed NED frame
*/
static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg)
{
@ -546,7 +546,7 @@ static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg)
/**
* @brief Get field ve from gps_input message
*
* @return GPS velocity in m/s in EAST direction in earth-fixed NED frame
* @return [m/s] GPS velocity in east direction in earth-fixed NED frame
*/
static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg)
{
@ -556,7 +556,7 @@ static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg)
/**
* @brief Get field vd from gps_input message
*
* @return GPS velocity in m/s in DOWN direction in earth-fixed NED frame
* @return [m/s] GPS velocity in down direction in earth-fixed NED frame
*/
static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg)
{
@ -566,7 +566,7 @@ static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg)
/**
* @brief Get field speed_accuracy from gps_input message
*
* @return GPS speed accuracy in m/s
* @return [m/s] GPS speed accuracy
*/
static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg)
{
@ -576,7 +576,7 @@ static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_messa
/**
* @brief Get field horiz_accuracy from gps_input message
*
* @return GPS horizontal accuracy in m
* @return [m] GPS horizontal accuracy
*/
static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg)
{
@ -586,7 +586,7 @@ static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_messa
/**
* @brief Get field vert_accuracy from gps_input message
*
* @return GPS vertical accuracy in m
* @return [m] GPS vertical accuracy
*/
static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg)
{

View file

@ -3,19 +3,19 @@
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
MAVPACKED(
typedef struct __mavlink_gps_raw_int_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84, EGM96 ellipsoid)*/
int32_t lon; /*< [degE7] Longitude (WGS84, EGM96 ellipsoid)*/
int32_t alt; /*< [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/
uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/
uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< GPS fix type.*/
uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
}) mavlink_gps_raw_int_t;
} mavlink_gps_raw_int_t;
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
@ -33,6 +33,7 @@ typedef struct __mavlink_gps_raw_int_t {
"GPS_RAW_INT", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
@ -40,7 +41,6 @@ typedef struct __mavlink_gps_raw_int_t {
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
} \
}
@ -49,6 +49,7 @@ typedef struct __mavlink_gps_raw_int_t {
"GPS_RAW_INT", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
@ -56,7 +57,6 @@ typedef struct __mavlink_gps_raw_int_t {
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
} \
}
@ -68,15 +68,15 @@ typedef struct __mavlink_gps_raw_int_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
* @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
* @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -123,15 +123,15 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
* @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
* @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -204,15 +204,15 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui
* @brief Send a gps_raw_int message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type GPS fix type.
* @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
* @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
* @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -314,7 +314,7 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m
/**
* @brief Get field time_usec from gps_raw_int message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
{
@ -324,7 +324,7 @@ static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_messa
/**
* @brief Get field fix_type from gps_raw_int message
*
* @return See the GPS_FIX_TYPE enum.
* @return GPS fix type.
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
@ -334,7 +334,7 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message
/**
* @brief Get field lat from gps_raw_int message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84, EGM96 ellipsoid)
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
@ -344,7 +344,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* m
/**
* @brief Get field lon from gps_raw_int message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84, EGM96 ellipsoid)
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
@ -354,7 +354,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* m
/**
* @brief Get field alt from gps_raw_int message
*
* @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t*
/**
* @brief Get field vel from gps_raw_int message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
{
@ -394,7 +394,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t*
/**
* @brief Get field cog from gps_raw_int message
*
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_GPS_RTCM_DATA 233
MAVPACKED(
typedef struct __mavlink_gps_rtcm_data_t {
uint8_t flags; /*< LSB: 1 means message is fragmented*/
uint8_t len; /*< data length*/
uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/
uint8_t len; /*< [bytes] data length*/
uint8_t data[180]; /*< RTCM message (may be fragmented)*/
}) mavlink_gps_rtcm_data_t;
} mavlink_gps_rtcm_data_t;
#define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182
#define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182
@ -47,8 +47,8 @@ typedef struct __mavlink_gps_rtcm_data_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param flags LSB: 1 means message is fragmented
* @param len data length
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len [bytes] data length
* @param data RTCM message (may be fragmented)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -79,8 +79,8 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param flags LSB: 1 means message is fragmented
* @param len data length
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len [bytes] data length
* @param data RTCM message (may be fragmented)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -137,8 +137,8 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id,
* @brief Send a gps_rtcm_data message
* @param chan MAVLink channel to send the message
*
* @param flags LSB: 1 means message is fragmented
* @param len data length
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len [bytes] data length
* @param data RTCM message (may be fragmented)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -208,7 +208,7 @@ static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field flags from gps_rtcm_data message
*
* @return LSB: 1 means message is fragmented
* @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
*/
static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg)
{
@ -218,7 +218,7 @@ static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_
/**
* @brief Get field len from gps_rtcm_data message
*
* @return data length
* @return [bytes] data length
*/
static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* msg)
{

View file

@ -3,22 +3,22 @@
#define MAVLINK_MSG_ID_GPS_RTK 127
MAVPACKED(
typedef struct __mavlink_gps_rtk_t {
uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/
uint32_t tow; /*< GPS Time of Week of last baseline*/
int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/
int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/
int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/
uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/
uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/
int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/
int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/
int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/
uint32_t accuracy; /*< Current estimate of baseline accuracy.*/
int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/
uint16_t wn; /*< GPS Week Number of last baseline*/
uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/
uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/
uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/
uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/
uint8_t nsats; /*< Current number of sats used for RTK calculation.*/
uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/
}) mavlink_gps_rtk_t;
uint8_t baseline_coords_type; /*< Coordinate system of baseline*/
} mavlink_gps_rtk_t;
#define MAVLINK_MSG_ID_GPS_RTK_LEN 35
#define MAVLINK_MSG_ID_GPS_RTK_MIN_LEN 35
@ -36,18 +36,18 @@ typedef struct __mavlink_gps_rtk_t {
"GPS_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \
} \
}
#else
@ -55,18 +55,18 @@ typedef struct __mavlink_gps_rtk_t {
"GPS_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \
} \
}
#endif
@ -77,17 +77,17 @@ typedef struct __mavlink_gps_rtk_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
@ -141,17 +141,17 @@ static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t compo
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
@ -231,17 +231,17 @@ static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_
* @brief Send a gps_rtk message
* @param chan MAVLink channel to send the message
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param time_last_baseline_ms [ms] Time since boot of last baseline message received.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param tow [ms] GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param rtk_rate [Hz] Rate of baseline messages being received by GPS
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param baseline_coords_type Coordinate system of baseline
* @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component.
* @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component.
* @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
*/
@ -356,7 +356,7 @@ static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavli
/**
* @brief Get field time_last_baseline_ms from gps_rtk message
*
* @return Time since boot of last baseline message received in ms.
* @return [ms] Time since boot of last baseline message received.
*/
static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg)
/**
* @brief Get field tow from gps_rtk message
*
* @return GPS Time of Week of last baseline
* @return [ms] GPS Time of Week of last baseline
*/
static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg)
{
@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t
/**
* @brief Get field rtk_rate from gps_rtk message
*
* @return Rate of baseline messages being received by GPS, in HZ
* @return [Hz] Rate of baseline messages being received by GPS
*/
static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg)
{
@ -426,7 +426,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg
/**
* @brief Get field baseline_coords_type from gps_rtk message
*
* @return Coordinate system of baseline. 0 == ECEF, 1 == NED
* @return Coordinate system of baseline
*/
static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg)
{
@ -436,7 +436,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink
/**
* @brief Get field baseline_a_mm from gps_rtk message
*
* @return Current baseline in ECEF x or NED north component in mm.
* @return [mm] Current baseline in ECEF x or NED north component.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg)
{
@ -446,7 +446,7 @@ static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_messag
/**
* @brief Get field baseline_b_mm from gps_rtk message
*
* @return Current baseline in ECEF y or NED east component in mm.
* @return [mm] Current baseline in ECEF y or NED east component.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg)
{
@ -456,7 +456,7 @@ static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_messag
/**
* @brief Get field baseline_c_mm from gps_rtk message
*
* @return Current baseline in ECEF z or NED down component in mm.
* @return [mm] Current baseline in ECEF z or NED down component.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg)
{

View file

@ -3,15 +3,15 @@
#define MAVLINK_MSG_ID_GPS_STATUS 25
MAVPACKED(
typedef struct __mavlink_gps_status_t {
uint8_t satellites_visible; /*< Number of satellites visible*/
uint8_t satellite_prn[20]; /*< Global satellite ID*/
uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/
uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/
uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/
uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/
}) mavlink_gps_status_t;
uint8_t satellite_elevation[20]; /*< [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/
uint8_t satellite_azimuth[20]; /*< [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.*/
uint8_t satellite_snr[20]; /*< [dB] Signal to noise ratio of satellite*/
} mavlink_gps_status_t;
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101
@ -63,9 +63,9 @@ typedef struct __mavlink_gps_status_t {
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr [dB] Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -104,9 +104,9 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr [dB] Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -171,9 +171,9 @@ static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uin
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr [dB] Signal to noise ratio of satellite
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -284,7 +284,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_m
/**
* @brief Get field satellite_elevation from gps_status message
*
* @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @return [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
{
@ -294,7 +294,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavl
/**
* @brief Get field satellite_azimuth from gps_status message
*
* @return Direction of satellite, 0: 0 deg, 255: 360 deg.
* @return [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
{
@ -304,7 +304,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlin
/**
* @brief Get field satellite_snr from gps_status message
*
* @return Signal to noise ratio of satellite
* @return [dB] Signal to noise ratio of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
{

View file

@ -3,15 +3,15 @@
#define MAVLINK_MSG_ID_HEARTBEAT 0
MAVPACKED(
typedef struct __mavlink_heartbeat_t {
uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/
uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/
uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/
uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/
uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/
uint8_t type; /*< Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.*/
uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/
uint8_t base_mode; /*< System mode bitmap.*/
uint8_t system_status; /*< System status flag.*/
uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/
}) mavlink_heartbeat_t;
} mavlink_heartbeat_t;
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9
@ -28,10 +28,10 @@ typedef struct __mavlink_heartbeat_t {
0, \
"HEARTBEAT", \
6, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
@ -40,10 +40,10 @@ typedef struct __mavlink_heartbeat_t {
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
"HEARTBEAT", \
6, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
@ -56,11 +56,11 @@ typedef struct __mavlink_heartbeat_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
* @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -98,11 +98,11 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
* @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -166,11 +166,11 @@ static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
* @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -255,7 +255,7 @@ static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mav
/**
* @brief Get field type from heartbeat message
*
* @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @return Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
@ -265,7 +265,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms
/**
* @brief Get field autopilot from heartbeat message
*
* @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
@ -275,7 +275,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_
/**
* @brief Get field base_mode from heartbeat message
*
* @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @return System mode bitmap.
*/
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{
@ -285,7 +285,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_
/**
* @brief Get field custom_mode from heartbeat message
*
* @return A bitfield for use for autopilot-specific flags.
* @return A bitfield for use for autopilot-specific flags
*/
static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
{
@ -295,7 +295,7 @@ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa
/**
* @brief Get field system_status from heartbeat message
*
* @return System status flag, see MAV_STATE ENUM
* @return System status flag.
*/
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{

View file

@ -3,33 +3,33 @@
#define MAVLINK_MSG_ID_HIGH_LATENCY 234
MAVPACKED(
typedef struct __mavlink_high_latency_t {
uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
int32_t latitude; /*< Latitude, expressed as degrees * 1E7*/
int32_t longitude; /*< Longitude, expressed as degrees * 1E7*/
int16_t roll; /*< roll (centidegrees)*/
int16_t pitch; /*< pitch (centidegrees)*/
uint16_t heading; /*< heading (centidegrees)*/
int16_t heading_sp; /*< heading setpoint (centidegrees)*/
int16_t altitude_amsl; /*< Altitude above mean sea level (meters)*/
int16_t altitude_sp; /*< Altitude setpoint relative to the home position (meters)*/
uint16_t wp_distance; /*< distance to target (meters)*/
uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/
int32_t latitude; /*< [degE7] Latitude*/
int32_t longitude; /*< [degE7] Longitude*/
int16_t roll; /*< [cdeg] roll*/
int16_t pitch; /*< [cdeg] pitch*/
uint16_t heading; /*< [cdeg] heading*/
int16_t heading_sp; /*< [cdeg] heading setpoint*/
int16_t altitude_amsl; /*< [m] Altitude above mean sea level*/
int16_t altitude_sp; /*< [m] Altitude setpoint relative to the home position*/
uint16_t wp_distance; /*< [m] distance to target*/
uint8_t base_mode; /*< Bitmap of enabled system modes.*/
uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/
int8_t throttle; /*< throttle (percentage)*/
uint8_t airspeed; /*< airspeed (m/s)*/
uint8_t airspeed_sp; /*< airspeed setpoint (m/s)*/
uint8_t groundspeed; /*< groundspeed (m/s)*/
int8_t climb_rate; /*< climb rate (m/s)*/
int8_t throttle; /*< [%] throttle (percentage)*/
uint8_t airspeed; /*< [m/s] airspeed*/
uint8_t airspeed_sp; /*< [m/s] airspeed setpoint*/
uint8_t groundspeed; /*< [m/s] groundspeed*/
int8_t climb_rate; /*< [m/s] climb rate*/
uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to 255*/
uint8_t gps_fix_type; /*< See the GPS_FIX_TYPE enum.*/
uint8_t battery_remaining; /*< Remaining battery (percentage)*/
int8_t temperature; /*< Autopilot temperature (degrees C)*/
int8_t temperature_air; /*< Air temperature (degrees C) from airspeed sensor*/
uint8_t gps_fix_type; /*< GPS Fix type.*/
uint8_t battery_remaining; /*< [%] Remaining battery (percentage)*/
int8_t temperature; /*< [degC] Autopilot temperature (degrees C)*/
int8_t temperature_air; /*< [degC] Air temperature (degrees C) from airspeed sensor*/
uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/
uint8_t wp_num; /*< current waypoint number*/
}) mavlink_high_latency_t;
} mavlink_high_latency_t;
#define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40
#define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40
@ -46,19 +46,18 @@ typedef struct __mavlink_high_latency_t {
234, \
"HIGH_LATENCY", \
24, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
{ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
{ "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \
{ "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
{ "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
{ "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \
{ "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \
{ "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
{ "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
{ "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \
{ "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \
@ -70,25 +69,25 @@ typedef struct __mavlink_high_latency_t {
{ "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \
{ "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \
{ "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \
{ "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \
"HIGH_LATENCY", \
24, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
{ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
{ "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \
{ "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
{ "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
{ "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \
{ "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \
{ "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
{ "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
{ "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \
{ "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \
@ -100,6 +99,7 @@ typedef struct __mavlink_high_latency_t {
{ "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \
{ "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \
{ "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \
{ "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
} \
}
#endif
@ -110,30 +110,30 @@ typedef struct __mavlink_high_latency_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param base_mode Bitmap of enabled system modes.
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @param roll roll (centidegrees)
* @param pitch pitch (centidegrees)
* @param heading heading (centidegrees)
* @param throttle throttle (percentage)
* @param heading_sp heading setpoint (centidegrees)
* @param latitude Latitude, expressed as degrees * 1E7
* @param longitude Longitude, expressed as degrees * 1E7
* @param altitude_amsl Altitude above mean sea level (meters)
* @param altitude_sp Altitude setpoint relative to the home position (meters)
* @param airspeed airspeed (m/s)
* @param airspeed_sp airspeed setpoint (m/s)
* @param groundspeed groundspeed (m/s)
* @param climb_rate climb rate (m/s)
* @param roll [cdeg] roll
* @param pitch [cdeg] pitch
* @param heading [cdeg] heading
* @param throttle [%] throttle (percentage)
* @param heading_sp [cdeg] heading setpoint
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude_amsl [m] Altitude above mean sea level
* @param altitude_sp [m] Altitude setpoint relative to the home position
* @param airspeed [m/s] airspeed
* @param airspeed_sp [m/s] airspeed setpoint
* @param groundspeed [m/s] groundspeed
* @param climb_rate [m/s] climb rate
* @param gps_nsat Number of satellites visible. If unknown, set to 255
* @param gps_fix_type See the GPS_FIX_TYPE enum.
* @param battery_remaining Remaining battery (percentage)
* @param temperature Autopilot temperature (degrees C)
* @param temperature_air Air temperature (degrees C) from airspeed sensor
* @param gps_fix_type GPS Fix type.
* @param battery_remaining [%] Remaining battery (percentage)
* @param temperature [degC] Autopilot temperature (degrees C)
* @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
* @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
* @param wp_num current waypoint number
* @param wp_distance distance to target (meters)
* @param wp_distance [m] distance to target
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -207,30 +207,30 @@ static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param base_mode Bitmap of enabled system modes.
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @param roll roll (centidegrees)
* @param pitch pitch (centidegrees)
* @param heading heading (centidegrees)
* @param throttle throttle (percentage)
* @param heading_sp heading setpoint (centidegrees)
* @param latitude Latitude, expressed as degrees * 1E7
* @param longitude Longitude, expressed as degrees * 1E7
* @param altitude_amsl Altitude above mean sea level (meters)
* @param altitude_sp Altitude setpoint relative to the home position (meters)
* @param airspeed airspeed (m/s)
* @param airspeed_sp airspeed setpoint (m/s)
* @param groundspeed groundspeed (m/s)
* @param climb_rate climb rate (m/s)
* @param roll [cdeg] roll
* @param pitch [cdeg] pitch
* @param heading [cdeg] heading
* @param throttle [%] throttle (percentage)
* @param heading_sp [cdeg] heading setpoint
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude_amsl [m] Altitude above mean sea level
* @param altitude_sp [m] Altitude setpoint relative to the home position
* @param airspeed [m/s] airspeed
* @param airspeed_sp [m/s] airspeed setpoint
* @param groundspeed [m/s] groundspeed
* @param climb_rate [m/s] climb rate
* @param gps_nsat Number of satellites visible. If unknown, set to 255
* @param gps_fix_type See the GPS_FIX_TYPE enum.
* @param battery_remaining Remaining battery (percentage)
* @param temperature Autopilot temperature (degrees C)
* @param temperature_air Air temperature (degrees C) from airspeed sensor
* @param gps_fix_type GPS Fix type.
* @param battery_remaining [%] Remaining battery (percentage)
* @param temperature [degC] Autopilot temperature (degrees C)
* @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
* @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
* @param wp_num current waypoint number
* @param wp_distance distance to target (meters)
* @param wp_distance [m] distance to target
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -330,30 +330,30 @@ static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, u
* @brief Send a high_latency message
* @param chan MAVLink channel to send the message
*
* @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param base_mode Bitmap of enabled system modes.
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @param roll roll (centidegrees)
* @param pitch pitch (centidegrees)
* @param heading heading (centidegrees)
* @param throttle throttle (percentage)
* @param heading_sp heading setpoint (centidegrees)
* @param latitude Latitude, expressed as degrees * 1E7
* @param longitude Longitude, expressed as degrees * 1E7
* @param altitude_amsl Altitude above mean sea level (meters)
* @param altitude_sp Altitude setpoint relative to the home position (meters)
* @param airspeed airspeed (m/s)
* @param airspeed_sp airspeed setpoint (m/s)
* @param groundspeed groundspeed (m/s)
* @param climb_rate climb rate (m/s)
* @param roll [cdeg] roll
* @param pitch [cdeg] pitch
* @param heading [cdeg] heading
* @param throttle [%] throttle (percentage)
* @param heading_sp [cdeg] heading setpoint
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude_amsl [m] Altitude above mean sea level
* @param altitude_sp [m] Altitude setpoint relative to the home position
* @param airspeed [m/s] airspeed
* @param airspeed_sp [m/s] airspeed setpoint
* @param groundspeed [m/s] groundspeed
* @param climb_rate [m/s] climb rate
* @param gps_nsat Number of satellites visible. If unknown, set to 255
* @param gps_fix_type See the GPS_FIX_TYPE enum.
* @param battery_remaining Remaining battery (percentage)
* @param temperature Autopilot temperature (degrees C)
* @param temperature_air Air temperature (degrees C) from airspeed sensor
* @param gps_fix_type GPS Fix type.
* @param battery_remaining [%] Remaining battery (percentage)
* @param temperature [degC] Autopilot temperature (degrees C)
* @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
* @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
* @param wp_num current waypoint number
* @param wp_distance distance to target (meters)
* @param wp_distance [m] distance to target
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -510,7 +510,7 @@ static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field base_mode from high_latency message
*
* @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @return Bitmap of enabled system modes.
*/
static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg)
{
@ -540,7 +540,7 @@ static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_me
/**
* @brief Get field roll from high_latency message
*
* @return roll (centidegrees)
* @return [cdeg] roll
*/
static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg)
{
@ -550,7 +550,7 @@ static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t*
/**
* @brief Get field pitch from high_latency message
*
* @return pitch (centidegrees)
* @return [cdeg] pitch
*/
static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg)
{
@ -560,7 +560,7 @@ static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t
/**
* @brief Get field heading from high_latency message
*
* @return heading (centidegrees)
* @return [cdeg] heading
*/
static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg)
{
@ -570,7 +570,7 @@ static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_messag
/**
* @brief Get field throttle from high_latency message
*
* @return throttle (percentage)
* @return [%] throttle (percentage)
*/
static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg)
{
@ -580,7 +580,7 @@ static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message
/**
* @brief Get field heading_sp from high_latency message
*
* @return heading setpoint (centidegrees)
* @return [cdeg] heading setpoint
*/
static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg)
{
@ -590,7 +590,7 @@ static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_mess
/**
* @brief Get field latitude from high_latency message
*
* @return Latitude, expressed as degrees * 1E7
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg)
{
@ -600,7 +600,7 @@ static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_messag
/**
* @brief Get field longitude from high_latency message
*
* @return Longitude, expressed as degrees * 1E7
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg)
{
@ -610,7 +610,7 @@ static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_messa
/**
* @brief Get field altitude_amsl from high_latency message
*
* @return Altitude above mean sea level (meters)
* @return [m] Altitude above mean sea level
*/
static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg)
{
@ -620,7 +620,7 @@ static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_m
/**
* @brief Get field altitude_sp from high_latency message
*
* @return Altitude setpoint relative to the home position (meters)
* @return [m] Altitude setpoint relative to the home position
*/
static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg)
{
@ -630,7 +630,7 @@ static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_mes
/**
* @brief Get field airspeed from high_latency message
*
* @return airspeed (m/s)
* @return [m/s] airspeed
*/
static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg)
{
@ -640,7 +640,7 @@ static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_messag
/**
* @brief Get field airspeed_sp from high_latency message
*
* @return airspeed setpoint (m/s)
* @return [m/s] airspeed setpoint
*/
static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg)
{
@ -650,7 +650,7 @@ static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_mes
/**
* @brief Get field groundspeed from high_latency message
*
* @return groundspeed (m/s)
* @return [m/s] groundspeed
*/
static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg)
{
@ -660,7 +660,7 @@ static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_mes
/**
* @brief Get field climb_rate from high_latency message
*
* @return climb rate (m/s)
* @return [m/s] climb rate
*/
static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg)
{
@ -680,7 +680,7 @@ static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_messag
/**
* @brief Get field gps_fix_type from high_latency message
*
* @return See the GPS_FIX_TYPE enum.
* @return GPS Fix type.
*/
static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg)
{
@ -690,7 +690,7 @@ static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_me
/**
* @brief Get field battery_remaining from high_latency message
*
* @return Remaining battery (percentage)
* @return [%] Remaining battery (percentage)
*/
static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg)
{
@ -700,7 +700,7 @@ static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavli
/**
* @brief Get field temperature from high_latency message
*
* @return Autopilot temperature (degrees C)
* @return [degC] Autopilot temperature (degrees C)
*/
static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg)
{
@ -710,7 +710,7 @@ static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_mess
/**
* @brief Get field temperature_air from high_latency message
*
* @return Air temperature (degrees C) from airspeed sensor
* @return [degC] Air temperature (degrees C) from airspeed sensor
*/
static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg)
{
@ -740,7 +740,7 @@ static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_
/**
* @brief Get field wp_distance from high_latency message
*
* @return distance to target (meters)
* @return [m] distance to target
*/
static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,863 @@
#pragma once
// MESSAGE HIGH_LATENCY2 PACKING
#define MAVLINK_MSG_ID_HIGH_LATENCY2 235
typedef struct __mavlink_high_latency2_t {
uint32_t timestamp; /*< [ms] Timestamp (milliseconds since boot or Unix epoch)*/
int32_t latitude; /*< [degE7] Latitude*/
int32_t longitude; /*< [degE7] Longitude*/
uint16_t custom_mode; /*< A bitfield for use for autopilot-specific flags (2 byte version).*/
int16_t altitude; /*< [m] Altitude above mean sea level*/
int16_t target_altitude; /*< [m] Altitude setpoint*/
uint16_t target_distance; /*< [dam] Distance to target waypoint or position*/
uint16_t wp_num; /*< Current waypoint number*/
uint16_t failure_flags; /*< Bitmap of failure flags.*/
uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc.)*/
uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/
uint8_t heading; /*< [deg/2] Heading*/
uint8_t target_heading; /*< [deg/2] Heading setpoint*/
uint8_t throttle; /*< [%] Throttle*/
uint8_t airspeed; /*< [m/s*5] Airspeed*/
uint8_t airspeed_sp; /*< [m/s*5] Airspeed setpoint*/
uint8_t groundspeed; /*< [m/s*5] Groundspeed*/
uint8_t windspeed; /*< [m/s*5] Windspeed*/
uint8_t wind_heading; /*< [deg/2] Wind heading*/
uint8_t eph; /*< [dm] Maximum error horizontal position since last message*/
uint8_t epv; /*< [dm] Maximum error vertical position since last message*/
int8_t temperature_air; /*< [degC] Air temperature from airspeed sensor*/
int8_t climb_rate; /*< [dm/s] Maximum climb rate magnitude since last message*/
int8_t battery; /*< [%] Battery level (-1 if field not provided).*/
int8_t custom0; /*< Field for custom payload.*/
int8_t custom1; /*< Field for custom payload.*/
int8_t custom2; /*< Field for custom payload.*/
} mavlink_high_latency2_t;
#define MAVLINK_MSG_ID_HIGH_LATENCY2_LEN 42
#define MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN 42
#define MAVLINK_MSG_ID_235_LEN 42
#define MAVLINK_MSG_ID_235_MIN_LEN 42
#define MAVLINK_MSG_ID_HIGH_LATENCY2_CRC 179
#define MAVLINK_MSG_ID_235_CRC 179
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \
235, \
"HIGH_LATENCY2", \
27, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \
{ "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \
{ "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \
{ "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \
{ "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \
{ "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \
{ "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \
{ "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \
{ "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \
{ "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \
{ "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \
{ "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \
{ "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \
{ "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \
{ "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \
{ "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \
"HIGH_LATENCY2", \
27, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \
{ "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \
{ "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \
{ "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \
{ "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \
{ "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \
{ "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \
{ "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \
{ "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \
{ "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \
{ "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \
{ "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \
{ "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \
{ "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \
{ "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \
{ "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \
} \
}
#endif
/**
* @brief Pack a high_latency2 message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
* @param type Type of the MAV (quadrotor, helicopter, etc.)
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude [m] Altitude above mean sea level
* @param target_altitude [m] Altitude setpoint
* @param heading [deg/2] Heading
* @param target_heading [deg/2] Heading setpoint
* @param target_distance [dam] Distance to target waypoint or position
* @param throttle [%] Throttle
* @param airspeed [m/s*5] Airspeed
* @param airspeed_sp [m/s*5] Airspeed setpoint
* @param groundspeed [m/s*5] Groundspeed
* @param windspeed [m/s*5] Windspeed
* @param wind_heading [deg/2] Wind heading
* @param eph [dm] Maximum error horizontal position since last message
* @param epv [dm] Maximum error vertical position since last message
* @param temperature_air [degC] Air temperature from airspeed sensor
* @param climb_rate [dm/s] Maximum climb rate magnitude since last message
* @param battery [%] Battery level (-1 if field not provided).
* @param wp_num Current waypoint number
* @param failure_flags Bitmap of failure flags.
* @param custom0 Field for custom payload.
* @param custom1 Field for custom payload.
* @param custom2 Field for custom payload.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_high_latency2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_int32_t(buf, 4, latitude);
_mav_put_int32_t(buf, 8, longitude);
_mav_put_uint16_t(buf, 12, custom_mode);
_mav_put_int16_t(buf, 14, altitude);
_mav_put_int16_t(buf, 16, target_altitude);
_mav_put_uint16_t(buf, 18, target_distance);
_mav_put_uint16_t(buf, 20, wp_num);
_mav_put_uint16_t(buf, 22, failure_flags);
_mav_put_uint8_t(buf, 24, type);
_mav_put_uint8_t(buf, 25, autopilot);
_mav_put_uint8_t(buf, 26, heading);
_mav_put_uint8_t(buf, 27, target_heading);
_mav_put_uint8_t(buf, 28, throttle);
_mav_put_uint8_t(buf, 29, airspeed);
_mav_put_uint8_t(buf, 30, airspeed_sp);
_mav_put_uint8_t(buf, 31, groundspeed);
_mav_put_uint8_t(buf, 32, windspeed);
_mav_put_uint8_t(buf, 33, wind_heading);
_mav_put_uint8_t(buf, 34, eph);
_mav_put_uint8_t(buf, 35, epv);
_mav_put_int8_t(buf, 36, temperature_air);
_mav_put_int8_t(buf, 37, climb_rate);
_mav_put_int8_t(buf, 38, battery);
_mav_put_int8_t(buf, 39, custom0);
_mav_put_int8_t(buf, 40, custom1);
_mav_put_int8_t(buf, 41, custom2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN);
#else
mavlink_high_latency2_t packet;
packet.timestamp = timestamp;
packet.latitude = latitude;
packet.longitude = longitude;
packet.custom_mode = custom_mode;
packet.altitude = altitude;
packet.target_altitude = target_altitude;
packet.target_distance = target_distance;
packet.wp_num = wp_num;
packet.failure_flags = failure_flags;
packet.type = type;
packet.autopilot = autopilot;
packet.heading = heading;
packet.target_heading = target_heading;
packet.throttle = throttle;
packet.airspeed = airspeed;
packet.airspeed_sp = airspeed_sp;
packet.groundspeed = groundspeed;
packet.windspeed = windspeed;
packet.wind_heading = wind_heading;
packet.eph = eph;
packet.epv = epv;
packet.temperature_air = temperature_air;
packet.climb_rate = climb_rate;
packet.battery = battery;
packet.custom0 = custom0;
packet.custom1 = custom1;
packet.custom2 = custom2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
}
/**
* @brief Pack a high_latency2 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
* @param type Type of the MAV (quadrotor, helicopter, etc.)
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude [m] Altitude above mean sea level
* @param target_altitude [m] Altitude setpoint
* @param heading [deg/2] Heading
* @param target_heading [deg/2] Heading setpoint
* @param target_distance [dam] Distance to target waypoint or position
* @param throttle [%] Throttle
* @param airspeed [m/s*5] Airspeed
* @param airspeed_sp [m/s*5] Airspeed setpoint
* @param groundspeed [m/s*5] Groundspeed
* @param windspeed [m/s*5] Windspeed
* @param wind_heading [deg/2] Wind heading
* @param eph [dm] Maximum error horizontal position since last message
* @param epv [dm] Maximum error vertical position since last message
* @param temperature_air [degC] Air temperature from airspeed sensor
* @param climb_rate [dm/s] Maximum climb rate magnitude since last message
* @param battery [%] Battery level (-1 if field not provided).
* @param wp_num Current waypoint number
* @param failure_flags Bitmap of failure flags.
* @param custom0 Field for custom payload.
* @param custom1 Field for custom payload.
* @param custom2 Field for custom payload.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_high_latency2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t timestamp,uint8_t type,uint8_t autopilot,uint16_t custom_mode,int32_t latitude,int32_t longitude,int16_t altitude,int16_t target_altitude,uint8_t heading,uint8_t target_heading,uint16_t target_distance,uint8_t throttle,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,uint8_t windspeed,uint8_t wind_heading,uint8_t eph,uint8_t epv,int8_t temperature_air,int8_t climb_rate,int8_t battery,uint16_t wp_num,uint16_t failure_flags,int8_t custom0,int8_t custom1,int8_t custom2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_int32_t(buf, 4, latitude);
_mav_put_int32_t(buf, 8, longitude);
_mav_put_uint16_t(buf, 12, custom_mode);
_mav_put_int16_t(buf, 14, altitude);
_mav_put_int16_t(buf, 16, target_altitude);
_mav_put_uint16_t(buf, 18, target_distance);
_mav_put_uint16_t(buf, 20, wp_num);
_mav_put_uint16_t(buf, 22, failure_flags);
_mav_put_uint8_t(buf, 24, type);
_mav_put_uint8_t(buf, 25, autopilot);
_mav_put_uint8_t(buf, 26, heading);
_mav_put_uint8_t(buf, 27, target_heading);
_mav_put_uint8_t(buf, 28, throttle);
_mav_put_uint8_t(buf, 29, airspeed);
_mav_put_uint8_t(buf, 30, airspeed_sp);
_mav_put_uint8_t(buf, 31, groundspeed);
_mav_put_uint8_t(buf, 32, windspeed);
_mav_put_uint8_t(buf, 33, wind_heading);
_mav_put_uint8_t(buf, 34, eph);
_mav_put_uint8_t(buf, 35, epv);
_mav_put_int8_t(buf, 36, temperature_air);
_mav_put_int8_t(buf, 37, climb_rate);
_mav_put_int8_t(buf, 38, battery);
_mav_put_int8_t(buf, 39, custom0);
_mav_put_int8_t(buf, 40, custom1);
_mav_put_int8_t(buf, 41, custom2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN);
#else
mavlink_high_latency2_t packet;
packet.timestamp = timestamp;
packet.latitude = latitude;
packet.longitude = longitude;
packet.custom_mode = custom_mode;
packet.altitude = altitude;
packet.target_altitude = target_altitude;
packet.target_distance = target_distance;
packet.wp_num = wp_num;
packet.failure_flags = failure_flags;
packet.type = type;
packet.autopilot = autopilot;
packet.heading = heading;
packet.target_heading = target_heading;
packet.throttle = throttle;
packet.airspeed = airspeed;
packet.airspeed_sp = airspeed_sp;
packet.groundspeed = groundspeed;
packet.windspeed = windspeed;
packet.wind_heading = wind_heading;
packet.eph = eph;
packet.epv = epv;
packet.temperature_air = temperature_air;
packet.climb_rate = climb_rate;
packet.battery = battery;
packet.custom0 = custom0;
packet.custom1 = custom1;
packet.custom2 = custom2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
}
/**
* @brief Encode a high_latency2 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param high_latency2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_high_latency2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2)
{
return mavlink_msg_high_latency2_pack(system_id, component_id, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2);
}
/**
* @brief Encode a high_latency2 struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param high_latency2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_high_latency2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2)
{
return mavlink_msg_high_latency2_pack_chan(system_id, component_id, chan, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2);
}
/**
* @brief Send a high_latency2 message
* @param chan MAVLink channel to send the message
*
* @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
* @param type Type of the MAV (quadrotor, helicopter, etc.)
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
* @param latitude [degE7] Latitude
* @param longitude [degE7] Longitude
* @param altitude [m] Altitude above mean sea level
* @param target_altitude [m] Altitude setpoint
* @param heading [deg/2] Heading
* @param target_heading [deg/2] Heading setpoint
* @param target_distance [dam] Distance to target waypoint or position
* @param throttle [%] Throttle
* @param airspeed [m/s*5] Airspeed
* @param airspeed_sp [m/s*5] Airspeed setpoint
* @param groundspeed [m/s*5] Groundspeed
* @param windspeed [m/s*5] Windspeed
* @param wind_heading [deg/2] Wind heading
* @param eph [dm] Maximum error horizontal position since last message
* @param epv [dm] Maximum error vertical position since last message
* @param temperature_air [degC] Air temperature from airspeed sensor
* @param climb_rate [dm/s] Maximum climb rate magnitude since last message
* @param battery [%] Battery level (-1 if field not provided).
* @param wp_num Current waypoint number
* @param failure_flags Bitmap of failure flags.
* @param custom0 Field for custom payload.
* @param custom1 Field for custom payload.
* @param custom2 Field for custom payload.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_high_latency2_send(mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_int32_t(buf, 4, latitude);
_mav_put_int32_t(buf, 8, longitude);
_mav_put_uint16_t(buf, 12, custom_mode);
_mav_put_int16_t(buf, 14, altitude);
_mav_put_int16_t(buf, 16, target_altitude);
_mav_put_uint16_t(buf, 18, target_distance);
_mav_put_uint16_t(buf, 20, wp_num);
_mav_put_uint16_t(buf, 22, failure_flags);
_mav_put_uint8_t(buf, 24, type);
_mav_put_uint8_t(buf, 25, autopilot);
_mav_put_uint8_t(buf, 26, heading);
_mav_put_uint8_t(buf, 27, target_heading);
_mav_put_uint8_t(buf, 28, throttle);
_mav_put_uint8_t(buf, 29, airspeed);
_mav_put_uint8_t(buf, 30, airspeed_sp);
_mav_put_uint8_t(buf, 31, groundspeed);
_mav_put_uint8_t(buf, 32, windspeed);
_mav_put_uint8_t(buf, 33, wind_heading);
_mav_put_uint8_t(buf, 34, eph);
_mav_put_uint8_t(buf, 35, epv);
_mav_put_int8_t(buf, 36, temperature_air);
_mav_put_int8_t(buf, 37, climb_rate);
_mav_put_int8_t(buf, 38, battery);
_mav_put_int8_t(buf, 39, custom0);
_mav_put_int8_t(buf, 40, custom1);
_mav_put_int8_t(buf, 41, custom2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
#else
mavlink_high_latency2_t packet;
packet.timestamp = timestamp;
packet.latitude = latitude;
packet.longitude = longitude;
packet.custom_mode = custom_mode;
packet.altitude = altitude;
packet.target_altitude = target_altitude;
packet.target_distance = target_distance;
packet.wp_num = wp_num;
packet.failure_flags = failure_flags;
packet.type = type;
packet.autopilot = autopilot;
packet.heading = heading;
packet.target_heading = target_heading;
packet.throttle = throttle;
packet.airspeed = airspeed;
packet.airspeed_sp = airspeed_sp;
packet.groundspeed = groundspeed;
packet.windspeed = windspeed;
packet.wind_heading = wind_heading;
packet.eph = eph;
packet.epv = epv;
packet.temperature_air = temperature_air;
packet.climb_rate = climb_rate;
packet.battery = battery;
packet.custom0 = custom0;
packet.custom1 = custom1;
packet.custom2 = custom2;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
#endif
}
/**
* @brief Send a high_latency2 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_high_latency2_send_struct(mavlink_channel_t chan, const mavlink_high_latency2_t* high_latency2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_high_latency2_send(chan, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)high_latency2, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
#endif
}
#if MAVLINK_MSG_ID_HIGH_LATENCY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_high_latency2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_int32_t(buf, 4, latitude);
_mav_put_int32_t(buf, 8, longitude);
_mav_put_uint16_t(buf, 12, custom_mode);
_mav_put_int16_t(buf, 14, altitude);
_mav_put_int16_t(buf, 16, target_altitude);
_mav_put_uint16_t(buf, 18, target_distance);
_mav_put_uint16_t(buf, 20, wp_num);
_mav_put_uint16_t(buf, 22, failure_flags);
_mav_put_uint8_t(buf, 24, type);
_mav_put_uint8_t(buf, 25, autopilot);
_mav_put_uint8_t(buf, 26, heading);
_mav_put_uint8_t(buf, 27, target_heading);
_mav_put_uint8_t(buf, 28, throttle);
_mav_put_uint8_t(buf, 29, airspeed);
_mav_put_uint8_t(buf, 30, airspeed_sp);
_mav_put_uint8_t(buf, 31, groundspeed);
_mav_put_uint8_t(buf, 32, windspeed);
_mav_put_uint8_t(buf, 33, wind_heading);
_mav_put_uint8_t(buf, 34, eph);
_mav_put_uint8_t(buf, 35, epv);
_mav_put_int8_t(buf, 36, temperature_air);
_mav_put_int8_t(buf, 37, climb_rate);
_mav_put_int8_t(buf, 38, battery);
_mav_put_int8_t(buf, 39, custom0);
_mav_put_int8_t(buf, 40, custom1);
_mav_put_int8_t(buf, 41, custom2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
#else
mavlink_high_latency2_t *packet = (mavlink_high_latency2_t *)msgbuf;
packet->timestamp = timestamp;
packet->latitude = latitude;
packet->longitude = longitude;
packet->custom_mode = custom_mode;
packet->altitude = altitude;
packet->target_altitude = target_altitude;
packet->target_distance = target_distance;
packet->wp_num = wp_num;
packet->failure_flags = failure_flags;
packet->type = type;
packet->autopilot = autopilot;
packet->heading = heading;
packet->target_heading = target_heading;
packet->throttle = throttle;
packet->airspeed = airspeed;
packet->airspeed_sp = airspeed_sp;
packet->groundspeed = groundspeed;
packet->windspeed = windspeed;
packet->wind_heading = wind_heading;
packet->eph = eph;
packet->epv = epv;
packet->temperature_air = temperature_air;
packet->climb_rate = climb_rate;
packet->battery = battery;
packet->custom0 = custom0;
packet->custom1 = custom1;
packet->custom2 = custom2;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC);
#endif
}
#endif
#endif
// MESSAGE HIGH_LATENCY2 UNPACKING
/**
* @brief Get field timestamp from high_latency2 message
*
* @return [ms] Timestamp (milliseconds since boot or Unix epoch)
*/
static inline uint32_t mavlink_msg_high_latency2_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field type from high_latency2 message
*
* @return Type of the MAV (quadrotor, helicopter, etc.)
*/
static inline uint8_t mavlink_msg_high_latency2_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
/**
* @brief Get field autopilot from high_latency2 message
*
* @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
*/
static inline uint8_t mavlink_msg_high_latency2_get_autopilot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 25);
}
/**
* @brief Get field custom_mode from high_latency2 message
*
* @return A bitfield for use for autopilot-specific flags (2 byte version).
*/
static inline uint16_t mavlink_msg_high_latency2_get_custom_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
/**
* @brief Get field latitude from high_latency2 message
*
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_high_latency2_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field longitude from high_latency2 message
*
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_high_latency2_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field altitude from high_latency2 message
*
* @return [m] Altitude above mean sea level
*/
static inline int16_t mavlink_msg_high_latency2_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
/**
* @brief Get field target_altitude from high_latency2 message
*
* @return [m] Altitude setpoint
*/
static inline int16_t mavlink_msg_high_latency2_get_target_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
/**
* @brief Get field heading from high_latency2 message
*
* @return [deg/2] Heading
*/
static inline uint8_t mavlink_msg_high_latency2_get_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 26);
}
/**
* @brief Get field target_heading from high_latency2 message
*
* @return [deg/2] Heading setpoint
*/
static inline uint8_t mavlink_msg_high_latency2_get_target_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 27);
}
/**
* @brief Get field target_distance from high_latency2 message
*
* @return [dam] Distance to target waypoint or position
*/
static inline uint16_t mavlink_msg_high_latency2_get_target_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field throttle from high_latency2 message
*
* @return [%] Throttle
*/
static inline uint8_t mavlink_msg_high_latency2_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field airspeed from high_latency2 message
*
* @return [m/s*5] Airspeed
*/
static inline uint8_t mavlink_msg_high_latency2_get_airspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field airspeed_sp from high_latency2 message
*
* @return [m/s*5] Airspeed setpoint
*/
static inline uint8_t mavlink_msg_high_latency2_get_airspeed_sp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field groundspeed from high_latency2 message
*
* @return [m/s*5] Groundspeed
*/
static inline uint8_t mavlink_msg_high_latency2_get_groundspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field windspeed from high_latency2 message
*
* @return [m/s*5] Windspeed
*/
static inline uint8_t mavlink_msg_high_latency2_get_windspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field wind_heading from high_latency2 message
*
* @return [deg/2] Wind heading
*/
static inline uint8_t mavlink_msg_high_latency2_get_wind_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field eph from high_latency2 message
*
* @return [dm] Maximum error horizontal position since last message
*/
static inline uint8_t mavlink_msg_high_latency2_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field epv from high_latency2 message
*
* @return [dm] Maximum error vertical position since last message
*/
static inline uint8_t mavlink_msg_high_latency2_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Get field temperature_air from high_latency2 message
*
* @return [degC] Air temperature from airspeed sensor
*/
static inline int8_t mavlink_msg_high_latency2_get_temperature_air(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 36);
}
/**
* @brief Get field climb_rate from high_latency2 message
*
* @return [dm/s] Maximum climb rate magnitude since last message
*/
static inline int8_t mavlink_msg_high_latency2_get_climb_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 37);
}
/**
* @brief Get field battery from high_latency2 message
*
* @return [%] Battery level (-1 if field not provided).
*/
static inline int8_t mavlink_msg_high_latency2_get_battery(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 38);
}
/**
* @brief Get field wp_num from high_latency2 message
*
* @return Current waypoint number
*/
static inline uint16_t mavlink_msg_high_latency2_get_wp_num(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
/**
* @brief Get field failure_flags from high_latency2 message
*
* @return Bitmap of failure flags.
*/
static inline uint16_t mavlink_msg_high_latency2_get_failure_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
/**
* @brief Get field custom0 from high_latency2 message
*
* @return Field for custom payload.
*/
static inline int8_t mavlink_msg_high_latency2_get_custom0(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 39);
}
/**
* @brief Get field custom1 from high_latency2 message
*
* @return Field for custom payload.
*/
static inline int8_t mavlink_msg_high_latency2_get_custom1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 40);
}
/**
* @brief Get field custom2 from high_latency2 message
*
* @return Field for custom payload.
*/
static inline int8_t mavlink_msg_high_latency2_get_custom2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 41);
}
/**
* @brief Decode a high_latency2 message into a struct
*
* @param msg The message to decode
* @param high_latency2 C-struct to decode the message contents into
*/
static inline void mavlink_msg_high_latency2_decode(const mavlink_message_t* msg, mavlink_high_latency2_t* high_latency2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
high_latency2->timestamp = mavlink_msg_high_latency2_get_timestamp(msg);
high_latency2->latitude = mavlink_msg_high_latency2_get_latitude(msg);
high_latency2->longitude = mavlink_msg_high_latency2_get_longitude(msg);
high_latency2->custom_mode = mavlink_msg_high_latency2_get_custom_mode(msg);
high_latency2->altitude = mavlink_msg_high_latency2_get_altitude(msg);
high_latency2->target_altitude = mavlink_msg_high_latency2_get_target_altitude(msg);
high_latency2->target_distance = mavlink_msg_high_latency2_get_target_distance(msg);
high_latency2->wp_num = mavlink_msg_high_latency2_get_wp_num(msg);
high_latency2->failure_flags = mavlink_msg_high_latency2_get_failure_flags(msg);
high_latency2->type = mavlink_msg_high_latency2_get_type(msg);
high_latency2->autopilot = mavlink_msg_high_latency2_get_autopilot(msg);
high_latency2->heading = mavlink_msg_high_latency2_get_heading(msg);
high_latency2->target_heading = mavlink_msg_high_latency2_get_target_heading(msg);
high_latency2->throttle = mavlink_msg_high_latency2_get_throttle(msg);
high_latency2->airspeed = mavlink_msg_high_latency2_get_airspeed(msg);
high_latency2->airspeed_sp = mavlink_msg_high_latency2_get_airspeed_sp(msg);
high_latency2->groundspeed = mavlink_msg_high_latency2_get_groundspeed(msg);
high_latency2->windspeed = mavlink_msg_high_latency2_get_windspeed(msg);
high_latency2->wind_heading = mavlink_msg_high_latency2_get_wind_heading(msg);
high_latency2->eph = mavlink_msg_high_latency2_get_eph(msg);
high_latency2->epv = mavlink_msg_high_latency2_get_epv(msg);
high_latency2->temperature_air = mavlink_msg_high_latency2_get_temperature_air(msg);
high_latency2->climb_rate = mavlink_msg_high_latency2_get_climb_rate(msg);
high_latency2->battery = mavlink_msg_high_latency2_get_battery(msg);
high_latency2->custom0 = mavlink_msg_high_latency2_get_custom0(msg);
high_latency2->custom1 = mavlink_msg_high_latency2_get_custom1(msg);
high_latency2->custom2 = mavlink_msg_high_latency2_get_custom2(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY2_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY2_LEN;
memset(high_latency2, 0, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN);
memcpy(high_latency2, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,24 +3,24 @@
#define MAVLINK_MSG_ID_HIGHRES_IMU 105
MAVPACKED(
typedef struct __mavlink_highres_imu_t {
uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
float xacc; /*< X acceleration (m/s^2)*/
float yacc; /*< Y acceleration (m/s^2)*/
float zacc; /*< Z acceleration (m/s^2)*/
float xgyro; /*< Angular speed around X axis (rad / sec)*/
float ygyro; /*< Angular speed around Y axis (rad / sec)*/
float zgyro; /*< Angular speed around Z axis (rad / sec)*/
float xmag; /*< X Magnetic field (Gauss)*/
float ymag; /*< Y Magnetic field (Gauss)*/
float zmag; /*< Z Magnetic field (Gauss)*/
float abs_pressure; /*< Absolute pressure in millibar*/
float diff_pressure; /*< Differential pressure in millibar*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float xacc; /*< [m/s/s] X acceleration*/
float yacc; /*< [m/s/s] Y acceleration*/
float zacc; /*< [m/s/s] Z acceleration*/
float xgyro; /*< [rad/s] Angular speed around X axis*/
float ygyro; /*< [rad/s] Angular speed around Y axis*/
float zgyro; /*< [rad/s] Angular speed around Z axis*/
float xmag; /*< [gauss] X Magnetic field*/
float ymag; /*< [gauss] Y Magnetic field*/
float zmag; /*< [gauss] Z Magnetic field*/
float abs_pressure; /*< [mbar] Absolute pressure*/
float diff_pressure; /*< [mbar] Differential pressure*/
float pressure_alt; /*< Altitude calculated from pressure*/
float temperature; /*< Temperature in degrees celsius*/
uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/
}) mavlink_highres_imu_t;
float temperature; /*< [degC] Temperature*/
uint16_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/
} mavlink_highres_imu_t;
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
#define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62
@ -83,21 +83,21 @@ typedef struct __mavlink_highres_imu_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis
* @param ygyro [rad/s] Angular speed around Y axis
* @param zgyro [rad/s] Angular speed around Z axis
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -153,21 +153,21 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis
* @param ygyro [rad/s] Angular speed around Y axis
* @param zgyro [rad/s] Angular speed around Z axis
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -249,21 +249,21 @@ static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, ui
* @brief Send a highres_imu message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis
* @param ygyro [rad/s] Angular speed around Y axis
* @param zgyro [rad/s] Angular speed around Z axis
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -384,7 +384,7 @@ static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, m
/**
* @brief Get field time_usec from highres_imu message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg)
{
@ -394,7 +394,7 @@ static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_messa
/**
* @brief Get field xacc from highres_imu message
*
* @return X acceleration (m/s^2)
* @return [m/s/s] X acceleration
*/
static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg)
{
@ -404,7 +404,7 @@ static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* ms
/**
* @brief Get field yacc from highres_imu message
*
* @return Y acceleration (m/s^2)
* @return [m/s/s] Y acceleration
*/
static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg)
{
@ -414,7 +414,7 @@ static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* ms
/**
* @brief Get field zacc from highres_imu message
*
* @return Z acceleration (m/s^2)
* @return [m/s/s] Z acceleration
*/
static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg)
{
@ -424,7 +424,7 @@ static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* ms
/**
* @brief Get field xgyro from highres_imu message
*
* @return Angular speed around X axis (rad / sec)
* @return [rad/s] Angular speed around X axis
*/
static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg)
{
@ -434,7 +434,7 @@ static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* m
/**
* @brief Get field ygyro from highres_imu message
*
* @return Angular speed around Y axis (rad / sec)
* @return [rad/s] Angular speed around Y axis
*/
static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg)
{
@ -444,7 +444,7 @@ static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* m
/**
* @brief Get field zgyro from highres_imu message
*
* @return Angular speed around Z axis (rad / sec)
* @return [rad/s] Angular speed around Z axis
*/
static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg)
{
@ -454,7 +454,7 @@ static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* m
/**
* @brief Get field xmag from highres_imu message
*
* @return X Magnetic field (Gauss)
* @return [gauss] X Magnetic field
*/
static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg)
{
@ -464,7 +464,7 @@ static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* ms
/**
* @brief Get field ymag from highres_imu message
*
* @return Y Magnetic field (Gauss)
* @return [gauss] Y Magnetic field
*/
static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg)
{
@ -474,7 +474,7 @@ static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* ms
/**
* @brief Get field zmag from highres_imu message
*
* @return Z Magnetic field (Gauss)
* @return [gauss] Z Magnetic field
*/
static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg)
{
@ -484,7 +484,7 @@ static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* ms
/**
* @brief Get field abs_pressure from highres_imu message
*
* @return Absolute pressure in millibar
* @return [mbar] Absolute pressure
*/
static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg)
{
@ -494,7 +494,7 @@ static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_messa
/**
* @brief Get field diff_pressure from highres_imu message
*
* @return Differential pressure in millibar
* @return [mbar] Differential pressure
*/
static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg)
{
@ -514,7 +514,7 @@ static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_messa
/**
* @brief Get field temperature from highres_imu message
*
* @return Temperature in degrees celsius
* @return [degC] Temperature
*/
static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg)
{
@ -524,7 +524,7 @@ static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_messag
/**
* @brief Get field fields_updated from highres_imu message
*
* @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93
MAVPACKED(
typedef struct __mavlink_hil_actuator_controls_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
uint64_t flags; /*< Flags as bitfield, reserved for future use.*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint64_t flags; /*< Flags as bitfield, 1: indicate simulation using lockstep.*/
float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/
uint8_t mode; /*< System mode (MAV_MODE), includes arming state.*/
}) mavlink_hil_actuator_controls_t;
uint8_t mode; /*< System mode. Includes arming state.*/
} mavlink_hil_actuator_controls_t;
#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81
#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81
@ -27,9 +27,9 @@ typedef struct __mavlink_hil_actuator_controls_t {
"HIL_ACTUATOR_CONTROLS", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
} \
}
#else
@ -37,9 +37,9 @@ typedef struct __mavlink_hil_actuator_controls_t {
"HIL_ACTUATOR_CONTROLS", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
} \
}
#endif
@ -50,10 +50,10 @@ typedef struct __mavlink_hil_actuator_controls_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
* @param mode System mode (MAV_MODE), includes arming state.
* @param flags Flags as bitfield, reserved for future use.
* @param mode System mode. Includes arming state.
* @param flags Flags as bitfield, 1: indicate simulation using lockstep.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id,
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
* @param mode System mode (MAV_MODE), includes arming state.
* @param flags Flags as bitfield, reserved for future use.
* @param mode System mode. Includes arming state.
* @param flags Flags as bitfield, 1: indicate simulation using lockstep.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t sys
* @brief Send a hil_actuator_controls message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
* @param mode System mode (MAV_MODE), includes arming state.
* @param flags Flags as bitfield, reserved for future use.
* @param mode System mode. Includes arming state.
* @param flags Flags as bitfield, 1: indicate simulation using lockstep.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -222,7 +222,7 @@ static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t
/**
* @brief Get field time_usec from hil_actuator_controls message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg)
{
@ -242,7 +242,7 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavl
/**
* @brief Get field mode from hil_actuator_controls message
*
* @return System mode (MAV_MODE), includes arming state.
* @return System mode. Includes arming state.
*/
static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg)
{
@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_m
/**
* @brief Get field flags from hil_actuator_controls message
*
* @return Flags as bitfield, reserved for future use.
* @return Flags as bitfield, 1: indicate simulation using lockstep.
*/
static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg)
{

View file

@ -3,9 +3,9 @@
#define MAVLINK_MSG_ID_HIL_CONTROLS 91
MAVPACKED(
typedef struct __mavlink_hil_controls_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float roll_ailerons; /*< Control output -1 .. 1*/
float pitch_elevator; /*< Control output -1 .. 1*/
float yaw_rudder; /*< Control output -1 .. 1*/
@ -14,9 +14,9 @@ typedef struct __mavlink_hil_controls_t {
float aux2; /*< Aux 2, -1 .. 1*/
float aux3; /*< Aux 3, -1 .. 1*/
float aux4; /*< Aux 4, -1 .. 1*/
uint8_t mode; /*< System mode (MAV_MODE)*/
uint8_t mode; /*< System mode.*/
uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/
}) mavlink_hil_controls_t;
} mavlink_hil_controls_t;
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
#define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42
@ -71,7 +71,7 @@ typedef struct __mavlink_hil_controls_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
@ -80,7 +80,7 @@ typedef struct __mavlink_hil_controls_t {
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param mode System mode.
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
@ -138,7 +138,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param mode System mode.
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -213,7 +213,7 @@ static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, u
* @brief Send a hil_controls message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
@ -222,7 +222,7 @@ static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, u
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param mode System mode.
* @param nav_mode Navigation mode (MAV_NAV_MODE)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -328,7 +328,7 @@ static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field time_usec from hil_controls message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg)
{
@ -418,7 +418,7 @@ static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* m
/**
* @brief Get field mode from hil_controls message
*
* @return System mode (MAV_MODE)
* @return System mode.
*/
static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
{

View file

@ -3,22 +3,22 @@
#define MAVLINK_MSG_ID_HIL_GPS 113
MAVPACKED(
typedef struct __mavlink_hil_gps_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/
uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/
uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/
int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/
int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/
int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/
uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/
uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535*/
uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535*/
uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: 65535*/
int16_t vn; /*< [cm/s] GPS velocity in north direction in earth-fixed NED frame*/
int16_t ve; /*< [cm/s] GPS velocity in east direction in earth-fixed NED frame*/
int16_t vd; /*< [cm/s] GPS velocity in down direction in earth-fixed NED frame*/
uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535*/
uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/
uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
}) mavlink_hil_gps_t;
} mavlink_hil_gps_t;
#define MAVLINK_MSG_ID_HIL_GPS_LEN 36
#define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36
@ -36,6 +36,7 @@ typedef struct __mavlink_hil_gps_t {
"HIL_GPS", \
13, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
@ -46,7 +47,6 @@ typedef struct __mavlink_hil_gps_t {
{ "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
{ "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
} \
}
@ -55,6 +55,7 @@ typedef struct __mavlink_hil_gps_t {
"HIL_GPS", \
13, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
@ -65,7 +66,6 @@ typedef struct __mavlink_hil_gps_t {
{ "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
{ "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
} \
}
@ -77,18 +77,18 @@ typedef struct __mavlink_hil_gps_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -141,18 +141,18 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -231,18 +231,18 @@ static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_
* @brief Send a hil_gps message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -356,7 +356,7 @@ static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavli
/**
* @brief Get field time_usec from hil_gps message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
{
@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t*
/**
* @brief Get field lat from hil_gps message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
/**
* @brief Get field lon from hil_gps message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
{
@ -396,7 +396,7 @@ static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
/**
* @brief Get field alt from hil_gps message
*
* @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @return [mm] Altitude (MSL). Positive for up.
*/
static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
{
@ -406,7 +406,7 @@ static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field eph from hil_gps message
*
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
{
@ -416,7 +416,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
/**
* @brief Get field epv from hil_gps message
*
* @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
* @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
{
@ -426,7 +426,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
/**
* @brief Get field vel from hil_gps message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: 65535
* @return [cm/s] GPS ground speed. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
{
@ -436,7 +436,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
/**
* @brief Get field vn from hil_gps message
*
* @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @return [cm/s] GPS velocity in north direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
{
@ -446,7 +446,7 @@ static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
/**
* @brief Get field ve from hil_gps message
*
* @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @return [cm/s] GPS velocity in east direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
{
@ -456,7 +456,7 @@ static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
/**
* @brief Get field vd from hil_gps message
*
* @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @return [cm/s] GPS velocity in down direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
{
@ -466,7 +466,7 @@ static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
/**
* @brief Get field cog from hil_gps message
*
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @return [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg)
{

View file

@ -3,21 +3,21 @@
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
MAVPACKED(
typedef struct __mavlink_hil_optical_flow_t {
uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/
float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/
float integrated_xgyro; /*< RH rotation around X axis (rad)*/
float integrated_ygyro; /*< RH rotation around Y axis (rad)*/
float integrated_zgyro; /*< RH rotation around Z axis (rad)*/
uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/
float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/
int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
float integrated_x; /*< [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/
float integrated_y; /*< [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/
float integrated_xgyro; /*< [rad] RH rotation around X axis*/
float integrated_ygyro; /*< [rad] RH rotation around Y axis*/
float integrated_zgyro; /*< [rad] RH rotation around Z axis*/
uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/
float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/
int16_t temperature; /*< [cdegC] Temperature*/
uint8_t sensor_id; /*< Sensor ID*/
uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/
}) mavlink_hil_optical_flow_t;
} mavlink_hil_optical_flow_t;
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44
@ -35,17 +35,17 @@ typedef struct __mavlink_hil_optical_flow_t {
"HIL_OPTICAL_FLOW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
} \
}
#else
@ -53,17 +53,17 @@ typedef struct __mavlink_hil_optical_flow_t {
"HIL_OPTICAL_FLOW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
} \
}
#endif
@ -74,18 +74,18 @@ typedef struct __mavlink_hil_optical_flow_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_i
* @brief Send a hil_optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -342,7 +342,7 @@ static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgb
/**
* @brief Get field time_usec from hil_optical_flow message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg)
{
@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_m
/**
* @brief Get field integration_time_us from hil_optical_flow message
*
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
*/
static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg)
{
@ -372,7 +372,7 @@ static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(cons
/**
* @brief Get field integrated_x from hil_optical_flow message
*
* @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @return [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg)
{
@ -382,7 +382,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_
/**
* @brief Get field integrated_y from hil_optical_flow message
*
* @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @return [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg)
{
@ -392,7 +392,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_
/**
* @brief Get field integrated_xgyro from hil_optical_flow message
*
* @return RH rotation around X axis (rad)
* @return [rad] RH rotation around X axis
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg)
{
@ -402,7 +402,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavl
/**
* @brief Get field integrated_ygyro from hil_optical_flow message
*
* @return RH rotation around Y axis (rad)
* @return [rad] RH rotation around Y axis
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg)
{
@ -412,7 +412,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavl
/**
* @brief Get field integrated_zgyro from hil_optical_flow message
*
* @return RH rotation around Z axis (rad)
* @return [rad] RH rotation around Z axis
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg)
{
@ -422,7 +422,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavl
/**
* @brief Get field temperature from hil_optical_flow message
*
* @return Temperature * 100 in centi-degrees Celsius
* @return [cdegC] Temperature
*/
static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg)
{
@ -442,7 +442,7 @@ static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_mes
/**
* @brief Get field time_delta_distance_us from hil_optical_flow message
*
* @return Time in microseconds since the distance was sampled.
* @return [us] Time since the distance was sampled.
*/
static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg)
{
@ -452,7 +452,7 @@ static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(c
/**
* @brief Get field distance from hil_optical_flow message
*
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg)
{

View file

@ -3,23 +3,23 @@
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92
MAVPACKED(
typedef struct __mavlink_hil_rc_inputs_raw_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/
uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/
uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/
uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/
uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/
uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/
uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/
uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/
uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/
uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/
uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/
uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/
uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/
}) mavlink_hil_rc_inputs_raw_t;
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint16_t chan1_raw; /*< [us] RC channel 1 value*/
uint16_t chan2_raw; /*< [us] RC channel 2 value*/
uint16_t chan3_raw; /*< [us] RC channel 3 value*/
uint16_t chan4_raw; /*< [us] RC channel 4 value*/
uint16_t chan5_raw; /*< [us] RC channel 5 value*/
uint16_t chan6_raw; /*< [us] RC channel 6 value*/
uint16_t chan7_raw; /*< [us] RC channel 7 value*/
uint16_t chan8_raw; /*< [us] RC channel 8 value*/
uint16_t chan9_raw; /*< [us] RC channel 9 value*/
uint16_t chan10_raw; /*< [us] RC channel 10 value*/
uint16_t chan11_raw; /*< [us] RC channel 11 value*/
uint16_t chan12_raw; /*< [us] RC channel 12 value*/
uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/
} mavlink_hil_rc_inputs_raw_t;
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN 33
@ -80,20 +80,20 @@ typedef struct __mavlink_hil_rc_inputs_raw_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param chan1_raw [us] RC channel 1 value
* @param chan2_raw [us] RC channel 2 value
* @param chan3_raw [us] RC channel 3 value
* @param chan4_raw [us] RC channel 4 value
* @param chan5_raw [us] RC channel 5 value
* @param chan6_raw [us] RC channel 6 value
* @param chan7_raw [us] RC channel 7 value
* @param chan8_raw [us] RC channel 8 value
* @param chan9_raw [us] RC channel 9 value
* @param chan10_raw [us] RC channel 10 value
* @param chan11_raw [us] RC channel 11 value
* @param chan12_raw [us] RC channel 12 value
* @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param chan1_raw [us] RC channel 1 value
* @param chan2_raw [us] RC channel 2 value
* @param chan3_raw [us] RC channel 3 value
* @param chan4_raw [us] RC channel 4 value
* @param chan5_raw [us] RC channel 5 value
* @param chan6_raw [us] RC channel 6 value
* @param chan7_raw [us] RC channel 7 value
* @param chan8_raw [us] RC channel 8 value
* @param chan9_raw [us] RC channel 9 value
* @param chan10_raw [us] RC channel 10 value
* @param chan11_raw [us] RC channel 11 value
* @param chan12_raw [us] RC channel 12 value
* @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_
* @brief Send a hil_rc_inputs_raw message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param chan1_raw [us] RC channel 1 value
* @param chan2_raw [us] RC channel 2 value
* @param chan3_raw [us] RC channel 3 value
* @param chan4_raw [us] RC channel 4 value
* @param chan5_raw [us] RC channel 5 value
* @param chan6_raw [us] RC channel 6 value
* @param chan7_raw [us] RC channel 7 value
* @param chan8_raw [us] RC channel 8 value
* @param chan9_raw [us] RC channel 9 value
* @param chan10_raw [us] RC channel 10 value
* @param chan11_raw [us] RC channel 11 value
* @param chan12_raw [us] RC channel 12 value
* @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -370,7 +370,7 @@ static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msg
/**
* @brief Get field time_usec from hil_rc_inputs_raw message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg)
{
@ -380,7 +380,7 @@ static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink
/**
* @brief Get field chan1_raw from hil_rc_inputs_raw message
*
* @return RC channel 1 value, in microseconds
* @return [us] RC channel 1 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg)
{
@ -390,7 +390,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink
/**
* @brief Get field chan2_raw from hil_rc_inputs_raw message
*
* @return RC channel 2 value, in microseconds
* @return [us] RC channel 2 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg)
{
@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink
/**
* @brief Get field chan3_raw from hil_rc_inputs_raw message
*
* @return RC channel 3 value, in microseconds
* @return [us] RC channel 3 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg)
{
@ -410,7 +410,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink
/**
* @brief Get field chan4_raw from hil_rc_inputs_raw message
*
* @return RC channel 4 value, in microseconds
* @return [us] RC channel 4 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg)
{
@ -420,7 +420,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink
/**
* @brief Get field chan5_raw from hil_rc_inputs_raw message
*
* @return RC channel 5 value, in microseconds
* @return [us] RC channel 5 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg)
{
@ -430,7 +430,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink
/**
* @brief Get field chan6_raw from hil_rc_inputs_raw message
*
* @return RC channel 6 value, in microseconds
* @return [us] RC channel 6 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg)
{
@ -440,7 +440,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink
/**
* @brief Get field chan7_raw from hil_rc_inputs_raw message
*
* @return RC channel 7 value, in microseconds
* @return [us] RC channel 7 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg)
{
@ -450,7 +450,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink
/**
* @brief Get field chan8_raw from hil_rc_inputs_raw message
*
* @return RC channel 8 value, in microseconds
* @return [us] RC channel 8 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg)
{
@ -460,7 +460,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink
/**
* @brief Get field chan9_raw from hil_rc_inputs_raw message
*
* @return RC channel 9 value, in microseconds
* @return [us] RC channel 9 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg)
{
@ -470,7 +470,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink
/**
* @brief Get field chan10_raw from hil_rc_inputs_raw message
*
* @return RC channel 10 value, in microseconds
* @return [us] RC channel 10 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg)
{
@ -480,7 +480,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlin
/**
* @brief Get field chan11_raw from hil_rc_inputs_raw message
*
* @return RC channel 11 value, in microseconds
* @return [us] RC channel 11 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg)
{
@ -490,7 +490,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlin
/**
* @brief Get field chan12_raw from hil_rc_inputs_raw message
*
* @return RC channel 12 value, in microseconds
* @return [us] RC channel 12 value
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg)
{
@ -500,7 +500,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlin
/**
* @brief Get field rssi from hil_rc_inputs_raw message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
* @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
*/
static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg)
{

View file

@ -3,24 +3,24 @@
#define MAVLINK_MSG_ID_HIL_SENSOR 107
MAVPACKED(
typedef struct __mavlink_hil_sensor_t {
uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
float xacc; /*< X acceleration (m/s^2)*/
float yacc; /*< Y acceleration (m/s^2)*/
float zacc; /*< Z acceleration (m/s^2)*/
float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/
float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/
float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/
float xmag; /*< X Magnetic field (Gauss)*/
float ymag; /*< Y Magnetic field (Gauss)*/
float zmag; /*< Z Magnetic field (Gauss)*/
float abs_pressure; /*< Absolute pressure in millibar*/
float diff_pressure; /*< Differential pressure (airspeed) in millibar*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float xacc; /*< [m/s/s] X acceleration*/
float yacc; /*< [m/s/s] Y acceleration*/
float zacc; /*< [m/s/s] Z acceleration*/
float xgyro; /*< [rad/s] Angular speed around X axis in body frame*/
float ygyro; /*< [rad/s] Angular speed around Y axis in body frame*/
float zgyro; /*< [rad/s] Angular speed around Z axis in body frame*/
float xmag; /*< [gauss] X Magnetic field*/
float ymag; /*< [gauss] Y Magnetic field*/
float zmag; /*< [gauss] Z Magnetic field*/
float abs_pressure; /*< [mbar] Absolute pressure*/
float diff_pressure; /*< [mbar] Differential pressure (airspeed)*/
float pressure_alt; /*< Altitude calculated from pressure*/
float temperature; /*< Temperature in degrees celsius*/
uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/
}) mavlink_hil_sensor_t;
float temperature; /*< [degC] Temperature*/
uint32_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/
} mavlink_hil_sensor_t;
#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64
#define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64
@ -83,21 +83,21 @@ typedef struct __mavlink_hil_sensor_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis in body frame
* @param ygyro [rad/s] Angular speed around Y axis in body frame
* @param zgyro [rad/s] Angular speed around Z axis in body frame
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -153,21 +153,21 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis in body frame
* @param ygyro [rad/s] Angular speed around Y axis in body frame
* @param zgyro [rad/s] Angular speed around Z axis in body frame
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -249,21 +249,21 @@ static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uin
* @brief Send a hil_sensor message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param xacc [m/s/s] X acceleration
* @param yacc [m/s/s] Y acceleration
* @param zacc [m/s/s] Z acceleration
* @param xgyro [rad/s] Angular speed around X axis in body frame
* @param ygyro [rad/s] Angular speed around Y axis in body frame
* @param zgyro [rad/s] Angular speed around Z axis in body frame
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -384,7 +384,7 @@ static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, ma
/**
* @brief Get field time_usec from hil_sensor message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg)
{
@ -394,7 +394,7 @@ static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_messag
/**
* @brief Get field xacc from hil_sensor message
*
* @return X acceleration (m/s^2)
* @return [m/s/s] X acceleration
*/
static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg)
{
@ -404,7 +404,7 @@ static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg
/**
* @brief Get field yacc from hil_sensor message
*
* @return Y acceleration (m/s^2)
* @return [m/s/s] Y acceleration
*/
static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg)
{
@ -414,7 +414,7 @@ static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg
/**
* @brief Get field zacc from hil_sensor message
*
* @return Z acceleration (m/s^2)
* @return [m/s/s] Z acceleration
*/
static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg)
{
@ -424,7 +424,7 @@ static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg
/**
* @brief Get field xgyro from hil_sensor message
*
* @return Angular speed around X axis in body frame (rad / sec)
* @return [rad/s] Angular speed around X axis in body frame
*/
static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg)
{
@ -434,7 +434,7 @@ static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* ms
/**
* @brief Get field ygyro from hil_sensor message
*
* @return Angular speed around Y axis in body frame (rad / sec)
* @return [rad/s] Angular speed around Y axis in body frame
*/
static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg)
{
@ -444,7 +444,7 @@ static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* ms
/**
* @brief Get field zgyro from hil_sensor message
*
* @return Angular speed around Z axis in body frame (rad / sec)
* @return [rad/s] Angular speed around Z axis in body frame
*/
static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg)
{
@ -454,7 +454,7 @@ static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* ms
/**
* @brief Get field xmag from hil_sensor message
*
* @return X Magnetic field (Gauss)
* @return [gauss] X Magnetic field
*/
static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg)
{
@ -464,7 +464,7 @@ static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg
/**
* @brief Get field ymag from hil_sensor message
*
* @return Y Magnetic field (Gauss)
* @return [gauss] Y Magnetic field
*/
static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg)
{
@ -474,7 +474,7 @@ static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg
/**
* @brief Get field zmag from hil_sensor message
*
* @return Z Magnetic field (Gauss)
* @return [gauss] Z Magnetic field
*/
static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg)
{
@ -484,7 +484,7 @@ static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg
/**
* @brief Get field abs_pressure from hil_sensor message
*
* @return Absolute pressure in millibar
* @return [mbar] Absolute pressure
*/
static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg)
{
@ -494,7 +494,7 @@ static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_messag
/**
* @brief Get field diff_pressure from hil_sensor message
*
* @return Differential pressure (airspeed) in millibar
* @return [mbar] Differential pressure (airspeed)
*/
static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg)
{
@ -514,7 +514,7 @@ static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_messag
/**
* @brief Get field temperature from hil_sensor message
*
* @return Temperature in degrees celsius
* @return [degC] Temperature
*/
static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg)
{
@ -524,7 +524,7 @@ static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message
/**
* @brief Get field fields_updated from hil_sensor message
*
* @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @return Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
*/
static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg)
{

View file

@ -3,25 +3,25 @@
#define MAVLINK_MSG_ID_HIL_STATE 90
MAVPACKED(
typedef struct __mavlink_hil_state_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
float roll; /*< Roll angle (rad)*/
float pitch; /*< Pitch angle (rad)*/
float yaw; /*< Yaw angle (rad)*/
float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/
float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/
float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/
int32_t lat; /*< Latitude, expressed as * 1E7*/
int32_t lon; /*< Longitude, expressed as * 1E7*/
int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/
int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/
int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/
int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/
int16_t xacc; /*< X acceleration (mg)*/
int16_t yacc; /*< Y acceleration (mg)*/
int16_t zacc; /*< Z acceleration (mg)*/
}) mavlink_hil_state_t;
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float roll; /*< [rad] Roll angle*/
float pitch; /*< [rad] Pitch angle*/
float yaw; /*< [rad] Yaw angle*/
float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/
float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/
float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
int32_t alt; /*< [mm] Altitude*/
int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/
int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/
int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/
int16_t xacc; /*< [mG] X acceleration*/
int16_t yacc; /*< [mG] Y acceleration*/
int16_t zacc; /*< [mG] Z acceleration*/
} mavlink_hil_state_t;
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
#define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56
@ -86,22 +86,22 @@ typedef struct __mavlink_hil_state_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -159,22 +159,22 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -258,22 +258,22 @@ static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint
* @brief Send a hil_state message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -398,7 +398,7 @@ static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mav
/**
* @brief Get field time_usec from hil_state message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
{
@ -408,7 +408,7 @@ static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message
/**
* @brief Get field roll from hil_state message
*
* @return Roll angle (rad)
* @return [rad] Roll angle
*/
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
{
@ -418,7 +418,7 @@ static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
/**
* @brief Get field pitch from hil_state message
*
* @return Pitch angle (rad)
* @return [rad] Pitch angle
*/
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
{
@ -428,7 +428,7 @@ static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg
/**
* @brief Get field yaw from hil_state message
*
* @return Yaw angle (rad)
* @return [rad] Yaw angle
*/
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
{
@ -438,7 +438,7 @@ static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
/**
* @brief Get field rollspeed from hil_state message
*
* @return Body frame roll / phi angular speed (rad/s)
* @return [rad/s] Body frame roll / phi angular speed
*/
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
{
@ -448,7 +448,7 @@ static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t*
/**
* @brief Get field pitchspeed from hil_state message
*
* @return Body frame pitch / theta angular speed (rad/s)
* @return [rad/s] Body frame pitch / theta angular speed
*/
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
{
@ -458,7 +458,7 @@ static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t
/**
* @brief Get field yawspeed from hil_state message
*
* @return Body frame yaw / psi angular speed (rad/s)
* @return [rad/s] Body frame yaw / psi angular speed
*/
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
{
@ -468,7 +468,7 @@ static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t*
/**
* @brief Get field lat from hil_state message
*
* @return Latitude, expressed as * 1E7
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
{
@ -478,7 +478,7 @@ static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg
/**
* @brief Get field lon from hil_state message
*
* @return Longitude, expressed as * 1E7
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
{
@ -488,7 +488,7 @@ static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg
/**
* @brief Get field alt from hil_state message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
* @return [mm] Altitude
*/
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
{
@ -498,7 +498,7 @@ static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg
/**
* @brief Get field vx from hil_state message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
* @return [cm/s] Ground X Speed (Latitude)
*/
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
{
@ -508,7 +508,7 @@ static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
/**
* @brief Get field vy from hil_state message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
* @return [cm/s] Ground Y Speed (Longitude)
*/
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
{
@ -518,7 +518,7 @@ static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
/**
* @brief Get field vz from hil_state message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
* @return [cm/s] Ground Z Speed (Altitude)
*/
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
{
@ -528,7 +528,7 @@ static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
/**
* @brief Get field xacc from hil_state message
*
* @return X acceleration (mg)
* @return [mG] X acceleration
*/
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
{
@ -538,7 +538,7 @@ static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* ms
/**
* @brief Get field yacc from hil_state message
*
* @return Y acceleration (mg)
* @return [mG] Y acceleration
*/
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
{
@ -548,7 +548,7 @@ static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* ms
/**
* @brief Get field zacc from hil_state message
*
* @return Z acceleration (mg)
* @return [mG] Z acceleration
*/
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
{

View file

@ -3,25 +3,25 @@
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115
MAVPACKED(
typedef struct __mavlink_hil_state_quaternion_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/
float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/
float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/
float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/
int32_t lat; /*< Latitude, expressed as * 1E7*/
int32_t lon; /*< Longitude, expressed as * 1E7*/
int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/
int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/
int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/
int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/
uint16_t ind_airspeed; /*< Indicated airspeed, expressed as m/s * 100*/
uint16_t true_airspeed; /*< True airspeed, expressed as m/s * 100*/
int16_t xacc; /*< X acceleration (mg)*/
int16_t yacc; /*< Y acceleration (mg)*/
int16_t zacc; /*< Z acceleration (mg)*/
}) mavlink_hil_state_quaternion_t;
float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/
float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/
float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
int32_t alt; /*< [mm] Altitude*/
int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/
int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/
int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/
uint16_t ind_airspeed; /*< [cm/s] Indicated airspeed*/
uint16_t true_airspeed; /*< [cm/s] True airspeed*/
int16_t xacc; /*< [mG] X acceleration*/
int16_t yacc; /*< [mG] Y acceleration*/
int16_t zacc; /*< [mG] Z acceleration*/
} mavlink_hil_state_quaternion_t;
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64
@ -86,22 +86,22 @@ typedef struct __mavlink_hil_state_quaternion_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param ind_airspeed [cm/s] Indicated airspeed
* @param true_airspeed [cm/s] True airspeed
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -157,22 +157,22 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id,
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param ind_airspeed [cm/s] Indicated airspeed
* @param true_airspeed [cm/s] True airspeed
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -254,22 +254,22 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t syst
* @brief Send a hil_state_quaternion message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param rollspeed [rad/s] Body frame roll / phi angular speed
* @param pitchspeed [rad/s] Body frame pitch / theta angular speed
* @param yawspeed [rad/s] Body frame yaw / psi angular speed
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param alt [mm] Altitude
* @param vx [cm/s] Ground X Speed (Latitude)
* @param vy [cm/s] Ground Y Speed (Longitude)
* @param vz [cm/s] Ground Z Speed (Altitude)
* @param ind_airspeed [cm/s] Indicated airspeed
* @param true_airspeed [cm/s] True airspeed
* @param xacc [mG] X acceleration
* @param yacc [mG] Y acceleration
* @param zacc [mG] Z acceleration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -390,7 +390,7 @@ static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *
/**
* @brief Get field time_usec from hil_state_quaternion message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg)
{
@ -410,7 +410,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(
/**
* @brief Get field rollspeed from hil_state_quaternion message
*
* @return Body frame roll / phi angular speed (rad/s)
* @return [rad/s] Body frame roll / phi angular speed
*/
static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg)
{
@ -420,7 +420,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink
/**
* @brief Get field pitchspeed from hil_state_quaternion message
*
* @return Body frame pitch / theta angular speed (rad/s)
* @return [rad/s] Body frame pitch / theta angular speed
*/
static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg)
{
@ -430,7 +430,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlin
/**
* @brief Get field yawspeed from hil_state_quaternion message
*
* @return Body frame yaw / psi angular speed (rad/s)
* @return [rad/s] Body frame yaw / psi angular speed
*/
static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg)
{
@ -440,7 +440,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_
/**
* @brief Get field lat from hil_state_quaternion message
*
* @return Latitude, expressed as * 1E7
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg)
{
@ -450,7 +450,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_mes
/**
* @brief Get field lon from hil_state_quaternion message
*
* @return Longitude, expressed as * 1E7
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg)
{
@ -460,7 +460,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_mes
/**
* @brief Get field alt from hil_state_quaternion message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
* @return [mm] Altitude
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg)
{
@ -470,7 +470,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_mes
/**
* @brief Get field vx from hil_state_quaternion message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
* @return [cm/s] Ground X Speed (Latitude)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg)
{
@ -480,7 +480,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_mess
/**
* @brief Get field vy from hil_state_quaternion message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
* @return [cm/s] Ground Y Speed (Longitude)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg)
{
@ -490,7 +490,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_mess
/**
* @brief Get field vz from hil_state_quaternion message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
* @return [cm/s] Ground Z Speed (Altitude)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg)
{
@ -500,7 +500,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_mess
/**
* @brief Get field ind_airspeed from hil_state_quaternion message
*
* @return Indicated airspeed, expressed as m/s * 100
* @return [cm/s] Indicated airspeed
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg)
{
@ -510,7 +510,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const m
/**
* @brief Get field true_airspeed from hil_state_quaternion message
*
* @return True airspeed, expressed as m/s * 100
* @return [cm/s] True airspeed
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg)
{
@ -520,7 +520,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const
/**
* @brief Get field xacc from hil_state_quaternion message
*
* @return X acceleration (mg)
* @return [mG] X acceleration
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg)
{
@ -530,7 +530,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_me
/**
* @brief Get field yacc from hil_state_quaternion message
*
* @return Y acceleration (mg)
* @return [mG] Y acceleration
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg)
{
@ -540,7 +540,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_me
/**
* @brief Get field zacc from hil_state_quaternion message
*
* @return Z acceleration (mg)
* @return [mG] Z acceleration
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg)
{

View file

@ -3,19 +3,19 @@
#define MAVLINK_MSG_ID_HOME_POSITION 242
MAVPACKED(
typedef struct __mavlink_home_position_t {
int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/
int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
float x; /*< Local X position of this position in the local coordinate frame*/
float y; /*< Local Y position of this position in the local coordinate frame*/
float z; /*< Local Z position of this position in the local coordinate frame*/
int32_t latitude; /*< [degE7] Latitude (WGS84)*/
int32_t longitude; /*< [degE7] Longitude (WGS84)*/
int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/
float x; /*< [m] Local X position of this position in the local coordinate frame*/
float y; /*< [m] Local Y position of this position in the local coordinate frame*/
float z; /*< [m] Local Z position of this position in the local coordinate frame*/
float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/
float 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.*/
float 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.*/
float 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.*/
}) mavlink_home_position_t;
float approach_x; /*< [m] 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.*/
float approach_y; /*< [m] 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.*/
float approach_z; /*< [m] 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.*/
} mavlink_home_position_t;
#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52
#define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52
@ -68,16 +68,16 @@ typedef struct __mavlink_home_position_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84, in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param x Local X position of this position in the local coordinate frame
* @param y Local Y position of this position in the local coordinate frame
* @param z Local Z position of this position in the local coordinate frame
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param x [m] Local X position of this position in the local coordinate frame
* @param y [m] Local Y position of this position in the local coordinate frame
* @param z [m] Local Z position of this position in the local coordinate frame
* @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
* @param 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.
* @param 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.
* @param 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.
* @param approach_x [m] 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.
* @param approach_y [m] 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.
* @param approach_z [m] 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.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -121,16 +121,16 @@ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84, in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param x Local X position of this position in the local coordinate frame
* @param y Local Y position of this position in the local coordinate frame
* @param z Local Z position of this position in the local coordinate frame
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param x [m] Local X position of this position in the local coordinate frame
* @param y [m] Local Y position of this position in the local coordinate frame
* @param z [m] Local Z position of this position in the local coordinate frame
* @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
* @param 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.
* @param 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.
* @param 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.
* @param approach_x [m] 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.
* @param approach_y [m] 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.
* @param approach_z [m] 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.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -200,16 +200,16 @@ static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id,
* @brief Send a home_position message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84, in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @param x Local X position of this position in the local coordinate frame
* @param y Local Y position of this position in the local coordinate frame
* @param z Local Z position of this position in the local coordinate frame
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param x [m] Local X position of this position in the local coordinate frame
* @param y [m] Local Y position of this position in the local coordinate frame
* @param z [m] Local Z position of this position in the local coordinate frame
* @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
* @param 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.
* @param 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.
* @param 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.
* @param approach_x [m] 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.
* @param approach_y [m] 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.
* @param approach_z [m] 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.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -306,7 +306,7 @@ static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field latitude from home_position message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return [degE7] Latitude (WGS84)
*/
static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg)
{
@ -316,7 +316,7 @@ static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_messa
/**
* @brief Get field longitude from home_position message
*
* @return Longitude (WGS84, in degrees * 1E7
* @return [degE7] Longitude (WGS84)
*/
static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_mess
/**
* @brief Get field altitude from home_position message
*
* @return Altitude (AMSL), in meters * 1000 (positive for up)
* @return [mm] Altitude (MSL). Positive for up.
*/
static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_messa
/**
* @brief Get field x from home_position message
*
* @return Local X position of this position in the local coordinate frame
* @return [m] Local X position of this position in the local coordinate frame
*/
static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg
/**
* @brief Get field y from home_position message
*
* @return Local Y position of this position in the local coordinate frame
* @return [m] Local Y position of this position in the local coordinate frame
*/
static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg
/**
* @brief Get field z from home_position message
*
* @return Local Z position of this position in the local coordinate frame
* @return [m] Local Z position of this position in the local coordinate frame
*/
static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg)
{
@ -376,7 +376,7 @@ static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t*
/**
* @brief Get field approach_x from home_position message
*
* @return 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.
* @return [m] 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.
*/
static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg)
{
@ -386,7 +386,7 @@ static inline float mavlink_msg_home_position_get_approach_x(const mavlink_messa
/**
* @brief Get field approach_y from home_position message
*
* @return 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.
* @return [m] 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.
*/
static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg)
{
@ -396,7 +396,7 @@ static inline float mavlink_msg_home_position_get_approach_y(const mavlink_messa
/**
* @brief Get field approach_z from home_position message
*
* @return 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.
* @return [m] 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.
*/
static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg)
{

View file

@ -3,17 +3,17 @@
#define MAVLINK_MSG_ID_LANDING_TARGET 149
MAVPACKED(
typedef struct __mavlink_landing_target_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/
float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/
float distance; /*< Distance to the target from the vehicle in meters*/
float size_x; /*< Size in radians of target along x-axis*/
float size_y; /*< Size in radians of target along y-axis*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float angle_x; /*< [rad] X-axis angular offset of the target from the center of the image*/
float angle_y; /*< [rad] Y-axis angular offset of the target from the center of the image*/
float distance; /*< [m] Distance to the target from the vehicle*/
float size_x; /*< [rad] Size of target along x-axis*/
float size_y; /*< [rad] Size of target along y-axis*/
uint8_t target_num; /*< The ID of the target if multiple targets are present*/
uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/
}) mavlink_landing_target_t;
uint8_t frame; /*< Coordinate frame used for following fields.*/
} mavlink_landing_target_t;
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30
#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30
@ -31,13 +31,13 @@ typedef struct __mavlink_landing_target_t {
"LANDING_TARGET", \
8, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
{ "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \
{ "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
} \
}
#else
@ -45,13 +45,13 @@ typedef struct __mavlink_landing_target_t {
"LANDING_TARGET", \
8, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
{ "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \
{ "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
} \
}
#endif
@ -62,14 +62,14 @@ typedef struct __mavlink_landing_target_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param target_num The ID of the target if multiple targets are present
* @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.
* @param angle_x X-axis angular offset (in radians) of the target from the center of the image
* @param angle_y Y-axis angular offset (in radians) of the target from the center of the image
* @param distance Distance to the target from the vehicle in meters
* @param size_x Size in radians of target along x-axis
* @param size_y Size in radians of target along y-axis
* @param frame Coordinate frame used for following fields.
* @param angle_x [rad] X-axis angular offset of the target from the center of the image
* @param angle_y [rad] Y-axis angular offset of the target from the center of the image
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param target_num The ID of the target if multiple targets are present
* @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.
* @param angle_x X-axis angular offset (in radians) of the target from the center of the image
* @param angle_y Y-axis angular offset (in radians) of the target from the center of the image
* @param distance Distance to the target from the vehicle in meters
* @param size_x Size in radians of target along x-axis
* @param size_y Size in radians of target along y-axis
* @param frame Coordinate frame used for following fields.
* @param angle_x [rad] X-axis angular offset of the target from the center of the image
* @param angle_y [rad] Y-axis angular offset of the target from the center of the image
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id,
* @brief Send a landing_target message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param target_num The ID of the target if multiple targets are present
* @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.
* @param angle_x X-axis angular offset (in radians) of the target from the center of the image
* @param angle_y Y-axis angular offset (in radians) of the target from the center of the image
* @param distance Distance to the target from the vehicle in meters
* @param size_x Size in radians of target along x-axis
* @param size_y Size in radians of target along y-axis
* @param frame Coordinate frame used for following fields.
* @param angle_x [rad] X-axis angular offset of the target from the center of the image
* @param angle_y [rad] Y-axis angular offset of the target from the center of the image
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -286,7 +286,7 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf
/**
* @brief Get field time_usec from landing_target message
*
* @return Timestamp (micros since boot or Unix epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg)
{
@ -306,7 +306,7 @@ static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_me
/**
* @brief Get field frame from landing_target message
*
* @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.
* @return Coordinate frame used for following fields.
*/
static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg)
{
@ -316,7 +316,7 @@ static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message
/**
* @brief Get field angle_x from landing_target message
*
* @return X-axis angular offset (in radians) of the target from the center of the image
* @return [rad] X-axis angular offset of the target from the center of the image
*/
static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message
/**
* @brief Get field angle_y from landing_target message
*
* @return Y-axis angular offset (in radians) of the target from the center of the image
* @return [rad] Y-axis angular offset of the target from the center of the image
*/
static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message
/**
* @brief Get field distance from landing_target message
*
* @return Distance to the target from the vehicle in meters
* @return [m] Distance to the target from the vehicle
*/
static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline float mavlink_msg_landing_target_get_distance(const mavlink_messag
/**
* @brief Get field size_x from landing_target message
*
* @return Size in radians of target along x-axis
* @return [rad] Size of target along x-axis
*/
static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_
/**
* @brief Get field size_y from landing_target message
*
* @return Size in radians of target along y-axis
* @return [rad] Size of target along y-axis
*/
static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,463 @@
#pragma once
// MESSAGE LINK_NODE_STATUS PACKING
#define MAVLINK_MSG_ID_LINK_NODE_STATUS 8
typedef struct __mavlink_link_node_status_t {
uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/
uint32_t tx_rate; /*< [bytes/s] Transmit rate*/
uint32_t rx_rate; /*< [bytes/s] Receive rate*/
uint32_t messages_sent; /*< Messages sent*/
uint32_t messages_received; /*< Messages received (estimated from counting seq)*/
uint32_t messages_lost; /*< Messages lost (estimated from counting seq)*/
uint16_t rx_parse_err; /*< [bytes] Number of bytes that could not be parsed correctly.*/
uint16_t tx_overflows; /*< [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX*/
uint16_t rx_overflows; /*< [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX*/
uint8_t tx_buf; /*< [%] Remaining free transmit buffer space*/
uint8_t rx_buf; /*< [%] Remaining free receive buffer space*/
} mavlink_link_node_status_t;
#define MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN 36
#define MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN 36
#define MAVLINK_MSG_ID_8_LEN 36
#define MAVLINK_MSG_ID_8_MIN_LEN 36
#define MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC 117
#define MAVLINK_MSG_ID_8_CRC 117
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \
8, \
"LINK_NODE_STATUS", \
11, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \
{ "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \
{ "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \
{ "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \
{ "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \
{ "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \
{ "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \
{ "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \
{ "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \
{ "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \
{ "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \
"LINK_NODE_STATUS", \
11, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \
{ "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \
{ "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \
{ "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \
{ "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \
{ "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \
{ "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \
{ "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \
{ "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \
{ "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \
{ "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \
} \
}
#endif
/**
* @brief Pack a link_node_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param timestamp [ms] Timestamp (time since system boot).
* @param tx_buf [%] Remaining free transmit buffer space
* @param rx_buf [%] Remaining free receive buffer space
* @param tx_rate [bytes/s] Transmit rate
* @param rx_rate [bytes/s] Receive rate
* @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
* @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param messages_sent Messages sent
* @param messages_received Messages received (estimated from counting seq)
* @param messages_lost Messages lost (estimated from counting seq)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_link_node_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint32_t(buf, 8, tx_rate);
_mav_put_uint32_t(buf, 12, rx_rate);
_mav_put_uint32_t(buf, 16, messages_sent);
_mav_put_uint32_t(buf, 20, messages_received);
_mav_put_uint32_t(buf, 24, messages_lost);
_mav_put_uint16_t(buf, 28, rx_parse_err);
_mav_put_uint16_t(buf, 30, tx_overflows);
_mav_put_uint16_t(buf, 32, rx_overflows);
_mav_put_uint8_t(buf, 34, tx_buf);
_mav_put_uint8_t(buf, 35, rx_buf);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
#else
mavlink_link_node_status_t packet;
packet.timestamp = timestamp;
packet.tx_rate = tx_rate;
packet.rx_rate = rx_rate;
packet.messages_sent = messages_sent;
packet.messages_received = messages_received;
packet.messages_lost = messages_lost;
packet.rx_parse_err = rx_parse_err;
packet.tx_overflows = tx_overflows;
packet.rx_overflows = rx_overflows;
packet.tx_buf = tx_buf;
packet.rx_buf = rx_buf;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
}
/**
* @brief Pack a link_node_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param timestamp [ms] Timestamp (time since system boot).
* @param tx_buf [%] Remaining free transmit buffer space
* @param rx_buf [%] Remaining free receive buffer space
* @param tx_rate [bytes/s] Transmit rate
* @param rx_rate [bytes/s] Receive rate
* @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
* @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param messages_sent Messages sent
* @param messages_received Messages received (estimated from counting seq)
* @param messages_lost Messages lost (estimated from counting seq)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_link_node_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t timestamp,uint8_t tx_buf,uint8_t rx_buf,uint32_t tx_rate,uint32_t rx_rate,uint16_t rx_parse_err,uint16_t tx_overflows,uint16_t rx_overflows,uint32_t messages_sent,uint32_t messages_received,uint32_t messages_lost)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint32_t(buf, 8, tx_rate);
_mav_put_uint32_t(buf, 12, rx_rate);
_mav_put_uint32_t(buf, 16, messages_sent);
_mav_put_uint32_t(buf, 20, messages_received);
_mav_put_uint32_t(buf, 24, messages_lost);
_mav_put_uint16_t(buf, 28, rx_parse_err);
_mav_put_uint16_t(buf, 30, tx_overflows);
_mav_put_uint16_t(buf, 32, rx_overflows);
_mav_put_uint8_t(buf, 34, tx_buf);
_mav_put_uint8_t(buf, 35, rx_buf);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
#else
mavlink_link_node_status_t packet;
packet.timestamp = timestamp;
packet.tx_rate = tx_rate;
packet.rx_rate = rx_rate;
packet.messages_sent = messages_sent;
packet.messages_received = messages_received;
packet.messages_lost = messages_lost;
packet.rx_parse_err = rx_parse_err;
packet.tx_overflows = tx_overflows;
packet.rx_overflows = rx_overflows;
packet.tx_buf = tx_buf;
packet.rx_buf = rx_buf;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
}
/**
* @brief Encode a link_node_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param link_node_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_link_node_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status)
{
return mavlink_msg_link_node_status_pack(system_id, component_id, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
}
/**
* @brief Encode a link_node_status struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param link_node_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_link_node_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status)
{
return mavlink_msg_link_node_status_pack_chan(system_id, component_id, chan, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
}
/**
* @brief Send a link_node_status message
* @param chan MAVLink channel to send the message
*
* @param timestamp [ms] Timestamp (time since system boot).
* @param tx_buf [%] Remaining free transmit buffer space
* @param rx_buf [%] Remaining free receive buffer space
* @param tx_rate [bytes/s] Transmit rate
* @param rx_rate [bytes/s] Receive rate
* @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
* @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
* @param messages_sent Messages sent
* @param messages_received Messages received (estimated from counting seq)
* @param messages_lost Messages lost (estimated from counting seq)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_link_node_status_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint32_t(buf, 8, tx_rate);
_mav_put_uint32_t(buf, 12, rx_rate);
_mav_put_uint32_t(buf, 16, messages_sent);
_mav_put_uint32_t(buf, 20, messages_received);
_mav_put_uint32_t(buf, 24, messages_lost);
_mav_put_uint16_t(buf, 28, rx_parse_err);
_mav_put_uint16_t(buf, 30, tx_overflows);
_mav_put_uint16_t(buf, 32, rx_overflows);
_mav_put_uint8_t(buf, 34, tx_buf);
_mav_put_uint8_t(buf, 35, rx_buf);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
#else
mavlink_link_node_status_t packet;
packet.timestamp = timestamp;
packet.tx_rate = tx_rate;
packet.rx_rate = rx_rate;
packet.messages_sent = messages_sent;
packet.messages_received = messages_received;
packet.messages_lost = messages_lost;
packet.rx_parse_err = rx_parse_err;
packet.tx_overflows = tx_overflows;
packet.rx_overflows = rx_overflows;
packet.tx_buf = tx_buf;
packet.rx_buf = rx_buf;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
#endif
}
/**
* @brief Send a link_node_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_link_node_status_send_struct(mavlink_channel_t chan, const mavlink_link_node_status_t* link_node_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_link_node_status_send(chan, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)link_node_status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_link_node_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint32_t(buf, 8, tx_rate);
_mav_put_uint32_t(buf, 12, rx_rate);
_mav_put_uint32_t(buf, 16, messages_sent);
_mav_put_uint32_t(buf, 20, messages_received);
_mav_put_uint32_t(buf, 24, messages_lost);
_mav_put_uint16_t(buf, 28, rx_parse_err);
_mav_put_uint16_t(buf, 30, tx_overflows);
_mav_put_uint16_t(buf, 32, rx_overflows);
_mav_put_uint8_t(buf, 34, tx_buf);
_mav_put_uint8_t(buf, 35, rx_buf);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
#else
mavlink_link_node_status_t *packet = (mavlink_link_node_status_t *)msgbuf;
packet->timestamp = timestamp;
packet->tx_rate = tx_rate;
packet->rx_rate = rx_rate;
packet->messages_sent = messages_sent;
packet->messages_received = messages_received;
packet->messages_lost = messages_lost;
packet->rx_parse_err = rx_parse_err;
packet->tx_overflows = tx_overflows;
packet->rx_overflows = rx_overflows;
packet->tx_buf = tx_buf;
packet->rx_buf = rx_buf;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE LINK_NODE_STATUS UNPACKING
/**
* @brief Get field timestamp from link_node_status message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint64_t mavlink_msg_link_node_status_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field tx_buf from link_node_status message
*
* @return [%] Remaining free transmit buffer space
*/
static inline uint8_t mavlink_msg_link_node_status_get_tx_buf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field rx_buf from link_node_status message
*
* @return [%] Remaining free receive buffer space
*/
static inline uint8_t mavlink_msg_link_node_status_get_rx_buf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Get field tx_rate from link_node_status message
*
* @return [bytes/s] Transmit rate
*/
static inline uint32_t mavlink_msg_link_node_status_get_tx_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field rx_rate from link_node_status message
*
* @return [bytes/s] Receive rate
*/
static inline uint32_t mavlink_msg_link_node_status_get_rx_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
/**
* @brief Get field rx_parse_err from link_node_status message
*
* @return [bytes] Number of bytes that could not be parsed correctly.
*/
static inline uint16_t mavlink_msg_link_node_status_get_rx_parse_err(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field tx_overflows from link_node_status message
*
* @return [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
*/
static inline uint16_t mavlink_msg_link_node_status_get_tx_overflows(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
/**
* @brief Get field rx_overflows from link_node_status message
*
* @return [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
*/
static inline uint16_t mavlink_msg_link_node_status_get_rx_overflows(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 32);
}
/**
* @brief Get field messages_sent from link_node_status message
*
* @return Messages sent
*/
static inline uint32_t mavlink_msg_link_node_status_get_messages_sent(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 16);
}
/**
* @brief Get field messages_received from link_node_status message
*
* @return Messages received (estimated from counting seq)
*/
static inline uint32_t mavlink_msg_link_node_status_get_messages_received(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field messages_lost from link_node_status message
*
* @return Messages lost (estimated from counting seq)
*/
static inline uint32_t mavlink_msg_link_node_status_get_messages_lost(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 24);
}
/**
* @brief Decode a link_node_status message into a struct
*
* @param msg The message to decode
* @param link_node_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_link_node_status_decode(const mavlink_message_t* msg, mavlink_link_node_status_t* link_node_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
link_node_status->timestamp = mavlink_msg_link_node_status_get_timestamp(msg);
link_node_status->tx_rate = mavlink_msg_link_node_status_get_tx_rate(msg);
link_node_status->rx_rate = mavlink_msg_link_node_status_get_rx_rate(msg);
link_node_status->messages_sent = mavlink_msg_link_node_status_get_messages_sent(msg);
link_node_status->messages_received = mavlink_msg_link_node_status_get_messages_received(msg);
link_node_status->messages_lost = mavlink_msg_link_node_status_get_messages_lost(msg);
link_node_status->rx_parse_err = mavlink_msg_link_node_status_get_rx_parse_err(msg);
link_node_status->tx_overflows = mavlink_msg_link_node_status_get_tx_overflows(msg);
link_node_status->rx_overflows = mavlink_msg_link_node_status_get_rx_overflows(msg);
link_node_status->tx_buf = mavlink_msg_link_node_status_get_tx_buf(msg);
link_node_status->rx_buf = mavlink_msg_link_node_status_get_rx_buf(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN;
memset(link_node_status, 0, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
memcpy(link_node_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32
MAVPACKED(
typedef struct __mavlink_local_position_ned_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
float x; /*< X Position*/
float y; /*< Y Position*/
float z; /*< Z Position*/
float vx; /*< X Speed*/
float vy; /*< Y Speed*/
float vz; /*< Z Speed*/
}) mavlink_local_position_ned_t;
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float x; /*< [m] X Position*/
float y; /*< [m] Y Position*/
float z; /*< [m] Z Position*/
float vx; /*< [m/s] X Speed*/
float vy; /*< [m/s] Y Speed*/
float vz; /*< [m/s] Z Speed*/
} mavlink_local_position_ned_t;
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28
@ -59,13 +59,13 @@ typedef struct __mavlink_local_position_ned_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system
* @brief Send a local_position_ned message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *ms
/**
* @brief Get field time_boot_ms from local_position_ned message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mav
/**
* @brief Get field x from local_position_ned message
*
* @return X Position
* @return [m] X Position
*/
static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t
/**
* @brief Get field y from local_position_ned message
*
* @return Y Position
* @return [m] Y Position
*/
static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t
/**
* @brief Get field z from local_position_ned message
*
* @return Z Position
* @return [m] Z Position
*/
static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t
/**
* @brief Get field vx from local_position_ned message
*
* @return X Speed
* @return [m/s] X Speed
*/
static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_
/**
* @brief Get field vy from local_position_ned message
*
* @return Y Speed
* @return [m/s] Y Speed
*/
static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_
/**
* @brief Get field vz from local_position_ned message
*
* @return Z Speed
* @return [m/s] Z Speed
*/
static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg)
{

View file

@ -3,21 +3,21 @@
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
MAVPACKED(
typedef struct __mavlink_local_position_ned_cov_t {
uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/
float x; /*< X Position*/
float y; /*< Y Position*/
float z; /*< Z Position*/
float vx; /*< X Speed (m/s)*/
float vy; /*< Y Speed (m/s)*/
float vz; /*< Z Speed (m/s)*/
float ax; /*< X Acceleration (m/s^2)*/
float ay; /*< Y Acceleration (m/s^2)*/
float az; /*< Z Acceleration (m/s^2)*/
float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float x; /*< [m] X Position*/
float y; /*< [m] Y Position*/
float z; /*< [m] Z Position*/
float vx; /*< [m/s] X Speed*/
float vy; /*< [m/s] Y Speed*/
float vz; /*< [m/s] Z Speed*/
float ax; /*< [m/s/s] X Acceleration*/
float ay; /*< [m/s/s] Y Acceleration*/
float az; /*< [m/s/s] Z Acceleration*/
float covariance[45]; /*< Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
}) mavlink_local_position_ned_cov_t;
} mavlink_local_position_ned_cov_t;
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225
@ -35,6 +35,7 @@ typedef struct __mavlink_local_position_ned_cov_t {
"LOCAL_POSITION_NED_COV", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \
@ -45,7 +46,6 @@ typedef struct __mavlink_local_position_ned_cov_t {
{ "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
{ "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
} \
}
#else
@ -53,6 +53,7 @@ typedef struct __mavlink_local_position_ned_cov_t {
"LOCAL_POSITION_NED_COV", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \
@ -63,7 +64,6 @@ typedef struct __mavlink_local_position_ned_cov_t {
{ "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
{ "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
} \
}
#endif
@ -74,18 +74,18 @@ typedef struct __mavlink_local_position_ned_cov_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
* @param ax [m/s/s] X Acceleration
* @param ay [m/s/s] Y Acceleration
* @param az [m/s/s] Z Acceleration
* @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -133,18 +133,18 @@ static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
* @param ax [m/s/s] X Acceleration
* @param ay [m/s/s] Y Acceleration
* @param az [m/s/s] Z Acceleration
* @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -218,18 +218,18 @@ static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t sy
* @brief Send a local_position_ned_cov message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since system boot or since UNIX epoch)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param vx [m/s] X Speed
* @param vy [m/s] Y Speed
* @param vz [m/s] Z Speed
* @param ax [m/s/s] X Acceleration
* @param ay [m/s/s] Y Acceleration
* @param az [m/s/s] Z Acceleration
* @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -334,7 +334,7 @@ static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t
/**
* @brief Get field time_usec from local_position_ned_cov message
*
* @return Timestamp (microseconds since system boot or since UNIX epoch)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg)
{
@ -354,7 +354,7 @@ static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(cons
/**
* @brief Get field x from local_position_ned_cov message
*
* @return X Position
* @return [m] X Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
{
@ -364,7 +364,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_messa
/**
* @brief Get field y from local_position_ned_cov message
*
* @return Y Position
* @return [m] Y Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
{
@ -374,7 +374,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_messa
/**
* @brief Get field z from local_position_ned_cov message
*
* @return Z Position
* @return [m] Z Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
{
@ -384,7 +384,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_messa
/**
* @brief Get field vx from local_position_ned_cov message
*
* @return X Speed (m/s)
* @return [m/s] X Speed
*/
static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
{
@ -394,7 +394,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_mess
/**
* @brief Get field vy from local_position_ned_cov message
*
* @return Y Speed (m/s)
* @return [m/s] Y Speed
*/
static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
{
@ -404,7 +404,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_mess
/**
* @brief Get field vz from local_position_ned_cov message
*
* @return Z Speed (m/s)
* @return [m/s] Z Speed
*/
static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
{
@ -414,7 +414,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_mess
/**
* @brief Get field ax from local_position_ned_cov message
*
* @return X Acceleration (m/s^2)
* @return [m/s/s] X Acceleration
*/
static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg)
{
@ -424,7 +424,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_mess
/**
* @brief Get field ay from local_position_ned_cov message
*
* @return Y Acceleration (m/s^2)
* @return [m/s/s] Y Acceleration
*/
static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg)
{
@ -434,7 +434,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_mess
/**
* @brief Get field az from local_position_ned_cov message
*
* @return Z Acceleration (m/s^2)
* @return [m/s/s] Z Acceleration
*/
static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg)
{
@ -444,7 +444,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_mess
/**
* @brief Get field covariance from local_position_ned_cov message
*
* @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @return Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89
MAVPACKED(
typedef struct __mavlink_local_position_ned_system_global_offset_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
float x; /*< X Position*/
float y; /*< Y Position*/
float z; /*< Z Position*/
float roll; /*< Roll*/
float pitch; /*< Pitch*/
float yaw; /*< Yaw*/
}) mavlink_local_position_ned_system_global_offset_t;
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float x; /*< [m] X Position*/
float y; /*< [m] Y Position*/
float z; /*< [m] Z Position*/
float roll; /*< [rad] Roll*/
float pitch; /*< [rad] Pitch*/
float yaw; /*< [rad] Yaw*/
} mavlink_local_position_ned_system_global_offset_t;
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN 28
@ -59,13 +59,13 @@ typedef struct __mavlink_local_position_ned_system_global_offset_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param roll [rad] Roll
* @param pitch [rad] Pitch
* @param yaw [rad] Yaw
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param roll [rad] Roll
* @param pitch [rad] Pitch
* @param yaw [rad] Yaw
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encod
* @brief Send a local_position_ned_system_global_offset message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param roll [rad] Roll
* @param pitch [rad] Pitch
* @param yaw [rad] Yaw
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -272,7 +272,7 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(
/**
* @brief Get field time_boot_ms from local_position_ned_system_global_offset message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_t
/**
* @brief Get field x from local_position_ned_system_global_offset message
*
* @return X Position
* @return [m] X Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(co
/**
* @brief Get field y from local_position_ned_system_global_offset message
*
* @return Y Position
* @return [m] Y Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(co
/**
* @brief Get field z from local_position_ned_system_global_offset message
*
* @return Z Position
* @return [m] Z Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg)
{
@ -312,7 +312,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(co
/**
* @brief Get field roll from local_position_ned_system_global_offset message
*
* @return Roll
* @return [rad] Roll
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg)
{
@ -322,7 +322,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll
/**
* @brief Get field pitch from local_position_ned_system_global_offset message
*
* @return Pitch
* @return [rad] Pitch
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg)
{
@ -332,7 +332,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitc
/**
* @brief Get field yaw from local_position_ned_system_global_offset message
*
* @return Yaw
* @return [rad] Yaw
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_LOG_DATA 120
MAVPACKED(
typedef struct __mavlink_log_data_t {
uint32_t ofs; /*< Offset into the log*/
uint16_t id; /*< Log id (from LOG_ENTRY reply)*/
uint8_t count; /*< Number of bytes (zero for end of log)*/
uint8_t count; /*< [bytes] Number of bytes (zero for end of log)*/
uint8_t data[90]; /*< log data*/
}) mavlink_log_data_t;
} mavlink_log_data_t;
#define MAVLINK_MSG_ID_LOG_DATA_LEN 97
#define MAVLINK_MSG_ID_LOG_DATA_MIN_LEN 97
@ -26,8 +26,8 @@ typedef struct __mavlink_log_data_t {
120, \
"LOG_DATA", \
4, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \
} \
@ -36,8 +36,8 @@ typedef struct __mavlink_log_data_t {
#define MAVLINK_MESSAGE_INFO_LOG_DATA { \
"LOG_DATA", \
4, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \
} \
@ -52,7 +52,7 @@ typedef struct __mavlink_log_data_t {
*
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param count [bytes] Number of bytes (zero for end of log)
* @param data log data
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t comp
* @param msg The MAVLink message to compress the data into
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param count [bytes] Number of bytes (zero for end of log)
* @param data log data
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -148,7 +148,7 @@ static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8
*
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param count [bytes] Number of bytes (zero for end of log)
* @param data log data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -242,7 +242,7 @@ static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg
/**
* @brief Get field count from log_data message
*
* @return Number of bytes (zero for end of log)
* @return [bytes] Number of bytes (zero for end of log)
*/
static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg)
{

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_LOG_ENTRY 118
MAVPACKED(
typedef struct __mavlink_log_entry_t {
uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/
uint32_t size; /*< Size of the log (may be approximate) in bytes*/
uint32_t time_utc; /*< [s] UTC timestamp of log since 1970, or 0 if not available*/
uint32_t size; /*< [bytes] Size of the log (may be approximate)*/
uint16_t id; /*< Log id*/
uint16_t num_logs; /*< Total number of logs*/
uint16_t last_log_num; /*< High log number*/
}) mavlink_log_entry_t;
} mavlink_log_entry_t;
#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14
#define MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN 14
@ -27,22 +27,22 @@ typedef struct __mavlink_log_entry_t {
118, \
"LOG_ENTRY", \
5, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \
{ "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \
{ "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \
{ "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \
"LOG_ENTRY", \
5, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \
{ { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \
{ "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \
{ "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \
{ "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \
} \
}
#endif
@ -56,8 +56,8 @@ typedef struct __mavlink_log_entry_t {
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
* @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available
* @param size [bytes] Size of the log (may be approximate)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -96,8 +96,8 @@ static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t com
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
* @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available
* @param size [bytes] Size of the log (may be approximate)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -162,8 +162,8 @@ static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
* @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available
* @param size [bytes] Size of the log (may be approximate)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -274,7 +274,7 @@ static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_mess
/**
* @brief Get field time_utc from log_entry message
*
* @return UTC timestamp of log in seconds since 1970, or 0 if not available
* @return [s] UTC timestamp of log since 1970, or 0 if not available
*/
static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg)
{
@ -284,7 +284,7 @@ static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_
/**
* @brief Get field size from log_entry message
*
* @return Size of the log (may be approximate) in bytes
* @return [bytes] Size of the log (may be approximate)
*/
static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_LOG_ERASE 121
MAVPACKED(
typedef struct __mavlink_log_erase_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_log_erase_t;
} mavlink_log_erase_t;
#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2
#define MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN 2

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119
MAVPACKED(
typedef struct __mavlink_log_request_data_t {
uint32_t ofs; /*< Offset into the log*/
uint32_t count; /*< Number of bytes*/
uint32_t count; /*< [bytes] Number of bytes*/
uint16_t id; /*< Log id (from LOG_ENTRY reply)*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_log_request_data_t;
} mavlink_log_request_data_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12
@ -27,22 +27,22 @@ typedef struct __mavlink_log_request_data_t {
119, \
"LOG_REQUEST_DATA", \
5, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
{ "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \
"LOG_REQUEST_DATA", \
5, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
{ "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
} \
}
#endif
@ -57,7 +57,7 @@ typedef struct __mavlink_log_request_data_t {
* @param target_component Component ID
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
* @param count [bytes] Number of bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint
* @param target_component Component ID
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
* @param count [bytes] Number of bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -163,7 +163,7 @@ static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_i
* @param target_component Component ID
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
* @param count [bytes] Number of bytes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -284,7 +284,7 @@ static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_messag
/**
* @brief Get field count from log_request_data message
*
* @return Number of bytes
* @return [bytes] Number of bytes
*/
static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_LOG_REQUEST_END 122
MAVPACKED(
typedef struct __mavlink_log_request_end_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_log_request_end_t;
} mavlink_log_request_end_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2
#define MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN 2

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117
MAVPACKED(
typedef struct __mavlink_log_request_list_t {
uint16_t start; /*< First log id (0 for first available)*/
uint16_t end; /*< Last log id (0xffff for last available)*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_log_request_list_t;
} mavlink_log_request_list_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN 6
@ -26,20 +26,20 @@ typedef struct __mavlink_log_request_list_t {
117, \
"LOG_REQUEST_LIST", \
4, \
{ { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \
{ "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \
"LOG_REQUEST_LIST", \
4, \
{ { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \
{ "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
} \
}
#endif

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_MANUAL_CONTROL 69
MAVPACKED(
typedef struct __mavlink_manual_control_t {
int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/
int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/
@ -11,7 +11,7 @@ typedef struct __mavlink_manual_control_t {
int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/
uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/
uint8_t target; /*< The system to be controlled.*/
}) mavlink_manual_control_t;
} mavlink_manual_control_t;
#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11
#define MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN 11
@ -28,24 +28,24 @@ typedef struct __mavlink_manual_control_t {
69, \
"MANUAL_CONTROL", \
6, \
{ { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
{ "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \
{ "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \
{ "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
"MANUAL_CONTROL", \
6, \
{ { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
{ "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \
{ "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \
{ "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
} \
}
#endif

View file

@ -3,16 +3,16 @@
#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81
MAVPACKED(
typedef struct __mavlink_manual_setpoint_t {
uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/
float roll; /*< Desired roll rate in radians per second*/
float pitch; /*< Desired pitch rate in radians per second*/
float yaw; /*< Desired yaw rate in radians per second*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float roll; /*< [rad/s] Desired roll rate*/
float pitch; /*< [rad/s] Desired pitch rate*/
float yaw; /*< [rad/s] Desired yaw rate*/
float thrust; /*< Collective thrust, normalized to 0 .. 1*/
uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/
uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/
}) mavlink_manual_setpoint_t;
} mavlink_manual_setpoint_t;
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN 22
@ -59,10 +59,10 @@ typedef struct __mavlink_manual_setpoint_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad/s] Desired roll rate
* @param pitch [rad/s] Desired pitch rate
* @param yaw [rad/s] Desired yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
@ -105,10 +105,10 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad/s] Desired roll rate
* @param pitch [rad/s] Desired pitch rate
* @param yaw [rad/s] Desired yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
@ -177,10 +177,10 @@ static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id
* @brief Send a manual_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [rad/s] Desired roll rate
* @param pitch [rad/s] Desired pitch rate
* @param yaw [rad/s] Desired yaw rate
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
@ -272,7 +272,7 @@ static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbu
/**
* @brief Get field time_boot_ms from manual_setpoint message
*
* @return Timestamp in milliseconds since system boot
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlin
/**
* @brief Get field roll from manual_setpoint message
*
* @return Desired roll rate in radians per second
* @return [rad/s] Desired roll rate
*/
static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg)
{
@ -292,7 +292,7 @@ static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t
/**
* @brief Get field pitch from manual_setpoint message
*
* @return Desired pitch rate in radians per second
* @return [rad/s] Desired pitch rate
*/
static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg)
{
@ -302,7 +302,7 @@ static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_
/**
* @brief Get field yaw from manual_setpoint message
*
* @return Desired yaw rate in radians per second
* @return [rad/s] Desired yaw rate
*/
static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_MEMORY_VECT 249
MAVPACKED(
typedef struct __mavlink_memory_vect_t {
uint16_t address; /*< Starting address of the debug variables*/
uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/
uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/
int8_t value[32]; /*< Memory contents at specified address*/
}) mavlink_memory_vect_t;
} mavlink_memory_vect_t;
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
#define MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN 36

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244
MAVPACKED(
typedef struct __mavlink_message_interval_t {
int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/
int32_t interval_us; /*< [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/
uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/
}) mavlink_message_interval_t;
} mavlink_message_interval_t;
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN 6
@ -24,16 +24,16 @@ typedef struct __mavlink_message_interval_t {
244, \
"MESSAGE_INTERVAL", \
2, \
{ { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
{ "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
{ { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
{ "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \
"MESSAGE_INTERVAL", \
2, \
{ { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
{ "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
{ { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
{ "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
} \
}
#endif
@ -45,7 +45,7 @@ typedef struct __mavlink_message_interval_t {
* @param msg The MAVLink message to compress the data into
*
* @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
* @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
* @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_i
* @param chan MAVLink channel to send the message
*
* @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
* @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -212,7 +212,7 @@ static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink
/**
* @brief Get field interval_us from message_interval message
*
* @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
* @return [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
*/
static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_MISSION_ACK 47
MAVPACKED(
typedef struct __mavlink_mission_ack_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t type; /*< See MAV_MISSION_RESULT enum*/
}) mavlink_mission_ack_t;
uint8_t type; /*< Mission result.*/
} mavlink_mission_ack_t;
#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3
#define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3
@ -49,7 +49,7 @@ typedef struct __mavlink_mission_ack_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
* @param type Mission result.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -83,7 +83,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
* @param type Mission result.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -143,7 +143,7 @@ static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, ui
*
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
* @param type Mission result.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink
/**
* @brief Get field type from mission_ack message
*
* @return See MAV_MISSION_RESULT enum
* @return Mission result.
*/
static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,313 @@
#pragma once
// MESSAGE MISSION_CHANGED PACKING
#define MAVLINK_MSG_ID_MISSION_CHANGED 52
typedef struct __mavlink_mission_changed_t {
int16_t start_index; /*< Start index for partial mission change (-1 for all items).*/
int16_t end_index; /*< End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.*/
uint8_t origin_sysid; /*< System ID of the author of the new mission.*/
uint8_t origin_compid; /*< Compnent ID of the author of the new mission.*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_changed_t;
#define MAVLINK_MSG_ID_MISSION_CHANGED_LEN 7
#define MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN 7
#define MAVLINK_MSG_ID_52_LEN 7
#define MAVLINK_MSG_ID_52_MIN_LEN 7
#define MAVLINK_MSG_ID_MISSION_CHANGED_CRC 132
#define MAVLINK_MSG_ID_52_CRC 132
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MISSION_CHANGED { \
52, \
"MISSION_CHANGED", \
5, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_changed_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_changed_t, end_index) }, \
{ "origin_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_changed_t, origin_sysid) }, \
{ "origin_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_changed_t, origin_compid) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_changed_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_CHANGED { \
"MISSION_CHANGED", \
5, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_changed_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_changed_t, end_index) }, \
{ "origin_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_changed_t, origin_sysid) }, \
{ "origin_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_changed_t, origin_compid) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_changed_t, mission_type) }, \
} \
}
#endif
/**
* @brief Pack a mission_changed message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param start_index Start index for partial mission change (-1 for all items).
* @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.
* @param origin_sysid System ID of the author of the new mission.
* @param origin_compid Compnent ID of the author of the new mission.
* @param mission_type Mission type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_changed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, origin_sysid);
_mav_put_uint8_t(buf, 5, origin_compid);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CHANGED_LEN);
#else
mavlink_mission_changed_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.origin_sysid = origin_sysid;
packet.origin_compid = origin_compid;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CHANGED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CHANGED;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
}
/**
* @brief Pack a mission_changed message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param start_index Start index for partial mission change (-1 for all items).
* @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.
* @param origin_sysid System ID of the author of the new mission.
* @param origin_compid Compnent ID of the author of the new mission.
* @param mission_type Mission type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_changed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t start_index,int16_t end_index,uint8_t origin_sysid,uint8_t origin_compid,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, origin_sysid);
_mav_put_uint8_t(buf, 5, origin_compid);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CHANGED_LEN);
#else
mavlink_mission_changed_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.origin_sysid = origin_sysid;
packet.origin_compid = origin_compid;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CHANGED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CHANGED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
}
/**
* @brief Encode a mission_changed struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_changed C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_changed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_changed_t* mission_changed)
{
return mavlink_msg_mission_changed_pack(system_id, component_id, msg, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type);
}
/**
* @brief Encode a mission_changed struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param mission_changed C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_changed_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_changed_t* mission_changed)
{
return mavlink_msg_mission_changed_pack_chan(system_id, component_id, chan, msg, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type);
}
/**
* @brief Send a mission_changed message
* @param chan MAVLink channel to send the message
*
* @param start_index Start index for partial mission change (-1 for all items).
* @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.
* @param origin_sysid System ID of the author of the new mission.
* @param origin_compid Compnent ID of the author of the new mission.
* @param mission_type Mission type.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mission_changed_send(mavlink_channel_t chan, int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, origin_sysid);
_mav_put_uint8_t(buf, 5, origin_compid);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, buf, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
#else
mavlink_mission_changed_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.origin_sysid = origin_sysid;
packet.origin_compid = origin_compid;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
#endif
}
/**
* @brief Send a mission_changed message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mission_changed_send_struct(mavlink_channel_t chan, const mavlink_mission_changed_t* mission_changed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_changed_send(chan, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)mission_changed, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
#endif
}
#if MAVLINK_MSG_ID_MISSION_CHANGED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_changed_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, origin_sysid);
_mav_put_uint8_t(buf, 5, origin_compid);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, buf, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
#else
mavlink_mission_changed_t *packet = (mavlink_mission_changed_t *)msgbuf;
packet->start_index = start_index;
packet->end_index = end_index;
packet->origin_sysid = origin_sysid;
packet->origin_compid = origin_compid;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)packet, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC);
#endif
}
#endif
#endif
// MESSAGE MISSION_CHANGED UNPACKING
/**
* @brief Get field start_index from mission_changed message
*
* @return Start index for partial mission change (-1 for all items).
*/
static inline int16_t mavlink_msg_mission_changed_get_start_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
/**
* @brief Get field end_index from mission_changed message
*
* @return End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.
*/
static inline int16_t mavlink_msg_mission_changed_get_end_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field origin_sysid from mission_changed message
*
* @return System ID of the author of the new mission.
*/
static inline uint8_t mavlink_msg_mission_changed_get_origin_sysid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field origin_compid from mission_changed message
*
* @return Compnent ID of the author of the new mission.
*/
static inline uint8_t mavlink_msg_mission_changed_get_origin_compid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field mission_type from mission_changed message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_changed_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Decode a mission_changed message into a struct
*
* @param msg The message to decode
* @param mission_changed C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_changed_decode(const mavlink_message_t* msg, mavlink_mission_changed_t* mission_changed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mission_changed->start_index = mavlink_msg_mission_changed_get_start_index(msg);
mission_changed->end_index = mavlink_msg_mission_changed_get_end_index(msg);
mission_changed->origin_sysid = mavlink_msg_mission_changed_get_origin_sysid(msg);
mission_changed->origin_compid = mavlink_msg_mission_changed_get_origin_compid(msg);
mission_changed->mission_type = mavlink_msg_mission_changed_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CHANGED_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CHANGED_LEN;
memset(mission_changed, 0, MAVLINK_MSG_ID_MISSION_CHANGED_LEN);
memcpy(mission_changed, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45
MAVPACKED(
typedef struct __mavlink_mission_clear_all_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_clear_all_t;
} mavlink_mission_clear_all_t;
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_MISSION_COUNT 44
MAVPACKED(
typedef struct __mavlink_mission_count_t {
uint16_t count; /*< Number of mission items in the sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_count_t;
} mavlink_mission_count_t;
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
#define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4
@ -25,18 +25,18 @@ typedef struct __mavlink_mission_count_t {
44, \
"MISSION_COUNT", \
3, \
{ { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
"MISSION_COUNT", \
3, \
{ { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
} \
}
#endif

View file

@ -3,10 +3,10 @@
#define MAVLINK_MSG_ID_MISSION_CURRENT 42
MAVPACKED(
typedef struct __mavlink_mission_current_t {
uint16_t seq; /*< Sequence*/
}) mavlink_mission_current_t;
} mavlink_mission_current_t;
#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2
#define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2

View file

@ -3,23 +3,23 @@
#define MAVLINK_MSG_ID_MISSION_ITEM 39
MAVPACKED(
typedef struct __mavlink_mission_item_t {
float param1; /*< PARAM1, see MAV_CMD enum*/
float param2; /*< PARAM2, see MAV_CMD enum*/
float param3; /*< PARAM3, see MAV_CMD enum*/
float param4; /*< PARAM4, see MAV_CMD enum*/
float x; /*< PARAM5 / local: x position, global: latitude*/
float y; /*< PARAM6 / y position: global: longitude*/
float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/
float x; /*< PARAM5 / local: X coordinate, global: latitude*/
float y; /*< PARAM6 / local: Y coordinate, global: longitude*/
float z; /*< PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).*/
uint16_t seq; /*< Sequence*/
uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/
uint16_t command; /*< The scheduled action for the waypoint.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/
uint8_t frame; /*< The coordinate system of the waypoint.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< autocontinue to next wp*/
}) mavlink_mission_item_t;
uint8_t autocontinue; /*< Autocontinue to next waypoint*/
} mavlink_mission_item_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37
@ -36,40 +36,40 @@ typedef struct __mavlink_mission_item_t {
39, \
"MISSION_ITEM", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \
"MISSION_ITEM", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
} \
}
#endif
@ -83,17 +83,17 @@ typedef struct __mavlink_mission_item_t {
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -150,17 +150,17 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -243,17 +243,17 @@ static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, u
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t*
/**
* @brief Get field frame from mission_item message
*
* @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @return The coordinate system of the waypoint.
*/
static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg)
{
@ -410,7 +410,7 @@ static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t
/**
* @brief Get field command from mission_item message
*
* @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @return The scheduled action for the waypoint.
*/
static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg)
{
@ -430,7 +430,7 @@ static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message
/**
* @brief Get field autocontinue from mission_item message
*
* @return autocontinue to next wp
* @return Autocontinue to next waypoint
*/
static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg)
{
@ -480,7 +480,7 @@ static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t*
/**
* @brief Get field x from mission_item message
*
* @return PARAM5 / local: x position, global: latitude
* @return PARAM5 / local: X coordinate, global: latitude
*/
static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg)
{
@ -490,7 +490,7 @@ static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg)
/**
* @brief Get field y from mission_item message
*
* @return PARAM6 / y position: global: longitude
* @return PARAM6 / local: Y coordinate, global: longitude
*/
static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg)
{
@ -500,7 +500,7 @@ static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg)
/**
* @brief Get field z from mission_item message
*
* @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @return PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
*/
static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg)
{

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73
MAVPACKED(
typedef struct __mavlink_mission_item_int_t {
float param1; /*< PARAM1, see MAV_CMD enum*/
float param2; /*< PARAM2, see MAV_CMD enum*/
@ -13,13 +13,13 @@ typedef struct __mavlink_mission_item_int_t {
int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/
float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/
uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/
uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/
uint16_t command; /*< The scheduled action for the waypoint.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/
uint8_t frame; /*< The coordinate system of the waypoint.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< autocontinue to next wp*/
}) mavlink_mission_item_int_t;
uint8_t autocontinue; /*< Autocontinue to next waypoint*/
} mavlink_mission_item_int_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37
@ -36,40 +36,40 @@ typedef struct __mavlink_mission_item_int_t {
73, \
"MISSION_ITEM_INT", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
"MISSION_ITEM_INT", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
} \
}
#endif
@ -83,10 +83,10 @@ typedef struct __mavlink_mission_item_int_t {
* @param target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint
* @param target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -243,10 +243,10 @@ static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_i
* @param target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param frame The coordinate system of the waypoint.
* @param command The scheduled action for the waypoint.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param autocontinue Autocontinue to next waypoint
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_messag
/**
* @brief Get field frame from mission_item_int message
*
* @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @return The coordinate system of the waypoint.
*/
static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg)
{
@ -410,7 +410,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_messa
/**
* @brief Get field command from mission_item_int message
*
* @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @return The scheduled action for the waypoint.
*/
static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg)
{
@ -430,7 +430,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_mes
/**
* @brief Get field autocontinue from mission_item_int message
*
* @return autocontinue to next wp
* @return Autocontinue to next waypoint
*/
static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg)
{

View file

@ -3,10 +3,10 @@
#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46
MAVPACKED(
typedef struct __mavlink_mission_item_reached_t {
uint16_t seq; /*< Sequence*/
}) mavlink_mission_item_reached_t;
} mavlink_mission_item_reached_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2
#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN 2

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_MISSION_REQUEST 40
MAVPACKED(
typedef struct __mavlink_mission_request_t {
uint16_t seq; /*< Sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_request_t;
} mavlink_mission_request_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4
@ -25,18 +25,18 @@ typedef struct __mavlink_mission_request_t {
40, \
"MISSION_REQUEST", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
"MISSION_REQUEST", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
} \
}
#endif

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51
MAVPACKED(
typedef struct __mavlink_mission_request_int_t {
uint16_t seq; /*< Sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_request_int_t;
} mavlink_mission_request_int_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4
@ -25,18 +25,18 @@ typedef struct __mavlink_mission_request_int_t {
51, \
"MISSION_REQUEST_INT", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \
"MISSION_REQUEST_INT", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
} \
}
#endif

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43
MAVPACKED(
typedef struct __mavlink_mission_request_list_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_request_list_t;
} mavlink_mission_request_list_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37
MAVPACKED(
typedef struct __mavlink_mission_request_partial_list_t {
int16_t start_index; /*< Start index, 0 by default*/
int16_t start_index; /*< Start index*/
int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_request_partial_list_t;
} mavlink_mission_request_partial_list_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6
@ -26,20 +26,20 @@ typedef struct __mavlink_mission_request_partial_list_t {
37, \
"MISSION_REQUEST_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \
{ "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
"MISSION_REQUEST_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \
{ "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
} \
}
#endif
@ -52,7 +52,7 @@ typedef struct __mavlink_mission_request_partial_list_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -152,7 +152,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -250,7 +250,7 @@ static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_compon
/**
* @brief Get field start_index from mission_request_partial_list message
*
* @return Start index, 0 by default
* @return Start index
*/
static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41
MAVPACKED(
typedef struct __mavlink_mission_set_current_t {
uint16_t seq; /*< Sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_set_current_t;
} mavlink_mission_set_current_t;
#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4
#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN 4
@ -25,18 +25,18 @@ typedef struct __mavlink_mission_set_current_t {
41, \
"MISSION_SET_CURRENT", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \
"MISSION_SET_CURRENT", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \
} \
}
#endif

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38
MAVPACKED(
typedef struct __mavlink_mission_write_partial_list_t {
int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/
int16_t start_index; /*< Start index. Must be smaller / equal to the largest index of the current onboard list.*/
int16_t end_index; /*< End index, equal or greater than start index.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_mission_write_partial_list_t;
} mavlink_mission_write_partial_list_t;
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6
@ -26,20 +26,20 @@ typedef struct __mavlink_mission_write_partial_list_t {
38, \
"MISSION_WRITE_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \
{ "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \
"MISSION_WRITE_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \
{ "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \
} \
}
#endif
@ -52,7 +52,7 @@ typedef struct __mavlink_mission_write_partial_list_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@ -152,7 +152,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -250,7 +250,7 @@ static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_componen
/**
* @brief Get field start_index from mission_write_partial_list message
*
* @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @return Start index. Must be smaller / equal to the largest index of the current onboard list.
*/
static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251
MAVPACKED(
typedef struct __mavlink_named_value_float_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float value; /*< Floating point value*/
char name[10]; /*< Name of the debug variable*/
}) mavlink_named_value_float_t;
} mavlink_named_value_float_t;
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN 18
@ -26,8 +26,8 @@ typedef struct __mavlink_named_value_float_t {
"NAMED_VALUE_FLOAT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
} \
}
#else
@ -35,8 +35,8 @@ typedef struct __mavlink_named_value_float_t {
"NAMED_VALUE_FLOAT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
} \
}
#endif
@ -47,7 +47,7 @@ typedef struct __mavlink_named_value_float_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Floating point value
*/
@ -208,7 +208,7 @@ static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msg
/**
* @brief Get field time_boot_ms from named_value_float message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg)
{

View file

@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252
MAVPACKED(
typedef struct __mavlink_named_value_int_t {
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
int32_t value; /*< Signed integer value*/
char name[10]; /*< Name of the debug variable*/
}) mavlink_named_value_int_t;
} mavlink_named_value_int_t;
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN 18
@ -26,8 +26,8 @@ typedef struct __mavlink_named_value_int_t {
"NAMED_VALUE_INT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
} \
}
#else
@ -35,8 +35,8 @@ typedef struct __mavlink_named_value_int_t {
"NAMED_VALUE_INT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
} \
}
#endif
@ -47,7 +47,7 @@ typedef struct __mavlink_named_value_int_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param name Name of the debug variable
* @param value Signed integer value
*/
@ -208,7 +208,7 @@ static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbu
/**
* @brief Get field time_boot_ms from named_value_int message
*
* @return Timestamp (milliseconds since system boot)
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg)
{

View file

@ -3,17 +3,17 @@
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
MAVPACKED(
typedef struct __mavlink_nav_controller_output_t {
float nav_roll; /*< Current desired roll in degrees*/
float nav_pitch; /*< Current desired pitch in degrees*/
float alt_error; /*< Current altitude error in meters*/
float aspd_error; /*< Current airspeed error in meters/second*/
float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/
int16_t nav_bearing; /*< Current desired heading in degrees*/
int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/
uint16_t wp_dist; /*< Distance to active MISSION in meters*/
}) mavlink_nav_controller_output_t;
float nav_roll; /*< [deg] Current desired roll*/
float nav_pitch; /*< [deg] Current desired pitch*/
float alt_error; /*< [m] Current altitude error*/
float aspd_error; /*< [m/s] Current airspeed error*/
float xtrack_error; /*< [m] Current crosstrack error on x-y plane*/
int16_t nav_bearing; /*< [deg] Current desired heading*/
int16_t target_bearing; /*< [deg] Bearing to current waypoint/target*/
uint16_t wp_dist; /*< [m] Distance to active waypoint*/
} mavlink_nav_controller_output_t;
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26
@ -32,12 +32,12 @@ typedef struct __mavlink_nav_controller_output_t {
8, \
{ { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
{ "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
} \
}
#else
@ -46,12 +46,12 @@ typedef struct __mavlink_nav_controller_output_t {
8, \
{ { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
{ "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
} \
}
#endif
@ -62,14 +62,14 @@ typedef struct __mavlink_nav_controller_output_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @param nav_roll [deg] Current desired roll
* @param nav_pitch [deg] Current desired pitch
* @param nav_bearing [deg] Current desired heading
* @param target_bearing [deg] Bearing to current waypoint/target
* @param wp_dist [m] Distance to active waypoint
* @param alt_error [m] Current altitude error
* @param aspd_error [m/s] Current airspeed error
* @param xtrack_error [m] Current crosstrack error on x-y plane
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id,
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @param nav_roll [deg] Current desired roll
* @param nav_pitch [deg] Current desired pitch
* @param nav_bearing [deg] Current desired heading
* @param target_bearing [deg] Bearing to current waypoint/target
* @param wp_dist [m] Distance to active waypoint
* @param alt_error [m] Current altitude error
* @param aspd_error [m/s] Current airspeed error
* @param xtrack_error [m] Current crosstrack error on x-y plane
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t sys
* @brief Send a nav_controller_output message
* @param chan MAVLink channel to send the message
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @param nav_roll [deg] Current desired roll
* @param nav_pitch [deg] Current desired pitch
* @param nav_bearing [deg] Current desired heading
* @param target_bearing [deg] Bearing to current waypoint/target
* @param wp_dist [m] Distance to active waypoint
* @param alt_error [m] Current altitude error
* @param aspd_error [m/s] Current airspeed error
* @param xtrack_error [m] Current crosstrack error on x-y plane
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -286,7 +286,7 @@ static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t
/**
* @brief Get field nav_roll from nav_controller_output message
*
* @return Current desired roll in degrees
* @return [deg] Current desired roll
*/
static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg)
{
@ -296,7 +296,7 @@ static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink
/**
* @brief Get field nav_pitch from nav_controller_output message
*
* @return Current desired pitch in degrees
* @return [deg] Current desired pitch
*/
static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg)
{
@ -306,7 +306,7 @@ static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlin
/**
* @brief Get field nav_bearing from nav_controller_output message
*
* @return Current desired heading in degrees
* @return [deg] Current desired heading
*/
static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg)
{
@ -316,7 +316,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const ma
/**
* @brief Get field target_bearing from nav_controller_output message
*
* @return Bearing to current MISSION/target in degrees
* @return [deg] Bearing to current waypoint/target
*/
static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const
/**
* @brief Get field wp_dist from nav_controller_output message
*
* @return Distance to active MISSION in meters
* @return [m] Distance to active waypoint
*/
static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavli
/**
* @brief Get field alt_error from nav_controller_output message
*
* @return Current altitude error in meters
* @return [m] Current altitude error
*/
static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg)
{
@ -346,7 +346,7 @@ static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlin
/**
* @brief Get field aspd_error from nav_controller_output message
*
* @return Current airspeed error in meters/second
* @return [m/s] Current airspeed error
*/
static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavli
/**
* @brief Get field xtrack_error from nav_controller_output message
*
* @return Current crosstrack error on x-y plane in meters
* @return [m] Current crosstrack error on x-y plane
*/
static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
{

View file

@ -3,17 +3,17 @@
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
MAVPACKED(
typedef struct __mavlink_optical_flow_t {
uint64_t time_usec; /*< Timestamp (UNIX)*/
float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/
float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/
float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/
int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/
int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/
float flow_comp_m_y; /*< [m/s] Flow in y-sensor direction, angular-speed compensated*/
float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/
int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/
int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/
uint8_t sensor_id; /*< Sensor ID*/
uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/
}) mavlink_optical_flow_t;
} mavlink_optical_flow_t;
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26
#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26
@ -31,13 +31,13 @@ typedef struct __mavlink_optical_flow_t {
"OPTICAL_FLOW", \
8, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
} \
}
#else
@ -45,13 +45,13 @@ typedef struct __mavlink_optical_flow_t {
"OPTICAL_FLOW", \
8, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
} \
}
#endif
@ -62,14 +62,14 @@ typedef struct __mavlink_optical_flow_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (UNIX)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (UNIX)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u
* @brief Send a optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (UNIX)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -286,7 +286,7 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field time_usec from optical_flow message
*
* @return Timestamp (UNIX)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg)
{
@ -306,7 +306,7 @@ static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_messa
/**
* @brief Get field flow_x from optical_flow message
*
* @return Flow in pixels * 10 in x-sensor direction (dezi-pixels)
* @return [dpix] Flow in x-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
{
@ -316,7 +316,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_
/**
* @brief Get field flow_y from optical_flow message
*
* @return Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @return [dpix] Flow in y-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
{
@ -326,7 +326,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_
/**
* @brief Get field flow_comp_m_x from optical_flow message
*
* @return Flow in meters in x-sensor direction, angular-speed compensated
* @return [m/s] Flow in x-sensor direction, angular-speed compensated
*/
static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg)
{
@ -336,7 +336,7 @@ static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_mes
/**
* @brief Get field flow_comp_m_y from optical_flow message
*
* @return Flow in meters in y-sensor direction, angular-speed compensated
* @return [m/s] Flow in y-sensor direction, angular-speed compensated
*/
static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
{
@ -356,7 +356,7 @@ static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message
/**
* @brief Get field ground_distance from optical_flow message
*
* @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @return [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
*/
static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
{

View file

@ -3,21 +3,21 @@
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106
MAVPACKED(
typedef struct __mavlink_optical_flow_rad_t {
uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/
float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/
float integrated_xgyro; /*< RH rotation around X axis (rad)*/
float integrated_ygyro; /*< RH rotation around Y axis (rad)*/
float integrated_zgyro; /*< RH rotation around Z axis (rad)*/
uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/
float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/
int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
float integrated_x; /*< [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/
float integrated_y; /*< [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/
float integrated_xgyro; /*< [rad] RH rotation around X axis*/
float integrated_ygyro; /*< [rad] RH rotation around Y axis*/
float integrated_zgyro; /*< [rad] RH rotation around Z axis*/
uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/
float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/
int16_t temperature; /*< [cdegC] Temperature*/
uint8_t sensor_id; /*< Sensor ID*/
uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/
}) mavlink_optical_flow_rad_t;
} mavlink_optical_flow_rad_t;
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN 44
@ -35,17 +35,17 @@ typedef struct __mavlink_optical_flow_rad_t {
"OPTICAL_FLOW_RAD", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
} \
}
#else
@ -53,17 +53,17 @@ typedef struct __mavlink_optical_flow_rad_t {
"OPTICAL_FLOW_RAD", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
} \
}
#endif
@ -74,18 +74,18 @@ typedef struct __mavlink_optical_flow_rad_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_i
* @brief Send a optical_flow_rad message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro [rad] RH rotation around X axis
* @param integrated_ygyro [rad] RH rotation around Y axis
* @param integrated_zgyro [rad] RH rotation around Z axis
* @param temperature [cdegC] Temperature
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @param time_delta_distance_us [us] Time since the distance was sampled.
* @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -342,7 +342,7 @@ static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgb
/**
* @brief Get field time_usec from optical_flow_rad message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg)
{
@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_m
/**
* @brief Get field integration_time_us from optical_flow_rad message
*
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
*/
static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg)
{
@ -372,7 +372,7 @@ static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(cons
/**
* @brief Get field integrated_x from optical_flow_rad message
*
* @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @return [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg)
{
@ -382,7 +382,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_
/**
* @brief Get field integrated_y from optical_flow_rad message
*
* @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @return [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg)
{
@ -392,7 +392,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_
/**
* @brief Get field integrated_xgyro from optical_flow_rad message
*
* @return RH rotation around X axis (rad)
* @return [rad] RH rotation around X axis
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg)
{
@ -402,7 +402,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavl
/**
* @brief Get field integrated_ygyro from optical_flow_rad message
*
* @return RH rotation around Y axis (rad)
* @return [rad] RH rotation around Y axis
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg)
{
@ -412,7 +412,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavl
/**
* @brief Get field integrated_zgyro from optical_flow_rad message
*
* @return RH rotation around Z axis (rad)
* @return [rad] RH rotation around Z axis
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg)
{
@ -422,7 +422,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavl
/**
* @brief Get field temperature from optical_flow_rad message
*
* @return Temperature * 100 in centi-degrees Celsius
* @return [cdegC] Temperature
*/
static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg)
{
@ -442,7 +442,7 @@ static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_mes
/**
* @brief Get field time_delta_distance_us from optical_flow_rad message
*
* @return Time in microseconds since the distance was sampled.
* @return [us] Time since the distance was sampled.
*/
static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg)
{
@ -452,7 +452,7 @@ static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(c
/**
* @brief Get field distance from optical_flow_rad message
*
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,330 @@
#pragma once
// MESSAGE PARAM_ACK_TRANSACTION PACKING
#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION 19
typedef struct __mavlink_param_ack_transaction_t {
float param_value; /*< Parameter value (new value if PARAM_ACCEPTED, current value otherwise)*/
uint8_t target_system; /*< Id of system that sent PARAM_SET message.*/
uint8_t target_component; /*< Id of system that sent PARAM_SET message.*/
char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
uint8_t param_type; /*< Parameter type.*/
uint8_t param_result; /*< Result code.*/
} mavlink_param_ack_transaction_t;
#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN 24
#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN 24
#define MAVLINK_MSG_ID_19_LEN 24
#define MAVLINK_MSG_ID_19_MIN_LEN 24
#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC 137
#define MAVLINK_MSG_ID_19_CRC 137
#define MAVLINK_MSG_PARAM_ACK_TRANSACTION_FIELD_PARAM_ID_LEN 16
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_PARAM_ACK_TRANSACTION { \
19, \
"PARAM_ACK_TRANSACTION", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_ack_transaction_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_ack_transaction_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_ack_transaction_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_ack_transaction_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_ack_transaction_t, param_type) }, \
{ "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_param_ack_transaction_t, param_result) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_ACK_TRANSACTION { \
"PARAM_ACK_TRANSACTION", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_ack_transaction_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_ack_transaction_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_ack_transaction_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_ack_transaction_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_ack_transaction_t, param_type) }, \
{ "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_param_ack_transaction_t, param_result) }, \
} \
}
#endif
/**
* @brief Pack a param_ack_transaction message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system Id of system that sent PARAM_SET message.
* @param target_component Id of system that sent PARAM_SET message.
* @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_ack_transaction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_uint8_t(buf, 23, param_result);
_mav_put_char_array(buf, 6, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN);
#else
mavlink_param_ack_transaction_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
}
/**
* @brief Pack a param_ack_transaction message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system Id of system that sent PARAM_SET message.
* @param target_component Id of system that sent PARAM_SET message.
* @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_ack_transaction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type,uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_uint8_t(buf, 23, param_result);
_mav_put_char_array(buf, 6, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN);
#else
mavlink_param_ack_transaction_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
}
/**
* @brief Encode a param_ack_transaction struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_ack_transaction C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ack_transaction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ack_transaction_t* param_ack_transaction)
{
return mavlink_msg_param_ack_transaction_pack(system_id, component_id, msg, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result);
}
/**
* @brief Encode a param_ack_transaction struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param param_ack_transaction C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ack_transaction_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ack_transaction_t* param_ack_transaction)
{
return mavlink_msg_param_ack_transaction_pack_chan(system_id, component_id, chan, msg, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result);
}
/**
* @brief Send a param_ack_transaction message
* @param chan MAVLink channel to send the message
*
* @param target_system Id of system that sent PARAM_SET message.
* @param target_component Id of system that sent PARAM_SET message.
* @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_ack_transaction_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_uint8_t(buf, 23, param_result);
_mav_put_char_array(buf, 6, param_id, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
#else
mavlink_param_ack_transaction_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)&packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
#endif
}
/**
* @brief Send a param_ack_transaction message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_param_ack_transaction_send_struct(mavlink_channel_t chan, const mavlink_param_ack_transaction_t* param_ack_transaction)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_param_ack_transaction_send(chan, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)param_ack_transaction, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
#endif
}
#if MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_ack_transaction_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_uint8_t(buf, 23, param_result);
_mav_put_char_array(buf, 6, param_id, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
#else
mavlink_param_ack_transaction_t *packet = (mavlink_param_ack_transaction_t *)msgbuf;
packet->param_value = param_value;
packet->target_system = target_system;
packet->target_component = target_component;
packet->param_type = param_type;
packet->param_result = param_result;
mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC);
#endif
}
#endif
#endif
// MESSAGE PARAM_ACK_TRANSACTION UNPACKING
/**
* @brief Get field target_system from param_ack_transaction message
*
* @return Id of system that sent PARAM_SET message.
*/
static inline uint8_t mavlink_msg_param_ack_transaction_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from param_ack_transaction message
*
* @return Id of system that sent PARAM_SET message.
*/
static inline uint8_t mavlink_msg_param_ack_transaction_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field param_id from param_ack_transaction message
*
* @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
static inline uint16_t mavlink_msg_param_ack_transaction_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 6);
}
/**
* @brief Get field param_value from param_ack_transaction message
*
* @return Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
*/
static inline float mavlink_msg_param_ack_transaction_get_param_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field param_type from param_ack_transaction message
*
* @return Parameter type.
*/
static inline uint8_t mavlink_msg_param_ack_transaction_get_param_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field param_result from param_ack_transaction message
*
* @return Result code.
*/
static inline uint8_t mavlink_msg_param_ack_transaction_get_param_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 23);
}
/**
* @brief Decode a param_ack_transaction message into a struct
*
* @param msg The message to decode
* @param param_ack_transaction C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_ack_transaction_decode(const mavlink_message_t* msg, mavlink_param_ack_transaction_t* param_ack_transaction)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
param_ack_transaction->param_value = mavlink_msg_param_ack_transaction_get_param_value(msg);
param_ack_transaction->target_system = mavlink_msg_param_ack_transaction_get_target_system(msg);
param_ack_transaction->target_component = mavlink_msg_param_ack_transaction_get_target_component(msg);
mavlink_msg_param_ack_transaction_get_param_id(msg, param_ack_transaction->param_id);
param_ack_transaction->param_type = mavlink_msg_param_ack_transaction_get_param_type(msg);
param_ack_transaction->param_result = mavlink_msg_param_ack_transaction_get_param_result(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN? msg->len : MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN;
memset(param_ack_transaction, 0, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN);
memcpy(param_ack_transaction, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_PARAM_MAP_RC 50
MAVPACKED(
typedef struct __mavlink_param_map_rc_t {
float param_value0; /*< Initial parameter value*/
float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/
@ -13,8 +13,8 @@ typedef struct __mavlink_param_map_rc_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/
}) mavlink_param_map_rc_t;
uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.*/
} mavlink_param_map_rc_t;
#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37
#define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37
@ -31,30 +31,30 @@ typedef struct __mavlink_param_map_rc_t {
50, \
"PARAM_MAP_RC", \
9, \
{ { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
{ "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
{ "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
{ "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \
{ "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \
{ "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
{ "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \
"PARAM_MAP_RC", \
9, \
{ { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
{ "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
{ "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
{ "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \
{ "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \
{ "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
{ "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
} \
}
#endif
@ -69,7 +69,7 @@ typedef struct __mavlink_param_map_rc_t {
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
@ -119,7 +119,7 @@ static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
@ -195,7 +195,7 @@ static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, u
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
@ -332,7 +332,7 @@ static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_mes
/**
* @brief Get field parameter_rc_channel_index from param_map_rc message
*
* @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @return Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
*/
static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg)
{

View file

@ -3,11 +3,11 @@
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21
MAVPACKED(
typedef struct __mavlink_param_request_list_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
}) mavlink_param_request_list_t;
} mavlink_param_request_list_t;
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN 2

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
MAVPACKED(
typedef struct __mavlink_param_request_read_t {
int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
}) mavlink_param_request_read_t;
} mavlink_param_request_read_t;
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20
@ -26,20 +26,20 @@ typedef struct __mavlink_param_request_read_t {
20, \
"PARAM_REQUEST_READ", \
4, \
{ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
"PARAM_REQUEST_READ", \
4, \
{ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
} \
}
#endif

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_PARAM_SET 23
MAVPACKED(
typedef struct __mavlink_param_set_t {
float param_value; /*< Onboard parameter value*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/
}) mavlink_param_set_t;
uint8_t param_type; /*< Onboard parameter type.*/
} mavlink_param_set_t;
#define MAVLINK_MSG_ID_PARAM_SET_LEN 23
#define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23
@ -27,10 +27,10 @@ typedef struct __mavlink_param_set_t {
23, \
"PARAM_SET", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
} \
}
@ -38,10 +38,10 @@ typedef struct __mavlink_param_set_t {
#define MAVLINK_MESSAGE_INFO_PARAM_SET { \
"PARAM_SET", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
} \
}
@ -57,7 +57,7 @@ typedef struct __mavlink_param_set_t {
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint
* @param target_component Component ID
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -276,7 +276,7 @@ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_
/**
* @brief Get field param_type from param_set message
*
* @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @return Onboard parameter type.
*/
static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
{

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_PARAM_VALUE 22
MAVPACKED(
typedef struct __mavlink_param_value_t {
float param_value; /*< Onboard parameter value*/
uint16_t param_count; /*< Total number of onboard parameters*/
uint16_t param_index; /*< Index of this onboard parameter*/
char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/
}) mavlink_param_value_t;
uint8_t param_type; /*< Onboard parameter type.*/
} mavlink_param_value_t;
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
#define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25
@ -27,22 +27,22 @@ typedef struct __mavlink_param_value_t {
22, \
"PARAM_VALUE", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
{ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
{ "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
{ "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
"PARAM_VALUE", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
{ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
{ "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
{ "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
} \
}
#endif
@ -55,7 +55,7 @@ typedef struct __mavlink_param_value_t {
*
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
@ -157,7 +157,7 @@ static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, ui
*
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @param param_type Onboard parameter type.
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
*/
@ -256,7 +256,7 @@ static inline float mavlink_msg_param_value_get_param_value(const mavlink_messag
/**
* @brief Get field param_type from param_value message
*
* @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @return Onboard parameter type.
*/
static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg)
{

View file

@ -3,13 +3,13 @@
#define MAVLINK_MSG_ID_PING 4
MAVPACKED(
typedef struct __mavlink_ping_t {
uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t seq; /*< PING sequence*/
uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/
uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/
}) mavlink_ping_t;
uint8_t target_system; /*< 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system*/
uint8_t target_component; /*< 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.*/
} mavlink_ping_t;
#define MAVLINK_MSG_ID_PING_LEN 14
#define MAVLINK_MSG_ID_PING_MIN_LEN 14
@ -50,10 +50,10 @@ typedef struct __mavlink_ping_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t c
* @brief Send a ping message
* @param chan MAVLink channel to send the message
*
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -230,7 +230,7 @@ static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_
/**
* @brief Get field time_usec from ping message
*
* @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg)
{
@ -250,7 +250,7 @@ static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
/**
* @brief Get field target_system from ping message
*
* @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @return 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
*/
static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
{
@ -260,7 +260,7 @@ static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t
/**
* @brief Get field target_component from ping message
*
* @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @return 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.
*/
static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
{

View file

@ -3,23 +3,23 @@
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87
MAVPACKED(
typedef struct __mavlink_position_target_global_int_t {
uint32_t 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.*/
int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/
int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/
float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/
float vx; /*< X velocity in NED frame in meter / s*/
float vy; /*< Y velocity in NED frame in meter / s*/
float vz; /*< Z velocity in NED frame in meter / s*/
float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float yaw; /*< yaw setpoint in rad*/
float yaw_rate; /*< yaw rate setpoint in rad/s*/
uint16_t 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*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time 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.*/
int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/
int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/
float alt; /*< [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)*/
float vx; /*< [m/s] X velocity in NED frame*/
float vy; /*< [m/s] Y velocity in NED frame*/
float vz; /*< [m/s] Z velocity in NED frame*/
float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
float yaw; /*< [rad] yaw setpoint*/
float yaw_rate; /*< [rad/s] yaw rate setpoint*/
uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/
}) mavlink_position_target_global_int_t;
} mavlink_position_target_global_int_t;
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51
@ -37,6 +37,8 @@ typedef struct __mavlink_position_target_global_int_t {
"POSITION_TARGET_GLOBAL_INT", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
@ -48,8 +50,6 @@ typedef struct __mavlink_position_target_global_int_t {
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
} \
}
#else
@ -57,6 +57,8 @@ typedef struct __mavlink_position_target_global_int_t {
"POSITION_TARGET_GLOBAL_INT", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
@ -68,8 +70,6 @@ typedef struct __mavlink_position_target_global_int_t {
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
} \
}
#endif
@ -80,20 +80,20 @@ typedef struct __mavlink_position_target_global_int_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param 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.
* @param time_boot_ms [ms] Timestamp (time 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.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param 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
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param lat_int [degE7] X Position in WGS84 frame
* @param lon_int [degE7] Y Position in WGS84 frame
* @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)
* @param vx [m/s] X velocity in NED frame
* @param vy [m/s] Y velocity in NED frame
* @param vz [m/s] Z velocity in NED frame
* @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw [rad] yaw setpoint
* @param yaw_rate [rad/s] yaw rate setpoint
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param 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.
* @param time_boot_ms [ms] Timestamp (time 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.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param 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
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param lat_int [degE7] X Position in WGS84 frame
* @param lon_int [degE7] Y Position in WGS84 frame
* @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)
* @param vx [m/s] X velocity in NED frame
* @param vy [m/s] Y velocity in NED frame
* @param vz [m/s] Z velocity in NED frame
* @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw [rad] yaw setpoint
* @param yaw_rate [rad/s] yaw rate setpoint
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_
* @brief Send a position_target_global_int message
* @param chan MAVLink channel to send the message
*
* @param 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.
* @param time_boot_ms [ms] Timestamp (time 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.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param 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
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param lat_int [degE7] X Position in WGS84 frame
* @param lon_int [degE7] Y Position in WGS84 frame
* @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)
* @param vx [m/s] X velocity in NED frame
* @param vy [m/s] Y velocity in NED frame
* @param vz [m/s] Z velocity in NED frame
* @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw [rad] yaw setpoint
* @param yaw_rate [rad/s] yaw rate setpoint
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -370,7 +370,7 @@ static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_messa
/**
* @brief Get field time_boot_ms from position_target_global_int message
*
* @return 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.
* @return [ms] Timestamp (time 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.
*/
static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
{
@ -390,7 +390,7 @@ static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_fram
/**
* @brief Get field type_mask from position_target_global_int message
*
* @return 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
* @return Bitmap to indicate which dimensions should be ignored by the vehicle.
*/
static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
{
@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(cons
/**
* @brief Get field lat_int from position_target_global_int message
*
* @return X Position in WGS84 frame in 1e7 * meters
* @return [degE7] X Position in WGS84 frame
*/
static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
{
@ -410,7 +410,7 @@ static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const m
/**
* @brief Get field lon_int from position_target_global_int message
*
* @return Y Position in WGS84 frame in 1e7 * meters
* @return [degE7] Y Position in WGS84 frame
*/
static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
{
@ -420,7 +420,7 @@ static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const m
/**
* @brief Get field alt from position_target_global_int message
*
* @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @return [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)
*/
static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg)
{
@ -430,7 +430,7 @@ static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink
/**
* @brief Get field vx from position_target_global_int message
*
* @return X velocity in NED frame in meter / s
* @return [m/s] X velocity in NED frame
*/
static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg)
{
@ -440,7 +440,7 @@ static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_
/**
* @brief Get field vy from position_target_global_int message
*
* @return Y velocity in NED frame in meter / s
* @return [m/s] Y velocity in NED frame
*/
static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg)
{
@ -450,7 +450,7 @@ static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_
/**
* @brief Get field vz from position_target_global_int message
*
* @return Z velocity in NED frame in meter / s
* @return [m/s] Z velocity in NED frame
*/
static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg)
{
@ -460,7 +460,7 @@ static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_
/**
* @brief Get field afx from position_target_global_int message
*
* @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg)
{
@ -470,7 +470,7 @@ static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink
/**
* @brief Get field afy from position_target_global_int message
*
* @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg)
{
@ -480,7 +480,7 @@ static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink
/**
* @brief Get field afz from position_target_global_int message
*
* @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg)
{
@ -490,7 +490,7 @@ static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink
/**
* @brief Get field yaw from position_target_global_int message
*
* @return yaw setpoint in rad
* @return [rad] yaw setpoint
*/
static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg)
{
@ -500,7 +500,7 @@ static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink
/**
* @brief Get field yaw_rate from position_target_global_int message
*
* @return yaw rate setpoint in rad/s
* @return [rad/s] yaw rate setpoint
*/
static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
{

Some files were not shown because too many files have changed in this diff Show more