PX4-Autopilot/docs/uk/msg_docs/EstimatorSensorBias.md
Hamish Willee 88d623bedb
Move PX4 Guide source into /docs (#24490)
* Add vitepress tree

* Update existing workflows so they dont trigger on changes in the docs path

* Add nojekyll, package.json, LICENCE etc

* Add crowdin docs upload/download scripts

* Add docs flaw checker workflows

* Used docs prefix for docs workflows

* Crowdin obvious fixes

* ci: docs move to self hosted runner

runs on a beefy server for faster builds

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* ci: don't run build action for docs or ci changes

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* ci: update runners

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* Add docs/en

* Add docs assets and scripts

* Fix up editlinks to point to PX4 sources

* Download just the translations that are supported

* Add translation sources for zh, uk, ko

* Update latest tranlsation and uorb graphs

* update vitepress to latest

---------

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Co-authored-by: Ramon Roche <mrpollo@gmail.com>
2025-03-13 16:08:27 +11:00

41 lines
2.2 KiB
Markdown
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

# EstimatorSensorBias (повідомлення UORB)
Показання датчиків та похибки в процесі роботи в одиницях СІ. Показання датчиків компенсуються для статичних зсувів,
похибки шкали, зсув під час роботи та тепловий зсув (якщо термокомпенсація увімкнена та доступна).
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSensorBias.msg)
```c
#
# Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets,
# scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available).
#
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
# In-run bias estimates (subtract from uncorrected data)
uint32 gyro_device_id # unique device ID for the sensor that does not change between power cycles
float32[3] gyro_bias # gyroscope in-run bias in body frame (rad/s)
float32 gyro_bias_limit # magnitude of maximum gyroscope in-run bias in body frame (rad/s)
float32[3] gyro_bias_variance
bool gyro_bias_valid
bool gyro_bias_stable # true when the gyro bias estimate is stable enough to use for calibration
uint32 accel_device_id # unique device ID for the sensor that does not change between power cycles
float32[3] accel_bias # accelerometer in-run bias in body frame (m/s^2)
float32 accel_bias_limit # magnitude of maximum accelerometer in-run bias in body frame (m/s^2)
float32[3] accel_bias_variance
bool accel_bias_valid
bool accel_bias_stable # true when the accel bias estimate is stable enough to use for calibration
uint32 mag_device_id # unique device ID for the sensor that does not change between power cycles
float32[3] mag_bias # magnetometer in-run bias in body frame (Gauss)
float32 mag_bias_limit # magnitude of maximum magnetometer in-run bias in body frame (Gauss)
float32[3] mag_bias_variance
bool mag_bias_valid
bool mag_bias_stable # true when the mag bias estimate is stable enough to use for calibration
```