PX4-Autopilot/docs/ko/msg_docs/ActuatorMotors.md
PX4 Build Bot be0ee3d185
docs(i18n): PX4 guide translations (Crowdin) - ko (#26758)
Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
2026-03-19 15:36:21 +11:00

58 lines
4.6 KiB
Markdown

---
pageClass: is-wide-page
---
# ActuatorMotors (UORB message)
Motor control message.
Normalised thrust setpoint for up to 12 motors.
Published by the vehicle's allocation and consumed by the ESC protocol drivers e.g. PWM, DSHOT, UAVCAN.
**TOPICS:** actuator_motors
## Fields
| 명칭 | 형식 | Unit [Frame] | Range/Enum | 설명 |
| ------------------------------------- | ------------- | ---------------------------------------------------------------- | ---------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| timestamp | `uint64` | us | | Time since system start |
| timestamp_sample | `uint64` | us | | Sampling timestamp of the data this control response is based on |
| reversible_flags | `uint16` | | | Bitset indicating which motors are configured to be reversible |
| control | `float32[12]` | | [-1 : 1] | Normalized thrust. Where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) |
## Constants
| 명칭 | 형식 | Value | 설명 |
| --------------------------------------------------------------------------------------------------------- | -------- | ----- | -------------------------------------------------------------------------------------- |
| <a id="#MESSAGE_VERSION"></a> MESSAGE_VERSION | `uint32` | 0 | |
| <a id="#ACTUATOR_FUNCTION_MOTOR1"></a> ACTUATOR_FUNCTION_MOTOR1 | `uint8` | 101 | output_functions.yaml Motor.start |
| <a id="#NUM_CONTROLS"></a> NUM_CONTROLS | `uint8` | 12 | output_functions.yaml Motor.count |
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg)
:::details
Click here to see original file
```c
# Motor control message
#
# Normalised thrust setpoint for up to 12 motors.
# Published by the vehicle's allocation and consumed by the ESC protocol drivers e.g. PWM, DSHOT, UAVCAN.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # output_functions.yaml Motor.start
uint8 NUM_CONTROLS = 12 # output_functions.yaml Motor.count
float32[12] control # [@range -1, 1] Normalized thrust. Where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors)
```
:::