mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
GCS_MAVLink: regenerate headers
This commit is contained in:
parent
91623322f9
commit
afe1fce94e
File diff suppressed because one or more lines are too long
@ -4,13 +4,13 @@
|
||||
|
||||
typedef struct __mavlink_ahrs_t
|
||||
{
|
||||
float omegaIx; ///< X gyro drift estimate rad/s
|
||||
float omegaIy; ///< Y gyro drift estimate rad/s
|
||||
float omegaIz; ///< Z gyro drift estimate rad/s
|
||||
float accel_weight; ///< average accel_weight
|
||||
float renorm_val; ///< average renormalisation value
|
||||
float error_rp; ///< average error_roll_pitch value
|
||||
float error_yaw; ///< average error_yaw value
|
||||
float omegaIx; /*< X gyro drift estimate rad/s*/
|
||||
float omegaIy; /*< Y gyro drift estimate rad/s*/
|
||||
float omegaIz; /*< Z gyro drift estimate rad/s*/
|
||||
float accel_weight; /*< average accel_weight*/
|
||||
float renorm_val; /*< average renormalisation value*/
|
||||
float error_rp; /*< average error_roll_pitch value*/
|
||||
float error_yaw; /*< average error_yaw value*/
|
||||
} mavlink_ahrs_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS_LEN 28
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_ahrs2_t
|
||||
{
|
||||
float roll; ///< Roll angle (rad)
|
||||
float pitch; ///< Pitch angle (rad)
|
||||
float yaw; ///< Yaw angle (rad)
|
||||
float altitude; ///< Altitude (MSL)
|
||||
int32_t lat; ///< Latitude in degrees * 1E7
|
||||
int32_t lng; ///< Longitude in degrees * 1E7
|
||||
float roll; /*< Roll angle (rad)*/
|
||||
float pitch; /*< Pitch angle (rad)*/
|
||||
float yaw; /*< Yaw angle (rad)*/
|
||||
float altitude; /*< Altitude (MSL)*/
|
||||
int32_t lat; /*< Latitude in degrees * 1E7*/
|
||||
int32_t lng; /*< Longitude in degrees * 1E7*/
|
||||
} mavlink_ahrs2_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS2_LEN 24
|
||||
|
@ -4,16 +4,16 @@
|
||||
|
||||
typedef struct __mavlink_ahrs3_t
|
||||
{
|
||||
float roll; ///< Roll angle (rad)
|
||||
float pitch; ///< Pitch angle (rad)
|
||||
float yaw; ///< Yaw angle (rad)
|
||||
float altitude; ///< Altitude (MSL)
|
||||
int32_t lat; ///< Latitude in degrees * 1E7
|
||||
int32_t lng; ///< Longitude in degrees * 1E7
|
||||
float v1; ///< test variable1
|
||||
float v2; ///< test variable2
|
||||
float v3; ///< test variable3
|
||||
float v4; ///< test variable4
|
||||
float roll; /*< Roll angle (rad)*/
|
||||
float pitch; /*< Pitch angle (rad)*/
|
||||
float yaw; /*< Yaw angle (rad)*/
|
||||
float altitude; /*< Altitude (MSL)*/
|
||||
int32_t lat; /*< Latitude in degrees * 1E7*/
|
||||
int32_t lng; /*< Longitude in degrees * 1E7*/
|
||||
float v1; /*< test variable1*/
|
||||
float v2; /*< test variable2*/
|
||||
float v3; /*< test variable3*/
|
||||
float v4; /*< test variable4*/
|
||||
} mavlink_ahrs3_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS3_LEN 40
|
||||
|
@ -4,18 +4,18 @@
|
||||
|
||||
typedef struct __mavlink_airspeed_autocal_t
|
||||
{
|
||||
float vx; ///< GPS velocity north m/s
|
||||
float vy; ///< GPS velocity east m/s
|
||||
float vz; ///< GPS velocity down m/s
|
||||
float diff_pressure; ///< Differential pressure pascals
|
||||
float EAS2TAS; ///< Estimated to true airspeed ratio
|
||||
float ratio; ///< Airspeed ratio
|
||||
float state_x; ///< EKF state x
|
||||
float state_y; ///< EKF state y
|
||||
float state_z; ///< EKF state z
|
||||
float Pax; ///< EKF Pax
|
||||
float Pby; ///< EKF Pby
|
||||
float Pcz; ///< EKF Pcz
|
||||
float vx; /*< GPS velocity north m/s*/
|
||||
float vy; /*< GPS velocity east m/s*/
|
||||
float vz; /*< GPS velocity down m/s*/
|
||||
float diff_pressure; /*< Differential pressure pascals*/
|
||||
float EAS2TAS; /*< Estimated to true airspeed ratio*/
|
||||
float ratio; /*< Airspeed ratio*/
|
||||
float state_x; /*< EKF state x*/
|
||||
float state_y; /*< EKF state y*/
|
||||
float state_z; /*< EKF state z*/
|
||||
float Pax; /*< EKF Pax*/
|
||||
float Pby; /*< EKF Pby*/
|
||||
float Pcz; /*< EKF Pcz*/
|
||||
} mavlink_airspeed_autocal_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_ap_adc_t
|
||||
{
|
||||
uint16_t adc1; ///< ADC output 1
|
||||
uint16_t adc2; ///< ADC output 2
|
||||
uint16_t adc3; ///< ADC output 3
|
||||
uint16_t adc4; ///< ADC output 4
|
||||
uint16_t adc5; ///< ADC output 5
|
||||
uint16_t adc6; ///< ADC output 6
|
||||
uint16_t adc1; /*< ADC output 1*/
|
||||
uint16_t adc2; /*< ADC output 2*/
|
||||
uint16_t adc3; /*< ADC output 3*/
|
||||
uint16_t adc4; /*< ADC output 4*/
|
||||
uint16_t adc5; /*< ADC output 5*/
|
||||
uint16_t adc6; /*< ADC output 6*/
|
||||
} mavlink_ap_adc_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_autopilot_version_request_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_autopilot_version_request_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN 2
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_battery2_t
|
||||
{
|
||||
uint16_t voltage; ///< voltage in millivolts
|
||||
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
uint16_t voltage; /*< voltage in millivolts*/
|
||||
int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/
|
||||
} mavlink_battery2_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_BATTERY2_LEN 4
|
||||
|
@ -4,19 +4,19 @@
|
||||
|
||||
typedef struct __mavlink_camera_feedback_t
|
||||
{
|
||||
uint64_t time_usec; ///< Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)
|
||||
int32_t lat; ///< Latitude in (deg * 1E7)
|
||||
int32_t lng; ///< Longitude in (deg * 1E7)
|
||||
float alt_msl; ///< Altitude Absolute (meters AMSL)
|
||||
float alt_rel; ///< Altitude Relative (meters above HOME location)
|
||||
float roll; ///< Camera Roll angle (earth frame, degrees, +-180)
|
||||
float pitch; ///< Camera Pitch angle (earth frame, degrees, +-180)
|
||||
float yaw; ///< Camera Yaw (earth frame, degrees, 0-360, true)
|
||||
float foc_len; ///< Focal Length (mm)
|
||||
uint16_t img_idx; ///< Image index
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t cam_idx; ///< Camera ID
|
||||
uint8_t flags; ///< See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask
|
||||
uint64_t time_usec; /*< Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)*/
|
||||
int32_t lat; /*< Latitude in (deg * 1E7)*/
|
||||
int32_t lng; /*< Longitude in (deg * 1E7)*/
|
||||
float alt_msl; /*< Altitude Absolute (meters AMSL)*/
|
||||
float alt_rel; /*< Altitude Relative (meters above HOME location)*/
|
||||
float roll; /*< Camera Roll angle (earth frame, degrees, +-180)*/
|
||||
float pitch; /*< Camera Pitch angle (earth frame, degrees, +-180)*/
|
||||
float yaw; /*< Camera Yaw (earth frame, degrees, 0-360, true)*/
|
||||
float foc_len; /*< Focal Length (mm)*/
|
||||
uint16_t img_idx; /*< Image index*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t cam_idx; /*< Camera ID*/
|
||||
uint8_t flags; /*< See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask*/
|
||||
} mavlink_camera_feedback_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 45
|
||||
|
@ -4,15 +4,15 @@
|
||||
|
||||
typedef struct __mavlink_camera_status_t
|
||||
{
|
||||
uint64_t time_usec; ///< Image timestamp (microseconds since UNIX epoch, according to camera clock)
|
||||
float p1; ///< Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
|
||||
float p2; ///< Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
|
||||
float p3; ///< Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
|
||||
float p4; ///< Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
|
||||
uint16_t img_idx; ///< Image index
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t cam_idx; ///< Camera ID
|
||||
uint8_t event_id; ///< See CAMERA_STATUS_TYPES enum for definition of the bitmask
|
||||
uint64_t time_usec; /*< Image timestamp (microseconds since UNIX epoch, according to camera clock)*/
|
||||
float p1; /*< Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)*/
|
||||
float p2; /*< Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)*/
|
||||
float p3; /*< Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)*/
|
||||
float p4; /*< Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum)*/
|
||||
uint16_t img_idx; /*< Image index*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t cam_idx; /*< Camera ID*/
|
||||
uint8_t event_id; /*< See CAMERA_STATUS_TYPES enum for definition of the bitmask*/
|
||||
} mavlink_camera_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_CAMERA_STATUS_LEN 29
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_compassmot_status_t
|
||||
{
|
||||
float current; ///< current (amps)
|
||||
float CompensationX; ///< Motor Compensation X
|
||||
float CompensationY; ///< Motor Compensation Y
|
||||
float CompensationZ; ///< Motor Compensation Z
|
||||
uint16_t throttle; ///< throttle (percent*10)
|
||||
uint16_t interference; ///< interference (percent)
|
||||
float current; /*< current (amps)*/
|
||||
float CompensationX; /*< Motor Compensation X*/
|
||||
float CompensationY; /*< Motor Compensation Y*/
|
||||
float CompensationZ; /*< Motor Compensation Z*/
|
||||
uint16_t throttle; /*< throttle (percent*10)*/
|
||||
uint16_t interference; /*< interference (percent)*/
|
||||
} mavlink_compassmot_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_data16_t
|
||||
{
|
||||
uint8_t type; ///< data type
|
||||
uint8_t len; ///< data length
|
||||
uint8_t data[16]; ///< raw data
|
||||
uint8_t type; /*< data type*/
|
||||
uint8_t len; /*< data length*/
|
||||
uint8_t data[16]; /*< raw data*/
|
||||
} mavlink_data16_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA16_LEN 18
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_data32_t
|
||||
{
|
||||
uint8_t type; ///< data type
|
||||
uint8_t len; ///< data length
|
||||
uint8_t data[32]; ///< raw data
|
||||
uint8_t type; /*< data type*/
|
||||
uint8_t len; /*< data length*/
|
||||
uint8_t data[32]; /*< raw data*/
|
||||
} mavlink_data32_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA32_LEN 34
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_data64_t
|
||||
{
|
||||
uint8_t type; ///< data type
|
||||
uint8_t len; ///< data length
|
||||
uint8_t data[64]; ///< raw data
|
||||
uint8_t type; /*< data type*/
|
||||
uint8_t len; /*< data length*/
|
||||
uint8_t data[64]; /*< raw data*/
|
||||
} mavlink_data64_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA64_LEN 66
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_data96_t
|
||||
{
|
||||
uint8_t type; ///< data type
|
||||
uint8_t len; ///< data length
|
||||
uint8_t data[96]; ///< raw data
|
||||
uint8_t type; /*< data type*/
|
||||
uint8_t len; /*< data length*/
|
||||
uint8_t data[96]; /*< raw data*/
|
||||
} mavlink_data96_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA96_LEN 98
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
typedef struct __mavlink_digicam_configure_t
|
||||
{
|
||||
float extra_value; ///< Correspondent value to given extra_param
|
||||
uint16_t shutter_speed; ///< Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t mode; ///< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
|
||||
uint8_t aperture; ///< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
|
||||
uint8_t iso; ///< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
|
||||
uint8_t exposure_type; ///< Exposure type enumeration from 1 to N (0 means ignore)
|
||||
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
|
||||
uint8_t engine_cut_off; ///< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
|
||||
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
|
||||
float extra_value; /*< Correspondent value to given extra_param*/
|
||||
uint16_t shutter_speed; /*< Divisor number //e.g. 1000 means 1/1000 (0 means ignore)*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t mode; /*< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)*/
|
||||
uint8_t aperture; /*< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)*/
|
||||
uint8_t iso; /*< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)*/
|
||||
uint8_t exposure_type; /*< Exposure type enumeration from 1 to N (0 means ignore)*/
|
||||
uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once*/
|
||||
uint8_t engine_cut_off; /*< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)*/
|
||||
uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore)*/
|
||||
} mavlink_digicam_configure_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
|
||||
|
@ -4,16 +4,16 @@
|
||||
|
||||
typedef struct __mavlink_digicam_control_t
|
||||
{
|
||||
float extra_value; ///< Correspondent value to given extra_param
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t session; ///< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
|
||||
uint8_t zoom_pos; ///< 1 to N //Zoom's absolute position (0 means ignore)
|
||||
int8_t zoom_step; ///< -100 to 100 //Zooming step value to offset zoom from the current position
|
||||
uint8_t focus_lock; ///< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
|
||||
uint8_t shot; ///< 0: ignore, 1: shot or start filming
|
||||
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
|
||||
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
|
||||
float extra_value; /*< Correspondent value to given extra_param*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t session; /*< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens*/
|
||||
uint8_t zoom_pos; /*< 1 to N //Zoom's absolute position (0 means ignore)*/
|
||||
int8_t zoom_step; /*< -100 to 100 //Zooming step value to offset zoom from the current position*/
|
||||
uint8_t focus_lock; /*< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus*/
|
||||
uint8_t shot; /*< 0: ignore, 1: shot or start filming*/
|
||||
uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once*/
|
||||
uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore)*/
|
||||
} mavlink_digicam_control_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_ekf_status_report_t
|
||||
{
|
||||
float velocity_variance; ///< Velocity variance
|
||||
float pos_horiz_variance; ///< Horizontal Position variance
|
||||
float pos_vert_variance; ///< Vertical Position variance
|
||||
float compass_variance; ///< Compass variance
|
||||
float terrain_alt_variance; ///< Terrain Altitude variance
|
||||
uint16_t flags; ///< Flags
|
||||
float velocity_variance; /*< Velocity variance*/
|
||||
float pos_horiz_variance; /*< Horizontal Position variance*/
|
||||
float pos_vert_variance; /*< Vertical Position variance*/
|
||||
float compass_variance; /*< Compass variance*/
|
||||
float terrain_alt_variance; /*< Terrain Altitude variance*/
|
||||
uint16_t flags; /*< Flags*/
|
||||
} mavlink_ekf_status_report_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 22
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_fence_fetch_point_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t idx; /*< point index (first point is 1, 0 is for return point)*/
|
||||
} mavlink_fence_fetch_point_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_fence_point_t
|
||||
{
|
||||
float lat; ///< Latitude of point
|
||||
float lng; ///< Longitude of point
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
|
||||
uint8_t count; ///< total number of points (for sanity checking)
|
||||
float lat; /*< Latitude of point*/
|
||||
float lng; /*< Longitude of point*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t idx; /*< point index (first point is 1, 0 is for return point)*/
|
||||
uint8_t count; /*< total number of points (for sanity checking)*/
|
||||
} mavlink_fence_point_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
typedef struct __mavlink_fence_status_t
|
||||
{
|
||||
uint32_t breach_time; ///< time of last breach in milliseconds since boot
|
||||
uint16_t breach_count; ///< number of fence breaches
|
||||
uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside
|
||||
uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum)
|
||||
uint32_t breach_time; /*< time of last breach in milliseconds since boot*/
|
||||
uint16_t breach_count; /*< number of fence breaches*/
|
||||
uint8_t breach_status; /*< 0 if currently inside fence, 1 if outside*/
|
||||
uint8_t breach_type; /*< last breach type (see FENCE_BREACH_* enum)*/
|
||||
} mavlink_fence_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_axis_calibration_progress_t
|
||||
{
|
||||
uint8_t calibration_axis; ///< Which gimbal axis we're reporting calibration progress for
|
||||
uint8_t calibration_progress; ///< The current calibration progress for this axis, 0x64=100%
|
||||
uint8_t calibration_status; ///< The status of the running calibration
|
||||
uint8_t calibration_axis; /*< Which gimbal axis we're reporting calibration progress for*/
|
||||
uint8_t calibration_progress; /*< The current calibration progress for this axis, 0x64=100%*/
|
||||
uint8_t calibration_status; /*< The status of the running calibration*/
|
||||
} mavlink_gimbal_axis_calibration_progress_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_AXIS_CALIBRATION_PROGRESS_LEN 3
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_control_t
|
||||
{
|
||||
float demanded_rate_x; ///< Demanded angular rate X (rad/s)
|
||||
float demanded_rate_y; ///< Demanded angular rate Y (rad/s)
|
||||
float demanded_rate_z; ///< Demanded angular rate Z (rad/s)
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
float demanded_rate_x; /*< Demanded angular rate X (rad/s)*/
|
||||
float demanded_rate_y; /*< Demanded angular rate Y (rad/s)*/
|
||||
float demanded_rate_z; /*< Demanded angular rate Z (rad/s)*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_control_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN 14
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_erase_firmware_and_config_t
|
||||
{
|
||||
uint32_t knock; ///< Knock value to confirm this is a valid request
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint32_t knock; /*< Knock value to confirm this is a valid request*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_erase_firmware_and_config_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_ERASE_FIRMWARE_AND_CONFIG_LEN 6
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_factory_parameters_loaded_t
|
||||
{
|
||||
uint8_t dummy; ///< Dummy field because mavgen doesn't allow messages with no fields
|
||||
uint8_t dummy; /*< Dummy field because mavgen doesn't allow messages with no fields*/
|
||||
} mavlink_gimbal_factory_parameters_loaded_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_LEN 1
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_home_offset_calibration_result_t
|
||||
{
|
||||
uint8_t calibration_result; ///< The result of the home offset calibration
|
||||
uint8_t calibration_result; /*< The result of the home offset calibration*/
|
||||
} mavlink_gimbal_home_offset_calibration_result_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_HOME_OFFSET_CALIBRATION_RESULT_LEN 1
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_perform_factory_tests_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_perform_factory_tests_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_PERFORM_FACTORY_TESTS_LEN 2
|
||||
|
@ -4,18 +4,18 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_report_t
|
||||
{
|
||||
float delta_time; ///< Time since last update (seconds)
|
||||
float delta_angle_x; ///< Delta angle X (radians)
|
||||
float delta_angle_y; ///< Delta angle Y (radians)
|
||||
float delta_angle_z; ///< Delta angle X (radians)
|
||||
float delta_velocity_x; ///< Delta velocity X (m/s)
|
||||
float delta_velocity_y; ///< Delta velocity Y (m/s)
|
||||
float delta_velocity_z; ///< Delta velocity Z (m/s)
|
||||
float joint_roll; ///< Joint ROLL (radians)
|
||||
float joint_el; ///< Joint EL (radians)
|
||||
float joint_az; ///< Joint AZ (radians)
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
float delta_time; /*< Time since last update (seconds)*/
|
||||
float delta_angle_x; /*< Delta angle X (radians)*/
|
||||
float delta_angle_y; /*< Delta angle Y (radians)*/
|
||||
float delta_angle_z; /*< Delta angle X (radians)*/
|
||||
float delta_velocity_x; /*< Delta velocity X (m/s)*/
|
||||
float delta_velocity_y; /*< Delta velocity Y (m/s)*/
|
||||
float delta_velocity_z; /*< Delta velocity Z (m/s)*/
|
||||
float joint_roll; /*< Joint ROLL (radians)*/
|
||||
float joint_el; /*< Joint EL (radians)*/
|
||||
float joint_az; /*< Joint AZ (radians)*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_report_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_report_axis_calibration_status_t
|
||||
{
|
||||
uint8_t yaw_requires_calibration; ///< Whether or not the yaw axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration
|
||||
uint8_t pitch_requires_calibration; ///< Whether or not the pitch axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration
|
||||
uint8_t roll_requires_calibration; ///< Whether or not the roll axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration
|
||||
uint8_t yaw_requires_calibration; /*< Whether or not the yaw axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration*/
|
||||
uint8_t pitch_requires_calibration; /*< Whether or not the pitch axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration*/
|
||||
uint8_t roll_requires_calibration; /*< Whether or not the roll axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration*/
|
||||
} mavlink_gimbal_report_axis_calibration_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_REPORT_AXIS_CALIBRATION_STATUS_LEN 3
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_report_factory_tests_progress_t
|
||||
{
|
||||
uint8_t test; ///< Which factory test is currently running
|
||||
uint8_t test_section; ///< Which section of the test is currently running. The meaning of this is test-dependent
|
||||
uint8_t test_section_progress; ///< The progress of the current test section, 0x64=100%
|
||||
uint8_t test_status; ///< The status of the currently executing test section. The meaning of this is test and section-dependent
|
||||
uint8_t test; /*< Which factory test is currently running*/
|
||||
uint8_t test_section; /*< Which section of the test is currently running. The meaning of this is test-dependent*/
|
||||
uint8_t test_section_progress; /*< The progress of the current test section, 0x64=100%*/
|
||||
uint8_t test_status; /*< The status of the currently executing test section. The meaning of this is test and section-dependent*/
|
||||
} mavlink_gimbal_report_factory_tests_progress_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_REPORT_FACTORY_TESTS_PROGRESS_LEN 4
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_request_axis_calibration_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_request_axis_calibration_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_REQUEST_AXIS_CALIBRATION_LEN 2
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_request_axis_calibration_status_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_request_axis_calibration_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_REQUEST_AXIS_CALIBRATION_STATUS_LEN 2
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_reset_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_reset_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_RESET_LEN 2
|
||||
|
@ -4,20 +4,20 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_set_factory_parameters_t
|
||||
{
|
||||
uint32_t magic_1; ///< Magic number 1 for validation
|
||||
uint32_t magic_2; ///< Magic number 2 for validation
|
||||
uint32_t magic_3; ///< Magic number 3 for validation
|
||||
uint32_t serial_number_pt_1; ///< Unit Serial Number Part 1 (part code, design, language/country)
|
||||
uint32_t serial_number_pt_2; ///< Unit Serial Number Part 2 (option, year, month)
|
||||
uint32_t serial_number_pt_3; ///< Unit Serial Number Part 3 (incrementing serial number per month)
|
||||
uint16_t assembly_year; ///< Assembly Date Year
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t assembly_month; ///< Assembly Date Month
|
||||
uint8_t assembly_day; ///< Assembly Date Day
|
||||
uint8_t assembly_hour; ///< Assembly Time Hour
|
||||
uint8_t assembly_minute; ///< Assembly Time Minute
|
||||
uint8_t assembly_second; ///< Assembly Time Second
|
||||
uint32_t magic_1; /*< Magic number 1 for validation*/
|
||||
uint32_t magic_2; /*< Magic number 2 for validation*/
|
||||
uint32_t magic_3; /*< Magic number 3 for validation*/
|
||||
uint32_t serial_number_pt_1; /*< Unit Serial Number Part 1 (part code, design, language/country)*/
|
||||
uint32_t serial_number_pt_2; /*< Unit Serial Number Part 2 (option, year, month)*/
|
||||
uint32_t serial_number_pt_3; /*< Unit Serial Number Part 3 (incrementing serial number per month)*/
|
||||
uint16_t assembly_year; /*< Assembly Date Year*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t assembly_month; /*< Assembly Date Month*/
|
||||
uint8_t assembly_day; /*< Assembly Date Day*/
|
||||
uint8_t assembly_hour; /*< Assembly Time Hour*/
|
||||
uint8_t assembly_minute; /*< Assembly Time Minute*/
|
||||
uint8_t assembly_second; /*< Assembly Time Second*/
|
||||
} mavlink_gimbal_set_factory_parameters_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_SET_FACTORY_PARAMETERS_LEN 33
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gimbal_set_home_offsets_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_set_home_offsets_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_SET_HOME_OFFSETS_LEN 2
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_gopro_get_request_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t cmd_id; ///< Command ID
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
} mavlink_gopro_get_request_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN 3
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gopro_get_response_t
|
||||
{
|
||||
uint8_t cmd_id; ///< Command ID
|
||||
uint8_t value; ///< Value
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t value; /*< Value*/
|
||||
} mavlink_gopro_get_response_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN 2
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
typedef struct __mavlink_gopro_heartbeat_t
|
||||
{
|
||||
uint8_t status; ///< Status
|
||||
uint8_t status; /*< Status*/
|
||||
} mavlink_gopro_heartbeat_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN 1
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
typedef struct __mavlink_gopro_set_request_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t cmd_id; ///< Command ID
|
||||
uint8_t value; ///< Value
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t value; /*< Value*/
|
||||
} mavlink_gopro_set_request_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN 4
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_gopro_set_response_t
|
||||
{
|
||||
uint8_t cmd_id; ///< Command ID
|
||||
uint8_t result; ///< Result
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t result; /*< Result*/
|
||||
} mavlink_gopro_set_response_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN 2
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_hwstatus_t
|
||||
{
|
||||
uint16_t Vcc; ///< board voltage (mV)
|
||||
uint8_t I2Cerr; ///< I2C error count
|
||||
uint16_t Vcc; /*< board voltage (mV)*/
|
||||
uint8_t I2Cerr; /*< I2C error count*/
|
||||
} mavlink_hwstatus_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_led_control_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t instance; ///< Instance (LED instance to control or 255 for all LEDs)
|
||||
uint8_t pattern; ///< Pattern (see LED_PATTERN_ENUM)
|
||||
uint8_t custom_len; ///< Custom Byte Length
|
||||
uint8_t custom_bytes[24]; ///< Custom Bytes
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t instance; /*< Instance (LED instance to control or 255 for all LEDs)*/
|
||||
uint8_t pattern; /*< Pattern (see LED_PATTERN_ENUM)*/
|
||||
uint8_t custom_len; /*< Custom Byte Length*/
|
||||
uint8_t custom_bytes[24]; /*< Custom Bytes*/
|
||||
} mavlink_led_control_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_LED_CONTROL_LEN 29
|
||||
|
@ -4,15 +4,15 @@
|
||||
|
||||
typedef struct __mavlink_limits_status_t
|
||||
{
|
||||
uint32_t last_trigger; ///< time of last breach in milliseconds since boot
|
||||
uint32_t last_action; ///< time of last recovery action in milliseconds since boot
|
||||
uint32_t last_recovery; ///< time of last successful recovery in milliseconds since boot
|
||||
uint32_t last_clear; ///< time of last all-clear in milliseconds since boot
|
||||
uint16_t breach_count; ///< number of fence breaches
|
||||
uint8_t limits_state; ///< state of AP_Limits, (see enum LimitState, LIMITS_STATE)
|
||||
uint8_t mods_enabled; ///< AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)
|
||||
uint8_t mods_required; ///< AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)
|
||||
uint8_t mods_triggered; ///< AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)
|
||||
uint32_t last_trigger; /*< time of last breach in milliseconds since boot*/
|
||||
uint32_t last_action; /*< time of last recovery action in milliseconds since boot*/
|
||||
uint32_t last_recovery; /*< time of last successful recovery in milliseconds since boot*/
|
||||
uint32_t last_clear; /*< time of last all-clear in milliseconds since boot*/
|
||||
uint16_t breach_count; /*< number of fence breaches*/
|
||||
uint8_t limits_state; /*< state of AP_Limits, (see enum LimitState, LIMITS_STATE)*/
|
||||
uint8_t mods_enabled; /*< AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)*/
|
||||
uint8_t mods_required; /*< AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)*/
|
||||
uint8_t mods_triggered; /*< AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)*/
|
||||
} mavlink_limits_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22
|
||||
|
@ -4,15 +4,15 @@
|
||||
|
||||
typedef struct __mavlink_mag_cal_progress_t
|
||||
{
|
||||
float direction_x; ///< Body frame direction vector for display
|
||||
float direction_y; ///< Body frame direction vector for display
|
||||
float direction_z; ///< Body frame direction vector for display
|
||||
uint8_t compass_id; ///< Compass being calibrated
|
||||
uint8_t cal_mask; ///< Bitmask of compasses being calibrated
|
||||
uint8_t cal_status; ///< Status (see MAG_CAL_STATUS enum)
|
||||
uint8_t attempt; ///< Attempt number
|
||||
uint8_t completion_pct; ///< Completion percentage
|
||||
uint8_t completion_mask[10]; ///< Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)
|
||||
float direction_x; /*< Body frame direction vector for display*/
|
||||
float direction_y; /*< Body frame direction vector for display*/
|
||||
float direction_z; /*< Body frame direction vector for display*/
|
||||
uint8_t compass_id; /*< Compass being calibrated*/
|
||||
uint8_t cal_mask; /*< Bitmask of compasses being calibrated*/
|
||||
uint8_t cal_status; /*< Status (see MAG_CAL_STATUS enum)*/
|
||||
uint8_t attempt; /*< Attempt number*/
|
||||
uint8_t completion_pct; /*< Completion percentage*/
|
||||
uint8_t completion_mask[10]; /*< Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)*/
|
||||
} mavlink_mag_cal_progress_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN 27
|
||||
|
@ -4,20 +4,20 @@
|
||||
|
||||
typedef struct __mavlink_mag_cal_report_t
|
||||
{
|
||||
float fitness; ///< RMS milligauss residuals
|
||||
float ofs_x; ///< X offset
|
||||
float ofs_y; ///< Y offset
|
||||
float ofs_z; ///< Z offset
|
||||
float diag_x; ///< X diagonal (matrix 11)
|
||||
float diag_y; ///< Y diagonal (matrix 22)
|
||||
float diag_z; ///< Z diagonal (matrix 33)
|
||||
float offdiag_x; ///< X off-diagonal (matrix 12 and 21)
|
||||
float offdiag_y; ///< Y off-diagonal (matrix 13 and 31)
|
||||
float offdiag_z; ///< Z off-diagonal (matrix 32 and 23)
|
||||
uint8_t compass_id; ///< Compass being calibrated
|
||||
uint8_t cal_mask; ///< Bitmask of compasses being calibrated
|
||||
uint8_t cal_status; ///< Status (see MAG_CAL_STATUS enum)
|
||||
uint8_t autosaved; ///< 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters
|
||||
float fitness; /*< RMS milligauss residuals*/
|
||||
float ofs_x; /*< X offset*/
|
||||
float ofs_y; /*< Y offset*/
|
||||
float ofs_z; /*< Z offset*/
|
||||
float diag_x; /*< X diagonal (matrix 11)*/
|
||||
float diag_y; /*< Y diagonal (matrix 22)*/
|
||||
float diag_z; /*< Z diagonal (matrix 33)*/
|
||||
float offdiag_x; /*< X off-diagonal (matrix 12 and 21)*/
|
||||
float offdiag_y; /*< Y off-diagonal (matrix 13 and 31)*/
|
||||
float offdiag_z; /*< Z off-diagonal (matrix 32 and 23)*/
|
||||
uint8_t compass_id; /*< Compass being calibrated*/
|
||||
uint8_t cal_mask; /*< Bitmask of compasses being calibrated*/
|
||||
uint8_t cal_status; /*< Status (see MAG_CAL_STATUS enum)*/
|
||||
uint8_t autosaved; /*< 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters*/
|
||||
} mavlink_mag_cal_report_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN 44
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_meminfo_t
|
||||
{
|
||||
uint16_t brkval; ///< heap top
|
||||
uint16_t freemem; ///< free memory
|
||||
uint16_t brkval; /*< heap top*/
|
||||
uint16_t freemem; /*< free memory*/
|
||||
} mavlink_meminfo_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MEMINFO_LEN 4
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_mount_configure_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum)
|
||||
uint8_t stab_roll; ///< (1 = yes, 0 = no)
|
||||
uint8_t stab_pitch; ///< (1 = yes, 0 = no)
|
||||
uint8_t stab_yaw; ///< (1 = yes, 0 = no)
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t mount_mode; /*< mount operating mode (see MAV_MOUNT_MODE enum)*/
|
||||
uint8_t stab_roll; /*< (1 = yes, 0 = no)*/
|
||||
uint8_t stab_pitch; /*< (1 = yes, 0 = no)*/
|
||||
uint8_t stab_yaw; /*< (1 = yes, 0 = no)*/
|
||||
} mavlink_mount_configure_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_mount_control_t
|
||||
{
|
||||
int32_t input_a; ///< pitch(deg*100) or lat, depending on mount mode
|
||||
int32_t input_b; ///< roll(deg*100) or lon depending on mount mode
|
||||
int32_t input_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t save_position; ///< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
|
||||
int32_t input_a; /*< pitch(deg*100) or lat, depending on mount mode*/
|
||||
int32_t input_b; /*< roll(deg*100) or lon depending on mount mode*/
|
||||
int32_t input_c; /*< yaw(deg*100) or alt (in cm) depending on mount mode*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t save_position; /*< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)*/
|
||||
} mavlink_mount_control_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
typedef struct __mavlink_mount_status_t
|
||||
{
|
||||
int32_t pointing_a; ///< pitch(deg*100)
|
||||
int32_t pointing_b; ///< roll(deg*100)
|
||||
int32_t pointing_c; ///< yaw(deg*100)
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
int32_t pointing_a; /*< pitch(deg*100)*/
|
||||
int32_t pointing_b; /*< roll(deg*100)*/
|
||||
int32_t pointing_c; /*< yaw(deg*100)*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_mount_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
typedef struct __mavlink_pid_tuning_t
|
||||
{
|
||||
float desired; ///< desired rate (degrees/s)
|
||||
float achieved; ///< achieved rate (degrees/s)
|
||||
float FF; ///< FF component
|
||||
float P; ///< P component
|
||||
float I; ///< I component
|
||||
float D; ///< D component
|
||||
uint8_t axis; ///< axis
|
||||
float desired; /*< desired rate (degrees/s)*/
|
||||
float achieved; /*< achieved rate (degrees/s)*/
|
||||
float FF; /*< FF component*/
|
||||
float P; /*< P component*/
|
||||
float I; /*< I component*/
|
||||
float D; /*< D component*/
|
||||
uint8_t axis; /*< axis*/
|
||||
} mavlink_pid_tuning_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_PID_TUNING_LEN 25
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
typedef struct __mavlink_radio_t
|
||||
{
|
||||
uint16_t rxerrors; ///< receive errors
|
||||
uint16_t fixed; ///< count of error corrected packets
|
||||
uint8_t rssi; ///< local signal strength
|
||||
uint8_t remrssi; ///< remote signal strength
|
||||
uint8_t txbuf; ///< how full the tx buffer is as a percentage
|
||||
uint8_t noise; ///< background noise level
|
||||
uint8_t remnoise; ///< remote background noise level
|
||||
uint16_t rxerrors; /*< receive errors*/
|
||||
uint16_t fixed; /*< count of error corrected packets*/
|
||||
uint8_t rssi; /*< local signal strength*/
|
||||
uint8_t remrssi; /*< remote signal strength*/
|
||||
uint8_t txbuf; /*< how full the tx buffer is as a percentage*/
|
||||
uint8_t noise; /*< background noise level*/
|
||||
uint8_t remnoise; /*< remote background noise level*/
|
||||
} mavlink_radio_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RADIO_LEN 9
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_rally_fetch_point_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t idx; ///< point index (first point is 0)
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t idx; /*< point index (first point is 0)*/
|
||||
} mavlink_rally_fetch_point_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN 3
|
||||
|
@ -4,16 +4,16 @@
|
||||
|
||||
typedef struct __mavlink_rally_point_t
|
||||
{
|
||||
int32_t lat; ///< Latitude of point in degrees * 1E7
|
||||
int32_t lng; ///< Longitude of point in degrees * 1E7
|
||||
int16_t alt; ///< Transit / loiter altitude in meters relative to home
|
||||
int16_t break_alt; ///< Break altitude in meters relative to home
|
||||
uint16_t land_dir; ///< Heading to aim for when landing. In centi-degrees.
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t idx; ///< point index (first point is 0)
|
||||
uint8_t count; ///< total number of points (for sanity checking)
|
||||
uint8_t flags; ///< See RALLY_FLAGS enum for definition of the bitmask.
|
||||
int32_t lat; /*< Latitude of point in degrees * 1E7*/
|
||||
int32_t lng; /*< Longitude of point in degrees * 1E7*/
|
||||
int16_t alt; /*< Transit / loiter altitude in meters relative to home*/
|
||||
int16_t break_alt; /*< Break altitude in meters relative to home*/
|
||||
uint16_t land_dir; /*< Heading to aim for when landing. In centi-degrees.*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t idx; /*< point index (first point is 0)*/
|
||||
uint8_t count; /*< total number of points (for sanity checking)*/
|
||||
uint8_t flags; /*< See RALLY_FLAGS enum for definition of the bitmask.*/
|
||||
} mavlink_rally_point_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RALLY_POINT_LEN 19
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_rangefinder_t
|
||||
{
|
||||
float distance; ///< distance in meters
|
||||
float voltage; ///< raw voltage if available, zero otherwise
|
||||
float distance; /*< distance in meters*/
|
||||
float voltage; /*< raw voltage if available, zero otherwise*/
|
||||
} mavlink_rangefinder_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RANGEFINDER_LEN 8
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_rpm_t
|
||||
{
|
||||
float rpm1; ///< RPM Sensor1
|
||||
float rpm2; ///< RPM Sensor2
|
||||
float rpm1; /*< RPM Sensor1*/
|
||||
float rpm2; /*< RPM Sensor2*/
|
||||
} mavlink_rpm_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RPM_LEN 8
|
||||
|
@ -4,18 +4,18 @@
|
||||
|
||||
typedef struct __mavlink_sensor_offsets_t
|
||||
{
|
||||
float mag_declination; ///< magnetic declination (radians)
|
||||
int32_t raw_press; ///< raw pressure from barometer
|
||||
int32_t raw_temp; ///< raw temperature from barometer
|
||||
float gyro_cal_x; ///< gyro X calibration
|
||||
float gyro_cal_y; ///< gyro Y calibration
|
||||
float gyro_cal_z; ///< gyro Z calibration
|
||||
float accel_cal_x; ///< accel X calibration
|
||||
float accel_cal_y; ///< accel Y calibration
|
||||
float accel_cal_z; ///< accel Z calibration
|
||||
int16_t mag_ofs_x; ///< magnetometer X offset
|
||||
int16_t mag_ofs_y; ///< magnetometer Y offset
|
||||
int16_t mag_ofs_z; ///< magnetometer Z offset
|
||||
float mag_declination; /*< magnetic declination (radians)*/
|
||||
int32_t raw_press; /*< raw pressure from barometer*/
|
||||
int32_t raw_temp; /*< raw temperature from barometer*/
|
||||
float gyro_cal_x; /*< gyro X calibration*/
|
||||
float gyro_cal_y; /*< gyro Y calibration*/
|
||||
float gyro_cal_z; /*< gyro Z calibration*/
|
||||
float accel_cal_x; /*< accel X calibration*/
|
||||
float accel_cal_y; /*< accel Y calibration*/
|
||||
float accel_cal_z; /*< accel Z calibration*/
|
||||
int16_t mag_ofs_x; /*< magnetometer X offset*/
|
||||
int16_t mag_ofs_y; /*< magnetometer Y offset*/
|
||||
int16_t mag_ofs_z; /*< magnetometer Z offset*/
|
||||
} mavlink_sensor_offsets_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
typedef struct __mavlink_set_mag_offsets_t
|
||||
{
|
||||
int16_t mag_ofs_x; ///< magnetometer X offset
|
||||
int16_t mag_ofs_y; ///< magnetometer Y offset
|
||||
int16_t mag_ofs_z; ///< magnetometer Z offset
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
int16_t mag_ofs_x; /*< magnetometer X offset*/
|
||||
int16_t mag_ofs_y; /*< magnetometer Y offset*/
|
||||
int16_t mag_ofs_z; /*< magnetometer Z offset*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_set_mag_offsets_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
typedef struct __mavlink_simstate_t
|
||||
{
|
||||
float roll; ///< Roll angle (rad)
|
||||
float pitch; ///< Pitch angle (rad)
|
||||
float yaw; ///< Yaw angle (rad)
|
||||
float xacc; ///< X acceleration m/s/s
|
||||
float yacc; ///< Y acceleration m/s/s
|
||||
float zacc; ///< Z acceleration m/s/s
|
||||
float xgyro; ///< Angular speed around X axis rad/s
|
||||
float ygyro; ///< Angular speed around Y axis rad/s
|
||||
float zgyro; ///< Angular speed around Z axis rad/s
|
||||
int32_t lat; ///< Latitude in degrees * 1E7
|
||||
int32_t lng; ///< Longitude in degrees * 1E7
|
||||
float roll; /*< Roll angle (rad)*/
|
||||
float pitch; /*< Pitch angle (rad)*/
|
||||
float yaw; /*< Yaw angle (rad)*/
|
||||
float xacc; /*< X acceleration m/s/s*/
|
||||
float yacc; /*< Y acceleration m/s/s*/
|
||||
float zacc; /*< Z acceleration m/s/s*/
|
||||
float xgyro; /*< Angular speed around X axis rad/s*/
|
||||
float ygyro; /*< Angular speed around Y axis rad/s*/
|
||||
float zgyro; /*< Angular speed around Z axis rad/s*/
|
||||
int32_t lat; /*< Latitude in degrees * 1E7*/
|
||||
int32_t lng; /*< Longitude in degrees * 1E7*/
|
||||
} mavlink_simstate_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_SIMSTATE_LEN 44
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_wind_t
|
||||
{
|
||||
float direction; ///< wind direction that wind is coming from (degrees)
|
||||
float speed; ///< wind speed in ground plane (m/s)
|
||||
float speed_z; ///< vertical wind speed (m/s)
|
||||
float direction; /*< wind direction that wind is coming from (degrees)*/
|
||||
float speed; /*< wind speed in ground plane (m/s)*/
|
||||
float speed_z; /*< vertical wind speed (m/s)*/
|
||||
} mavlink_wind_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_WIND_LEN 12
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Fri Sep 11 18:10:30 2015"
|
||||
#define MAVLINK_BUILD_DATE "Sat Sep 12 17:45:03 2015"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
File diff suppressed because one or more lines are too long
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_actuator_control_target_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (micros since boot or Unix epoch)
|
||||
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.
|
||||
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
typedef struct __mavlink_att_pos_mocap_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (micros since boot or Unix epoch)
|
||||
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)
|
||||
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
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)
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_LEN 28
|
||||
|
@ -4,14 +4,14 @@
|
||||
|
||||
typedef struct __mavlink_attitude_quaternion_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds 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)
|
||||
uint32_t time_boot_ms; /*< Timestamp (milliseconds 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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
typedef struct __mavlink_attitude_quaternion_cov_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
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
|
||||
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
typedef struct __mavlink_attitude_target_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp in milliseconds 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 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
|
||||
uint32_t time_boot_ms; /*< Timestamp in milliseconds 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 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;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
typedef struct __mavlink_auth_key_t
|
||||
{
|
||||
char key[32]; ///< key
|
||||
char key[32]; /*< key*/
|
||||
} mavlink_auth_key_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
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
|
||||
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
|
||||
uint32_t board_version; ///< HW / board version (last 8 bytes should be silicon ID, if any)
|
||||
uint16_t vendor_id; ///< ID of the board vendor
|
||||
uint16_t product_id; ///< ID of the product
|
||||
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.
|
||||
uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/
|
||||
uint64_t uid; /*< UID if provided by hardware*/
|
||||
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*/
|
||||
uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/
|
||||
uint16_t vendor_id; /*< ID of the board vendor*/
|
||||
uint16_t product_id; /*< ID of the product*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
|
||||
|
@ -4,15 +4,15 @@
|
||||
|
||||
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)
|
||||
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -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
|
||||
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)*/
|
||||
int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -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;
|
||||
|
||||
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
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.
|
||||
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 "!?,.-"
|
||||
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.*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
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
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_command_ack_t
|
||||
{
|
||||
uint16_t command; ///< Command ID, as defined by MAV_CMD enum.
|
||||
uint8_t result; ///< See MAV_RESULT enum
|
||||
uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/
|
||||
uint8_t result; /*< See MAV_RESULT enum*/
|
||||
} mavlink_command_ack_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
|
||||
|
@ -4,19 +4,19 @@
|
||||
|
||||
typedef struct __mavlink_command_int_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
|
||||
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
|
||||
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 current; ///< false:0, true:1
|
||||
uint8_t autocontinue; ///< autocontinue to next wp
|
||||
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*/
|
||||
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*/
|
||||
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 current; /*< false:0, true:1*/
|
||||
uint8_t autocontinue; /*< autocontinue to next wp*/
|
||||
} mavlink_command_int_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
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.
|
||||
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)
|
||||
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.*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_data_stream_t
|
||||
{
|
||||
uint16_t message_rate; ///< The requested interval between two messages of this type
|
||||
uint8_t stream_id; ///< The ID of the requested data stream
|
||||
uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped.
|
||||
uint16_t message_rate; /*< The requested interval between two messages of this type*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
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]
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
typedef struct __mavlink_debug_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
float value; ///< DEBUG value
|
||||
uint8_t ind; ///< index of debug variable
|
||||
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
|
||||
float value; /*< DEBUG value*/
|
||||
uint8_t ind; /*< index of debug variable*/
|
||||
} mavlink_debug_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG_LEN 9
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
typedef struct __mavlink_debug_vect_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp
|
||||
float x; ///< x
|
||||
float y; ///< y
|
||||
float z; ///< z
|
||||
char name[10]; ///< Name
|
||||
uint64_t time_usec; /*< Timestamp*/
|
||||
float x; /*< x*/
|
||||
float y; /*< y*/
|
||||
float z; /*< z*/
|
||||
char name[10]; /*< Name*/
|
||||
} mavlink_debug_vect_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
|
||||
|
@ -4,14 +4,14 @@
|
||||
|
||||
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.
|
||||
uint8_t id; ///< Onboard ID of the sensor
|
||||
uint8_t orientation; ///< Direction the sensor faces from FIXME enum.
|
||||
uint8_t covariance; ///< Measurement covariance in centimeters, 0 for unknown / invalid readings
|
||||
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.*/
|
||||
uint8_t id; /*< Onboard ID of the sensor*/
|
||||
uint8_t orientation; /*< Direction the sensor faces from FIXME enum.*/
|
||||
uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/
|
||||
} mavlink_distance_sensor_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
typedef struct __mavlink_encapsulated_data_t
|
||||
{
|
||||
uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
|
||||
uint8_t data[253]; ///< image data bytes
|
||||
uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/
|
||||
uint8_t data[253]; /*< image data bytes*/
|
||||
} mavlink_encapsulated_data_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
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.
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
|
||||
|
@ -4,15 +4,15 @@
|
||||
|
||||
typedef struct __mavlink_global_position_int_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
int32_t lat; ///< Latitude, expressed as * 1E7
|
||||
int32_t lon; ///< Longitude, expressed as * 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), 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 hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
|
||||
int32_t lat; /*< Latitude, expressed as * 1E7*/
|
||||
int32_t lon; /*< Longitude, expressed as * 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), 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 hdg; /*< Compass heading in degrees * 100, 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
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
typedef struct __mavlink_global_position_int_cov_t
|
||||
{
|
||||
uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
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), 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.)
|
||||
uint8_t estimator_type; ///< Class id of the estimator this estimate originated from.
|
||||
uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/
|
||||
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), 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.)*/
|
||||
uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
|
||||
} mavlink_global_position_int_cov_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185
|
||||
|
@ -4,13 +4,13 @@
|
||||
|
||||
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
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
|
||||
|
@ -4,18 +4,18 @@
|
||||
|
||||
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; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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
|
||||
uint8_t dgps_numch; ///< Number of DGPS satellites
|
||||
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; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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*/
|
||||
uint8_t dgps_numch; /*< Number of DGPS satellites*/
|
||||
} mavlink_gps2_raw_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
|
||||
|
@ -4,19 +4,19 @@
|
||||
|
||||
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 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 nsats; ///< Current number of sats used for RTK calculation.
|
||||
uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
|
||||
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 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 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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
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)
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
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)
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
|
||||
|
@ -4,16 +4,16 @@
|
||||
|
||||
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.
|
||||
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; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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
|
||||
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.*/
|
||||
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; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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_gps_raw_int_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
|
||||
|
@ -4,19 +4,19 @@
|
||||
|
||||
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 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 nsats; ///< Current number of sats used for RTK calculation.
|
||||
uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
|
||||
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 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 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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RTK_LEN 35
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
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
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
|
||||
|
@ -4,12 +4,12 @@
|
||||
|
||||
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
|
||||
uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
|
||||
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*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
|
||||
|
@ -4,21 +4,21 @@
|
||||
|
||||
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
|
||||
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
|
||||
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*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
|
||||
|
@ -4,17 +4,17 @@
|
||||
|
||||
typedef struct __mavlink_hil_controls_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
float roll_ailerons; ///< Control output -1 .. 1
|
||||
float pitch_elevator; ///< Control output -1 .. 1
|
||||
float yaw_rudder; ///< Control output -1 .. 1
|
||||
float throttle; ///< Throttle 0 .. 1
|
||||
float aux1; ///< Aux 1, -1 .. 1
|
||||
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 nav_mode; ///< Navigation mode (MAV_NAV_MODE)
|
||||
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
|
||||
float roll_ailerons; /*< Control output -1 .. 1*/
|
||||
float pitch_elevator; /*< Control output -1 .. 1*/
|
||||
float yaw_rudder; /*< Control output -1 .. 1*/
|
||||
float throttle; /*< Throttle 0 .. 1*/
|
||||
float aux1; /*< Aux 1, -1 .. 1*/
|
||||
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 nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/
|
||||
} mavlink_hil_controls_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
|
||||
|
@ -4,19 +4,19 @@
|
||||
|
||||
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
|
||||
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
|
||||
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*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_GPS_LEN 36
|
||||
|
@ -4,18 +4,18 @@
|
||||
|
||||
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
|
||||
uint8_t sensor_id; ///< Sensor ID
|
||||
uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
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*/
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
|
||||
|
@ -4,20 +4,20 @@
|
||||
|
||||
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%
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33
|
||||
|
@ -4,21 +4,21 @@
|
||||
|
||||
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
|
||||
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
|
||||
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*/
|
||||
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*/
|
||||
} mavlink_hil_sensor_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64
|
||||
|
@ -4,22 +4,22 @@
|
||||
|
||||
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)
|
||||
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;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user