mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 17:07:34 +08:00
New Crowdin translations - ko (#25780)
Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
This commit is contained in:
@@ -1,29 +1,39 @@
|
||||
# AirspeedValidated (UORB message)
|
||||
|
||||
Validated airspeed
|
||||
|
||||
Provides information about airspeed (indicated, true, calibrated) and the source of the data.
|
||||
Used by controllers, estimators and for airspeed reporting to operator.
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg)
|
||||
|
||||
```c
|
||||
# Validated airspeed
|
||||
#
|
||||
# Provides information about airspeed (indicated, true, calibrated) and the source of the data.
|
||||
# Used by controllers, estimators and for airspeed reporting to operator.
|
||||
|
||||
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid
|
||||
float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid
|
||||
float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid
|
||||
float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS)
|
||||
float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS)
|
||||
float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS)
|
||||
|
||||
int8 airspeed_source # Source of currently published airspeed values
|
||||
int8 DISABLED = -1
|
||||
int8 GROUND_MINUS_WIND = 0
|
||||
int8 SENSOR_1 = 1
|
||||
int8 SENSOR_2 = 2
|
||||
int8 SENSOR_3 = 3
|
||||
int8 SYNTHETIC = 4
|
||||
int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values
|
||||
int8 SOURCE_DISABLED = -1 # Disabled
|
||||
int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind
|
||||
int8 SOURCE_SENSOR_1 = 1 # Sensor 1
|
||||
int8 SOURCE_SENSOR_2 = 2 # Sensor 2
|
||||
int8 SOURCE_SENSOR_3 = 3 # Sensor 3
|
||||
int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed
|
||||
|
||||
# debug states
|
||||
float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid
|
||||
float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid
|
||||
float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s]
|
||||
float32 throttle_filtered # filtered fixed-wing throttle [-]
|
||||
float32 pitch_filtered # filtered pitch [rad]
|
||||
float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption
|
||||
float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed
|
||||
float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative
|
||||
float32 throttle_filtered # [-] Filtered fixed-wing throttle
|
||||
float32 pitch_filtered # [rad] Filtered pitch
|
||||
|
||||
```
|
||||
|
||||
@@ -1,42 +1,59 @@
|
||||
# AutotuneAttitudeControlStatus (UORB message)
|
||||
|
||||
Autotune attitude control status
|
||||
|
||||
This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune,
|
||||
and is subscribed to by the respective attitude controllers to command rate setpoints.
|
||||
|
||||
The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging.
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg)
|
||||
|
||||
```c
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
# Autotune attitude control status
|
||||
#
|
||||
# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune,
|
||||
# and is subscribed to by the respective attitude controllers to command rate setpoints.
|
||||
#
|
||||
# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging.
|
||||
|
||||
float32[5] coeff # coefficients of the identified discrete-time model
|
||||
float32[5] coeff_var # coefficients' variance of the identified discrete-time model
|
||||
float32 fitness # fitness of the parameter estimate
|
||||
float32 innov
|
||||
float32 dt_model
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 kc
|
||||
float32 ki
|
||||
float32 kd
|
||||
float32 kff
|
||||
float32 att_p
|
||||
float32[5] coeff # [-] Coefficients of the identified discrete-time model
|
||||
float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model
|
||||
float32 fitness # [-] Fitness of the parameter estimate
|
||||
float32 innov # [rad/s] Innovation (residual error between model and measured output)
|
||||
float32 dt_model # [s] Model sample time used for identification
|
||||
|
||||
float32[3] rate_sp
|
||||
|
||||
float32 u_filt
|
||||
float32 y_filt
|
||||
float32 kc # [-] Proportional rate-loop gain (ideal form)
|
||||
float32 ki # [-] Integral rate-loop gain (ideal form)
|
||||
float32 kd # [-] Derivative rate-loop gain (ideal form)
|
||||
float32 kff # [-] Feedforward rate-loop gain
|
||||
float32 att_p # [-] Proportional attitude gain
|
||||
|
||||
uint8 STATE_IDLE = 0
|
||||
uint8 STATE_INIT = 1
|
||||
uint8 STATE_ROLL = 2
|
||||
uint8 STATE_ROLL_PAUSE = 3
|
||||
uint8 STATE_PITCH = 4
|
||||
uint8 STATE_PITCH_PAUSE = 5
|
||||
uint8 STATE_YAW = 6
|
||||
uint8 STATE_YAW_PAUSE = 7
|
||||
uint8 STATE_VERIFICATION = 8
|
||||
uint8 STATE_APPLY = 9
|
||||
uint8 STATE_TEST = 10
|
||||
uint8 STATE_COMPLETE = 11
|
||||
uint8 STATE_FAIL = 12
|
||||
uint8 STATE_WAIT_FOR_DISARM = 13
|
||||
float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller.
|
||||
|
||||
uint8 state
|
||||
float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification.
|
||||
float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification.
|
||||
|
||||
uint8 state # [@enum STATE] Current state of the autotune procedure.
|
||||
uint8 STATE_IDLE = 0 # Idle (not running)
|
||||
uint8 STATE_INIT = 1 # Initialize filters and setup
|
||||
uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll)
|
||||
uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification
|
||||
uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight
|
||||
uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch)
|
||||
uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification
|
||||
uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight
|
||||
uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw)
|
||||
uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification
|
||||
uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight
|
||||
uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains
|
||||
uint8 STATE_APPLY = 12 # Apply gains
|
||||
uint8 STATE_TEST = 13 # Test gains in closed-loop
|
||||
uint8 STATE_COMPLETE = 14 # Tuning completed successfully
|
||||
uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable)
|
||||
uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing
|
||||
|
||||
```
|
||||
|
||||
@@ -24,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status.
|
||||
# Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value.
|
||||
|
||||
uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector
|
||||
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
|
||||
|
||||
```
|
||||
|
||||
@@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein
|
||||
bool cs_constant_pos # 42 - true if the vehicle is at a constant position
|
||||
bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used
|
||||
bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended
|
||||
bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used
|
||||
bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty
|
||||
bool cs_yaw_manual # 46 - true if yaw has been set manually
|
||||
bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty
|
||||
|
||||
# fault status
|
||||
uint32 fault_status_changes # number of filter fault status (fs) changes
|
||||
|
||||
@@ -17,5 +17,6 @@ bool fd_motor
|
||||
|
||||
float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed)
|
||||
uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures
|
||||
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
|
||||
|
||||
```
|
||||
|
||||
@@ -14,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2
|
||||
uint16 DEVICE_FLAGS_ROLL_LOCK = 4
|
||||
uint16 DEVICE_FLAGS_PITCH_LOCK = 8
|
||||
uint16 DEVICE_FLAGS_YAW_LOCK = 16
|
||||
uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32
|
||||
uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64
|
||||
|
||||
|
||||
float32[4] q
|
||||
float32 angular_velocity_x
|
||||
|
||||
@@ -0,0 +1,19 @@
|
||||
# SensorGnssStatus (UORB message)
|
||||
|
||||
Gnss quality indicators
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg)
|
||||
|
||||
```c
|
||||
# Gnss quality indicators
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles
|
||||
|
||||
bool quality_available # Set to true if quality indicators are available
|
||||
uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available
|
||||
uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available
|
||||
uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available
|
||||
uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available
|
||||
|
||||
```
|
||||
@@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision
|
||||
int32 noise_per_ms # GPS noise per millisecond
|
||||
uint16 automatic_gain_control # Automatic gain control monitor
|
||||
|
||||
uint8 JAMMING_STATE_UNKNOWN = 0
|
||||
uint8 JAMMING_STATE_OK = 1
|
||||
uint8 JAMMING_STATE_WARNING = 2
|
||||
uint8 JAMMING_STATE_CRITICAL = 3
|
||||
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
|
||||
int32 jamming_indicator # indicates jamming is occurring
|
||||
uint8 JAMMING_STATE_UNKNOWN = 0 #default
|
||||
uint8 JAMMING_STATE_OK = 1
|
||||
uint8 JAMMING_STATE_MITIGATED = 2
|
||||
uint8 JAMMING_STATE_DETECTED = 3
|
||||
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected
|
||||
int32 jamming_indicator # indicates jamming is occurring
|
||||
|
||||
uint8 SPOOFING_STATE_UNKNOWN = 0
|
||||
uint8 SPOOFING_STATE_NONE = 1
|
||||
uint8 SPOOFING_STATE_INDICATED = 2
|
||||
uint8 SPOOFING_STATE_MULTIPLE = 3
|
||||
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
|
||||
uint8 SPOOFING_STATE_UNKNOWN = 0 #default
|
||||
uint8 SPOOFING_STATE_OK = 1
|
||||
uint8 SPOOFING_STATE_MITIGATED = 2
|
||||
uint8 SPOOFING_STATE_DETECTED = 3
|
||||
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected
|
||||
|
||||
# Combined authentication state (e.g. Galileo OSNMA)
|
||||
uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default
|
||||
uint8 AUTHENTICATION_STATE_INITIALIZING = 1
|
||||
uint8 AUTHENTICATION_STATE_ERROR = 2
|
||||
uint8 AUTHENTICATION_STATE_OK = 3
|
||||
uint8 AUTHENTICATION_STATE_DISABLED = 4
|
||||
uint8 authentication_state # GPS signal authentication state
|
||||
|
||||
float32 vel_m_s # GPS ground speed, (metres/sec)
|
||||
float32 vel_n_m_s # GPS North velocity, (metres/sec)
|
||||
@@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi
|
||||
|
||||
uint8 satellites_used # Number of satellites used
|
||||
|
||||
uint32 SYSTEM_ERROR_OK = 0 #default
|
||||
uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1
|
||||
uint32 SYSTEM_ERROR_CONFIGURATION = 2
|
||||
uint32 SYSTEM_ERROR_SOFTWARE = 4
|
||||
uint32 SYSTEM_ERROR_ANTENNA = 8
|
||||
uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16
|
||||
uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32
|
||||
uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64
|
||||
uint32 system_error # General errors with the connected GPS receiver
|
||||
|
||||
float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI])
|
||||
float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI])
|
||||
float32 heading_accuracy # heading accuracy (rad, [0, 2PI])
|
||||
|
||||
@@ -1,41 +1,44 @@
|
||||
# VehicleOdometry (UORB message)
|
||||
|
||||
Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
Vehicle odometry data
|
||||
|
||||
Fits ROS REP 147 for aerial vehicles
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg)
|
||||
|
||||
```c
|
||||
# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
# Vehicle odometry data
|
||||
#
|
||||
# Fits ROS REP 147 for aerial vehicles
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp_sample
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Timestamp sample
|
||||
|
||||
uint8 POSE_FRAME_UNKNOWN = 0
|
||||
uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame
|
||||
uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference
|
||||
uint8 pose_frame # Position and orientation frame of reference
|
||||
uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference
|
||||
uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame
|
||||
uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North.
|
||||
uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down.
|
||||
|
||||
float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown
|
||||
float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown
|
||||
float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup.
|
||||
float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world)
|
||||
|
||||
uint8 VELOCITY_FRAME_UNKNOWN = 0
|
||||
uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame
|
||||
uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference
|
||||
uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame
|
||||
uint8 velocity_frame # Reference frame of the velocity data
|
||||
uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data
|
||||
uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame
|
||||
uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position.
|
||||
uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down.
|
||||
uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame
|
||||
|
||||
float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown
|
||||
float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity.
|
||||
float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame
|
||||
|
||||
float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown
|
||||
float32[3] position_variance # [m^2] Variance of position error
|
||||
float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame)
|
||||
float32[3] velocity_variance # [m^2/s^2] Variance of velocity error
|
||||
|
||||
float32[3] position_variance
|
||||
float32[3] orientation_variance
|
||||
float32[3] velocity_variance
|
||||
|
||||
uint8 reset_counter
|
||||
int8 quality
|
||||
uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position.
|
||||
int8 quality # [-] [@invalid 0] Quality. Unused.
|
||||
|
||||
# TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry
|
||||
# TOPICS estimator_odometry
|
||||
|
||||
@@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
|
||||
- [ActuatorMotors](ActuatorMotors.md) — Motor control message
|
||||
- [ActuatorServos](ActuatorServos.md) — Servo control message
|
||||
- [AirspeedValidated](AirspeedValidated.md)
|
||||
- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed
|
||||
- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply
|
||||
- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request
|
||||
- [BatteryStatus](BatteryStatus.md) — Battery status
|
||||
@@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
- [VehicleLandDetected](VehicleLandDetected.md)
|
||||
- [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED.
|
||||
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
|
||||
- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data
|
||||
- [VehicleRatesSetpoint](VehicleRatesSetpoint.md)
|
||||
- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander
|
||||
- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE
|
||||
@@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
- [AdcReport](AdcReport.md)
|
||||
- [Airspeed](Airspeed.md) — Airspeed data from sensors
|
||||
- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector)
|
||||
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md)
|
||||
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status
|
||||
- [BatteryInfo](BatteryInfo.md) — Battery information
|
||||
- [ButtonEvent](ButtonEvent.md)
|
||||
- [CameraCapture](CameraCapture.md)
|
||||
@@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
change with board revisions and sensor updates.
|
||||
- [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor
|
||||
- [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station.
|
||||
- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators
|
||||
- [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates.
|
||||
the field 'timestamp' is for the position & velocity (microseconds)
|
||||
- [SensorGyro](SensorGyro.md)
|
||||
|
||||
Reference in New Issue
Block a user