New Crowdin translations - ko (#25888)

Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
This commit is contained in:
PX4 Build Bot
2025-11-19 15:56:28 +11:00
committed by GitHub
parent e54d1fd114
commit ad2279adb5
9 changed files with 302 additions and 12 deletions

View File

@@ -182,6 +182,7 @@
- [Wiring Quickstart](assembly/quick_start_durandal.md)
- [Holybro Pix32 v5](flight_controller/holybro_pix32_v5.md)
- [Wiring Quickstart](assembly/quick_start_holybro_pix32_v5.md)
- [MicoAir H743 Lite](flight_controller/micoair743-lite.md)
- [ModalAI VOXL 2](flight_controller/modalai_voxl_2.md)
- [mRo Control Zero F7](flight_controller/mro_control_zero_f7.md)
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
@@ -504,6 +505,7 @@
- [UART/Serial 포트](uart/index.md)
- [포트 설정 가능 시리얼 드라이버](uart/user_configurable_serial_driver.md)
- [RTK GPS (통합)](advanced/rtk_gps.md)
- [PPS Time Synchronization](advanced/pps_time_sync.md)
- [미들웨어](middleware/index.md)
- [uORB 메시지 전송](middleware/uorb.md)
- [uORB 그라프](middleware/uorb_graph.md)

View File

@@ -0,0 +1,135 @@
# PPS Time Synchronization (PX4 Integration)
[Pulse Per Second](https://en.wikipedia.org/wiki/Pulse-per-second_signal) (PPS) time synchronization provides high-precision timing for GNSS receivers.
This page explains how PPS is integrated into PX4 and how to configure it.
## 개요
PPS (Pulse Per Second) is a timing signal provided by GNSS receivers that outputs an electrical pulse once per second, synchronized to UTC time.
The PPS signal provides a highly accurate timing reference that PX4 can use to:
- Refine GNSS time measurements and compensate for clock drift
- Provide precise UTC timestamps for camera capture events (for photogrammetry and mapping applications)
- Enable offline position refinement through accurate time correlation
## 지원 하드웨어
PPS time synchronization can be supported on flight controllers that have a hardware timer input pin that can be configured for PPS capture, by [enabling the PPS capture driver](#enable-pps-driver-in-board-configuration) in the board configuration.
Supported boards include (at time of writing):
- [Ark FMUv6x](../flight_controller/ark_v6x.md)
- Auterion FMUv6x
- Auterion FMUv6s
## 설정
### Enable PPS Driver in Board Configuration
The [PPS capture driver](../modules/modules_driver.md#pps-capture) must be enabled in the board configuration.
This is done by adding the following to your board's configuration:
```ini
CONFIG_DRIVERS_PPS_CAPTURE=y
```
### Configure PPS Parameters
The configuration varies depending on your flight controller hardware.
#### FMUv6X
For FMUv6X-based flight controllers, configure PWM AUX Timer 3 and Function 9:
```sh
param set PWM_AUX_TIM3 -2
param set PWM_AUX_FUNC9 2064
param set PPS_CAP_ENABLE 1
```
#### FMUv6S
For FMUv6S-based flight controllers, configure PWM MAIN Timer 3 and Function 10:
```sh
param set PWM_MAIN_TIM3 -2
param set PWM_MAIN_FUNC10 2064
param set PPS_CAP_ENABLE 1
```
### 배선
The wiring configuration depends on your specific flight controller.
#### Skynode X (FMUv6x)
Connect the PPS signal from your GNSS module to the flight controller using the 11-pin or 6-pin GPS connector:
For detailed pinout information, refer to:
- [Skynode GPS Peripherals - Pinouts](https://docs.auterion.com/hardware-integration/skynode/peripherals/gps#pinouts)
#### Skynode S (FMUv6S)
For FMUv6S, you need to route the PPS signal separately:
1. Connect your GNSS module using the standard 6-pin GPS connector: [Skynode S GPS Interface](https://docs.auterion.com/hardware-integration/skynode-s/interfaces#gps)
2. Connect the PPS signal from your GNSS module to the **PPM_IN** pin: [Skynode S Extras 1 Interface](https://docs.auterion.com/hardware-integration/skynode-s/interfaces#extras-1)
#### ARK Jetson Carrier Board (FMUv6x)
For ARK FMUv6X on the Jetson carrier board:
1. Connect your GNSS module using either the 10-pin or 6-pin GPS connector: [ARK PAB GPS1 Interface](../flight_controller/ark_pab#gps1)
2. Connect the PPS signal to the **FMU_CAP** pin: [ARK PAB ADIO Interface](../flight_controller/ark_pab.md#adio)
## 검증
After configuring PPS, you can verify that it is working correctly:
1. Connect to the [PX4 System Console](../debug/system_console.md) (via MAVLink shell or serial console).
2. Wait for GNSS fix.
3. Check the PPS capture status to confirm it is up and running:
```sh
pps_capture status
```
4. You can also check the [PpsCapture](../msg_docs/PpsCapture.md) uORB topic
```sh
listener pps_capture
```
Where you should see: `timestamp`, `rtc_timestamp`, and `pps_rate_exceeded_counter`.
### PPS Capture Driver
The PPS capture driver is located in `src/drivers/pps_capture` and uses hardware timer input capture to precisely measure the arrival time of each PPS pulse.
주요 기능:
- Sub-microsecond pulse capture precision (hardware-dependent)
- Automatic drift calculation and compensation
- Integration with the GNSS driver for refined time stamping
See also:
- [PPS Capture Driver Documentation](../modules/modules_driver.md#pps-capture)
- [PpsCapture Message](../msg_docs/PpsCapture.md)
### Time Synchronization Flow
1. GNSS module sends position/time data at ~1-20 Hz.
2. GNSS module outputs PPS pulse at 1 Hz, precisely aligned to UTC second boundary.
3. PPS capture driver measures the exact time of the PPS pulse arrival using hardware timer.
4. Driver calculates the offset between GNSS time (from UART data) and autopilot clock (from PPS measurement).
5. This offset is used to correct GNSS timestamps and improve sensor fusion accuracy.
The PPS signal provides much higher temporal precision than the transmitted time data, which has latency and jitter from serial communication.
:::warning
If the PPS driver does not sending any data for 5 seconds (despite having `PPS_CAP_ENABLE` set to 1), the `EKF2_GPS_DELAY` will be used instead for estimating the latency.
:::

View File

@@ -89,7 +89,7 @@ Flight controllers that have bootloader PX4-Autopilot `make` targets, can build
The list of controllers for which this applies can be obtained by running the following `make` command, and noting the `make` targets that end in `_bootloader`
```
$make list_config_targets
$ make list_config_targets
...
cuav_nora_bootloader

View File

@@ -30,6 +30,7 @@ This category includes boards that are not fully compliant with the pixhawk stan
- [Holybro Kakute H7](../flight_controller/kakuteh7.md)
- [Holybro Durandal](../flight_controller/durandal.md)
- [Holybro Pix32 v5](../flight_controller/holybro_pix32_v5.md)
- [MicoAir H743 Lite](../flight_controller/micoair743-lite.md)
- [ModalAI VOXL 2](../flight_controller/modalai_voxl_2.md)
- [mRo Control Zero](../flight_controller/mro_control_zero_f7.md)
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)

View File

@@ -0,0 +1,153 @@
# MicoAir743-Lite
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://micoair.com/) for hardware support or compliance issues.
:::
MicoAir743-Lite is an ultra-high performance H743 flight controller with an unbeatable price, featuring the ICM45686 IMU sensor and integrated Bluetooth telemetry.
![MicoAir743-Lite Front View](../../assets/flight_controller/micoair743_lite/front_view.png)
Equipped with a high-performance H7 processor, the MicoAir743-Lite features a compact form factor with SH1.0 connectors (which are more suitable than Pixhawk-standard GH1.25 for this board size).
When paired with with Bluetooth telemetry, the board can be debugged with a phone or PC.
:::info
This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
:::
## MicoAir743-Lite (v1.1)
![MicoAir743-Lite Back View](../../assets/flight_controller/micoair743_lite/back_view.png)
## 요약
### Processors & Sensors
- FMU Processor: STM32H743
- 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
- 내장 센서 :
- Accel/Gyro: ICM-45686 (with BalancedGyro™ Technology)
- Barometer: SPA06
- On-board Bluetooth Telemetry
- Connected to UART8 internally, baudrate 115200
- Connecting to QGC (PC or Android phone) via Bluetooth
- 기타 특성:
- Operating & storage temperature: -20 ~ 85°c
### 인터페이스
- 8 UART (TELEM / GPS / RC)
- 14 PWM outputs 10 supports DShot
- Support multiple RC inputs (SBUS / CRSF / DSM)
- 1 GPS port
- 1 I2C port
- 2 ADC port2 (VBAT, Current)
- 1 DJI O3/O4 VTX connector
- 1 MicroSD Card Slot
- 1 USB Type-C
### Electrical data
- VBAT Input:
- 2\~6S (6\~27V)
- USB Power Input:
- 4.75\~5.25V
- BEC Output:
- 5V 2A (for controller, receiver, GPS, optical flow or other devices)
- 9V 2A (for video transmitter, camera)
### Mechanical data
- Mounting: 30.5 x 30.5mm, Φ4mm
- Dimensions: 36 x 36 x 8 mm
- Weight: 10g
![MicoAir743-Lite Size](../../assets/flight_controller/micoair743_lite/size.png)
## 구매처
Order from [MicoAir Tech Store](https://store.micoair.com/product/micoair743-lite/).
## 핀배열
Pinouts definition can be found in the [MicoAir743-Lite_pinout.xlsx](https://raw.githubusercontent.com/PX4/PX4-Autopilot/refs/heads/main/docs/assets/flight_controller/micoair743_lite/micoair743_lite_pinout.xlsx) file.
## 시리얼 포트 매핑
| UART | 장치 | 포트 |
| ------ | ---------- | ------ |
| USART1 | /dev/ttyS0 | TELEM1 |
| USART2 | /dev/ttyS1 | GPS2 |
| USART3 | /dev/ttyS2 | GPS1 |
| UART4 | /dev/ttyS3 | TELEM2 |
| UART5 | /dev/ttyS4 | TELEM3 |
| USART6 | /dev/ttyS5 | RC |
| UART7 | /dev/ttyS6 | URT6 |
| UART8 | /dev/ttyS7 | TELEM4 |
## Interfaces Diagram
:::note
All the connectors used on the board are SH1.0
:::
![MicoAir743-Lite Interface Diagram](../../assets/flight_controller/micoair743_lite/interfaces_diagram.png)
## Sample Wiring Diagram
![MicoAir743-Lite Wiring Diagram](../../assets/flight_controller/micoair743_lite/wiring_diagram.png)
## 펌웨어 빌드
To [build PX4](../dev_setup/building_px4.md) for this target:
```sh
make micoair_h743-lite_default
```
## 펌웨어 설치
펌웨어는 일반적인 방법으로 설치할 수 있습니다.
- 소스 빌드 및 업로드
```sh
make micoair_h743-lite_default upload
```
- [Load the firmware](../config/firmware.md) using _QGroundControl_.
미리 빌드된 펌웨어나 사용자 지정 펌웨어를 사용할 수 있습니다.
::: info
At time of writing the only pre-built software is `PX4 main` (see [Installing PX4 Main, Beta or Custom Firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware)).
Release builds will be supported for PX4 v1.17 and later.
:::
## 무선 조종
A [Radio Control (RC) system](../getting_started/rc_transmitter_receiver.md) is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
The RC port is connected to the FMU and you can attach a receiver that uses the protocols `DSM`, `SBUS`, `CSRF`, `GHST`, or other protocol listed in [Radio Control modules](../modules/modules_driver_radio_control.md).
You will need to enable the protocol by setting the corresponding parameter `RC_xxxx_PRT_CFG`, such as [RC_CRSF_PRT_CFG](../advanced_config/parameter_reference.md#RC_CRSF_PRT_CFG) for a [CRSF receiver](../telemetry/crsf_telemetry.md).
## 지원 플랫폼 및 기체
일반 RC 서보 또는 Futaba S-Bus 서보로 제어 가능한 모든 멀티콥터/비행기/로버 또는 보트.
The complete set of supported configurations can be seen in the [Airframes Reference](../airframes/airframe_reference.md).
## 주변 장치
- [MicoAir Telemetry Radio Modules](https://micoair.com/radio_telemetry/)
- [MicoAir Optical & Range Sensor](https://micoair.com/optical_range_sensor/)
- [MicoAir GPS](https://micoair.com/gps/)
- [MicoAir ESC Modules](https://micoair.com/esc/)
## 추가 정보
- [MicoAir Tech.](https://micoair.com/)
- [Details about MicoAir743-Lite](https://micoair.com/flightcontroller_micoair743lite/)
- [QGroundControl Download and Install](https://docs.qgroundcontrol.com/Stable_V5.0/en/qgc-user-guide/getting_started/download_and_install.html)

View File

@@ -25,11 +25,6 @@ The default type is recommended.
:::
:::warning
There is a known issue ([PX4-Autopilot#25436](https://github.com/PX4/PX4-Autopilot/issues/25436)) with fixed-wing approaches and landings while in RTL mode.
Please review the issue and verify in simulation that the behavior you get is safe in an RTL landing scenario (if not, consider using rally points).
:::
## Technical Summary
Fixed-wing vehicles use the _mission landing/rally point_ return type by default.

View File

@@ -145,21 +145,21 @@ To ensure the port is set up correctly perform a [Serial Port Configuration](../
The following steps show how to configure a secondary GPS on the `GPS 2` port in _QGroundControl_:
1. [Find and set](../advanced_config/parameters.md) the parameter [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) to **GPS 2**.
- Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section.
- Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list.
- Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section.
- Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list.
![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png)
![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png)
2. 다른 매개변수를 표시하려면 기체를 재부팅하십시오.
3. Select the **Serial** tab, and open the [SER_GPS2_BAUD](../advanced_config/parameter_reference.md#SER_GPS2_BAUD) parameter (`GPS 2` port baud rate): set it to _Auto_ (or 115200 for the Trimble).
![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png)
![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png)
보조 GPS 포트를 설정 후 :
1. 두 GPS 시스템의 데이터를 혼합하도록 ECL/EKF2 추정기를 설정합니다.
For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers).
For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers).
### DroneCAN GNSS Configuration
@@ -201,7 +201,9 @@ EPH/EPV values therefore provide a more immediate and practical estimate of the
- GPS/RTK-GPS
- [RTK-GPS](../advanced/rtk_gps.md)
- [PPS Time Synchronization](../advanced/pps_time_sync.md)
- [GPS driver](../modules/modules_driver.md#gps)
- [PPS driver](../modules/modules_driver.md#pps-capture)
- [DroneCAN Example](../dronecan/index.md)
- 나침반
- [Driver source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer) (Compasses)

View File

@@ -40,6 +40,7 @@ This list contains stand-alone magnetometer modules (without GNSS).
| 장치 | 나침반 | DroneCan |
| :--------------------------------------------------------------------------------------------------------------- | :----: | :------: |
| [ARK MAG](https://arkelectron.com/product/ark-mag/) | RM3100 | ✓ |
| [Avionics Anonymous UAVCAN Magnetometer](https://www.tindie.com/products/avionicsanonymous/uavcan-magnetometer/) | ? | |
| [Holybro DroneCAN RM3100 Compass/Magnetometer](https://holybro.com/products/dronecan-rm3100-compass) | RM3100 | ✓ |
| [RaccoonLab DroneCAN/Cyphal Magnetometer RM3100](https://holybro.com/products/dronecan-rm3100-compass) | RM3100 | ✓ |

View File

@@ -454,6 +454,7 @@ uxrce_dds_client start -n fancy_uav
```
This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md).
:::
## PX4 ROS 2 QoS Settings
@@ -588,7 +589,7 @@ For a list of services, details and examples see the [service documentation](../
These guidelines explain how to migrate from using PX4 v1.13 [Fast-RTPS](../middleware/micrortps.md) middleware to PX4 v1.14 `uXRCE-DDS` middleware.
These are useful if you have [ROS 2 applications written for PX4 v1.13](https://docs.px4.io/v1.13/en/ros/ros2_comm.html), or you have used Fast-RTPS to interface your applications to PX4 [directly](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent).
::: info
:::info
This section contains migration-specific information.
You should also read the rest of this page to properly understand uXRCE-DDS.
:::