New Crowdin translations - uk (#25611)

Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
This commit is contained in:
PX4 Build Bot
2025-09-24 17:25:13 +10:00
committed by GitHub
parent 11359791a0
commit b28bdd600b

View File

@@ -267,9 +267,9 @@ private:
class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1]
{
public:
MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2]
: ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode),
_node(node)
MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2]
: ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode),
_node(owned_mode.node())
{ }
enum class State // [3]
@@ -345,8 +345,8 @@ private:
Наступні розділи надають список підтримуваних типів установок:
- GotoSetpointType: Плавне позиціонування та (за бажанням) керування курсом
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь
:::tip
@@ -355,14 +355,18 @@ The other setpoint types are currently experimental, and can be found in: [px4_r
Ви можете додати свої власні типи установок, додавши клас, який успадковується від px4_ros2::SetpointBase, встановлює прапорці конфігурації відповідно до того, що вимагає установка, а потім публікує будь-яку тему, що містить установку
:::
#### Установка "перейти до" (GotoSetpointType)
#### Go-to Setpoint (MulticopterGotoSetpointType)
<Badge type="warning" text="MC only" />
:::info
Цей тип установки наразі підтримується лише для багтрикоптерів.
This setpoint type is currently only supported for multicopters.
:::
Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type.
Тип установки транслюється до плавних позиційних та курсових вирівнювачів на основі FMU, сформульованих з оптимальним за часом, максимальною швидкістю зміни прискорення, з обмеженнями швидкості та прискорення.
Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type.
The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints.
There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates.
Найбільш тривіальне використання полягає в простому введенні 3D-позиції в метод оновлення:
@@ -554,7 +558,7 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX).
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:
- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html).
- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html).
- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype).
As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required.