PX4-Autopilot/docs/ko/msg_docs/SensorUwb.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

45 lines
1.8 KiB
Markdown

# SensorUwb (UORB message)
UWB distance contains the distance information measured by an ultra-wideband positioning system,
such as Pozyx or NXP Rddrone.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorUwb.msg)
```c
# UWB distance contains the distance information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.
uint64 timestamp # time since system start (microseconds)
uint32 sessionid # UWB SessionID
uint32 time_offset # Time between Ranging Rounds in ms
uint32 counter # Number of Ranges since last Start of Ranging
uint16 mac # MAC adress of Initiator (controller)
uint16 mac_dest # MAC adress of Responder (Controlee)
uint16 status # status feedback #
uint8 nlos # None line of site condition y/n
float32 distance # distance in m to the UWB receiver
#Angle of arrival, Angle in Degree -60..+60; FOV in both axis is 120 degrees
float32 aoa_azimuth_dev # Angle of arrival of first incomming RX msg
float32 aoa_elevation_dev # Angle of arrival of first incomming RX msg
float32 aoa_azimuth_resp # Angle of arrival of first incomming RX msg at the responder
float32 aoa_elevation_resp # Angle of arrival of first incomming RX msg at the responder
# Figure of merit for the angle measurements
uint8 aoa_azimuth_fom # AOA Azimuth FOM
uint8 aoa_elevation_fom # AOA Elevation FOM
uint8 aoa_dest_azimuth_fom # AOA Azimuth FOM
uint8 aoa_dest_elevation_fom # AOA Elevation FOM
# Initiator physical configuration
uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum
# Standard configuration is Antennas facing down and azimuth aligened in forward direction
float32 offset_x # UWB initiator offset in X axis (NED drone frame)
float32 offset_y # UWB initiator offset in Y axis (NED drone frame)
float32 offset_z # UWB initiator offset in Z axis (NED drone frame)
```