From 9d36080e66226ff5c209bb1810cd24162704177c Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 22 Aug 2024 11:28:30 +1000 Subject: [PATCH 1/2] MC manual/stabilized rename --- en/SUMMARY.md | 2 +- en/complete_vehicles_mc/crazyflie21.md | 2 +- en/concept/flight_modes.md | 2 +- en/config/_autotune.md | 2 +- en/config_mc/filter_tuning.md | 2 +- en/config_mc/pid_tuning_guide_multicopter.md | 6 +++--- .../pid_tuning_guide_multicopter_basic.md | 2 +- en/config_mc/racer_setup.md | 7 ++----- en/flight_modes_mc/altitude.md | 4 ++-- en/flight_modes_mc/index.md | 3 ++- en/flight_modes_mc/manual_stabilized.md | 21 ++++++++++++------- en/flight_modes_mc/position.md | 4 ++-- en/flying/basic_flying_mc.md | 2 +- 13 files changed, 32 insertions(+), 27 deletions(-) diff --git a/en/SUMMARY.md b/en/SUMMARY.md index 5eb4670723fc..38f6b32ca408 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -7,7 +7,7 @@ - [Position Mode (MC)](flight_modes_mc/position.md) - [Position Slow Mode (MC)](flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](flight_modes_mc/altitude.md) - - [Manual/Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) + - [Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](flight_modes_mc/acro.md) - [Orbit Mode (MC)](flight_modes_mc/orbit.md) - [Takeoff Mode (MC)](flight_modes_mc/takeoff.md) diff --git a/en/complete_vehicles_mc/crazyflie21.md b/en/complete_vehicles_mc/crazyflie21.md index 99586a8a6067..eb8fdd5bf125 100644 --- a/en/complete_vehicles_mc/crazyflie21.md +++ b/en/complete_vehicles_mc/crazyflie21.md @@ -8,7 +8,7 @@ Contact the [manufacturer](https://www.bitcraze.io/) for hardware support or com ::: :::warning -Crazyflie 2.1 is only able to fly in [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md). +Crazyflie 2.1 is only able to fly in [Stabilized mode](../flight_modes_mc/manual_stabilized.md). ::: The Crazyflie line of micro quads was created by Bitcraze AB. diff --git a/en/concept/flight_modes.md b/en/concept/flight_modes.md index de769ed4d225..49aba2e2931b 100644 --- a/en/concept/flight_modes.md +++ b/en/concept/flight_modes.md @@ -46,7 +46,7 @@ For example, experienced fliers can use modes that provide direct passthrough of - **Multirotors:** - - **MANUAL/STABILIZED** The pilot's inputs are passed as roll and pitch _angle_ commands and a yaw _rate_ command. + - **STABILIZED** (**MANUAL** also selects this mode): The pilot's inputs are passed as roll and pitch _angle_ commands and a yaw _rate_ command. Throttle is passed directly to control allocation. The autopilot controls the attitude, meaning it regulates the roll and pitch angles to zero when the RC sticks are centered, consequently leveling-out the attitude. However, in this mode the position of the vehicle is not controlled by the autopilot, hence the position can drift due to wind. diff --git a/en/config/_autotune.md b/en/config/_autotune.md index 4a5557931694..277079fc4ebf 100644 --- a/en/config/_autotune.md +++ b/en/config/_autotune.md @@ -40,7 +40,7 @@ To make sure the vehicle is stable enough for auto-tuning: 1. Perform a normal preflight safety checklist to ensure the flight zone is clear and has enough space. -1. Take off and
hover at 1m above ground in [Altitude mode](../flight_modes_mc/altitude.md) or [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md)
fly at cruise speed in [Position mode](../flight_modes_fw/position.md) or [Altitude mode](../flight_modes_fw/altitude.md)
. +1. Take off and
hover at 1m above ground in [Altitude mode](../flight_modes_mc/altitude.md) or [Stabilized mode](../flight_modes_mc/manual_stabilized.md)
fly at cruise speed in [Position mode](../flight_modes_fw/position.md) or [Altitude mode](../flight_modes_fw/altitude.md)
. 1. Use the RC transmitter roll stick to perform the following maneuver, tilting the vehicle just a few degrees: _roll left > roll right > center_ (The whole maneuver should take about 3 seconds). The vehicle should stabilise itself within 2 oscillations. diff --git a/en/config_mc/filter_tuning.md b/en/config_mc/filter_tuning.md index 662c134c45bd..2940fe583fd9 100644 --- a/en/config_mc/filter_tuning.md +++ b/en/config_mc/filter_tuning.md @@ -96,7 +96,7 @@ First make sure to have the high-rate logging profile activated ([SDLOG_PROFILE] Filter tuning is best done by reviewing flight logs. You can do multiple flights right after each other with different parameters and then inspect all logs, but make sure to disarm in between so that separate log files are created. -The performed flight maneuver can simply be hovering in [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md) with some rolling and pitching to all directions and some increased throttle periods. +The performed flight maneuver can simply be hovering in [Stabilized mode](../flight_modes_mc/manual_stabilized.md) with some rolling and pitching to all directions and some increased throttle periods. The total duration does not need to be more than 30 seconds. In order to better compare, the maneuver should be similar in all tests. diff --git a/en/config_mc/pid_tuning_guide_multicopter.md b/en/config_mc/pid_tuning_guide_multicopter.md index 70cef9457bc4..b4afb920541c 100644 --- a/en/config_mc/pid_tuning_guide_multicopter.md +++ b/en/config_mc/pid_tuning_guide_multicopter.md @@ -91,14 +91,14 @@ The related parameters for the tuning of the PID rate controllers are: - Pitch rate control ([MC_PITCHRATE_P](../advanced_config/parameter_reference.md#MC_PITCHRATE_P), [MC_PITCHRATE_I](../advanced_config/parameter_reference.md#MC_PITCHRATE_I), [MC_PITCHRATE_D](../advanced_config/parameter_reference.md#MC_PITCHRATE_D), [MC_PITCHRATE_K](../advanced_config/parameter_reference.md#MC_PITCHRATE_K)) - Yaw rate control ([MC_YAWRATE_P](../advanced_config/parameter_reference.md#MC_YAWRATE_P), [MC_YAWRATE_I](../advanced_config/parameter_reference.md#MC_YAWRATE_I), [MC_YAWRATE_D](../advanced_config/parameter_reference.md#MC_YAWRATE_D), [MC_YAWRATE_K](../advanced_config/parameter_reference.md#MC_YAWRATE_K)) -The rate controller can be tuned in [Acro mode](../flight_modes_mc/acro.md) or [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md): +The rate controller can be tuned in [Acro mode](../flight_modes_mc/acro.md) or [Stabilized mode](../flight_modes_mc/manual_stabilized.md): - _Acro mode_ is preferred, but is harder to fly. If you choose this mode, disable all stick expo: - `MC_ACRO_EXPO` = 0, `MC_ACRO_EXPO_Y` = 0, `MC_ACRO_SUPEXPO` = 0, `MC_ACRO_SUPEXPOY` = 0 - `MC_ACRO_P_MAX` = 200, `MC_ACRO_R_MAX` = 200 - `MC_ACRO_Y_MAX` = 100 -- _Manual/Stabilized mode_ is simpler to fly, but it is also more difficult to see if the attitude or the rate controller needs more tuning. +- _Stabilized mode_ is simpler to fly, but it is also more difficult to see if the attitude or the rate controller needs more tuning. If the vehicle does not fly at all: @@ -185,7 +185,7 @@ This controls the orientation and outputs desired body rates with the following The attitude controller is much easier to tune. In fact, most of the time the defaults do not need to be changed at all. -To tune the attitude controller, fly in _Manual/Stabilized mode_ and increase the **P** gains gradually. +To tune the attitude controller, fly in _Stabilized mode_ and increase the **P** gains gradually. If you start to see oscillations or overshoots, the gains are too high. The following parameters can also be adjusted. These determine the maximum rotation rates around all three axes: diff --git a/en/config_mc/pid_tuning_guide_multicopter_basic.md b/en/config_mc/pid_tuning_guide_multicopter_basic.md index dbafeb230982..1faf538b8f70 100644 --- a/en/config_mc/pid_tuning_guide_multicopter_basic.md +++ b/en/config_mc/pid_tuning_guide_multicopter_basic.md @@ -45,7 +45,7 @@ Then adjust the sliders (as discussed below) to improve the tracking of the resp - If using PWM outputs their minimum values should be set correctly in the [Actuator Configuration](../config/actuators.md). These need to be set low, but such that the **motors never stop** when the vehicle is armed. - This can be tested in [Acro mode](../flight_modes_mc/acro.md) or in [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md): + This can be tested in [Acro mode](../flight_modes_mc/acro.md) or in [Stabilized mode](../flight_modes_mc/manual_stabilized.md): - Remove propellers - Arm the vehicle and lower the throttle to the minimum diff --git a/en/config_mc/racer_setup.md b/en/config_mc/racer_setup.md index 2b45c60606fc..c34261d76631 100644 --- a/en/config_mc/racer_setup.md +++ b/en/config_mc/racer_setup.md @@ -76,8 +76,7 @@ In particular, set the [Airframe](../config/airframe.md) that most closely match These parameters are important: - Enable One-Shot or DShot by selecting the protocol for a group of outputs during [Actuator Configuration](../config/actuators.md). -- Set the maximum roll-, pitch- and yaw rates for Manual/Stabilized mode as - desired: [MC_ROLLRATE_MAX](../advanced_config/parameter_reference.md#MC_ROLLRATE_MAX), [MC_PITCHRATE_MAX](../advanced_config/parameter_reference.md#MC_PITCHRATE_MAX) and [MC_YAWRATE_MAX](../advanced_config/parameter_reference.md#MC_YAWRATE_MAX). +- Set the maximum roll-, pitch- and yaw rates for Stabilized mode as desired: [MC_ROLLRATE_MAX](../advanced_config/parameter_reference.md#MC_ROLLRATE_MAX), [MC_PITCHRATE_MAX](../advanced_config/parameter_reference.md#MC_PITCHRATE_MAX) and [MC_YAWRATE_MAX](../advanced_config/parameter_reference.md#MC_YAWRATE_MAX). The maximum tilt angle is configured with [MPC_MAN_TILT_MAX](../advanced_config/parameter_reference.md#MPC_MAN_TILT_MAX). - The minimum thrust [MPC_MANTHR_MIN](../advanced_config/parameter_reference.md#MPC_MANTHR_MIN) should be set to 0. @@ -85,7 +84,7 @@ These parameters are important: If you use a GPS you can skip this section and use the default estimator. Otherwise you should switch to the Q attitude estimator, which works without a magnetometer or barometer. - + To enable it set [ATT_EN = 1](../advanced_config/parameter_reference.md#ATT_EN), [EKF2_EN =0 ](../advanced_config/parameter_reference.md#EKF2_EN) and [LPE_EN = 0](../advanced_config/parameter_reference.md#LPE_EN) (for more information see [Switching State Estimators](../advanced/switching_state_estimators.md#how-to-enable-different-estimators)). Then change the following parameters: @@ -152,5 +151,3 @@ You can use the approach described in [Basic MC PID tuning](../config_mc/pid_tun After you have verified that the vehicle flies well at low and high throttle, you can enable [airmode](../config_mc/pid_tuning_guide_multicopter.md#airmode) with the [MC_AIRMODE](../advanced_config/parameter_reference.md#MC_AIRMODE) parameter. This feature makes sure that the vehicle is still controllable and tracks the rate at low throttle. - -Happy flipping :) diff --git a/en/flight_modes_mc/altitude.md b/en/flight_modes_mc/altitude.md index 12677aaa784b..13d54b914832 100644 --- a/en/flight_modes_mc/altitude.md +++ b/en/flight_modes_mc/altitude.md @@ -9,7 +9,7 @@ If moving in the horizontal plane the vehicle will continue until any momentum i If the wind blows the aircraft will drift in the direction of the wind. :::tip -_Altitude mode_ is the safest non-GPS manual mode for new fliers. It is just like [Manual/Stabilized](../flight_modes_mc/manual_stabilized.md) mode but additionally locks the vehicle altitude when the sticks are released. +_Altitude mode_ is the safest non-GPS manual mode for new fliers. It is just like [Stabilized](../flight_modes_mc/manual_stabilized.md) mode but additionally locks the vehicle altitude when the sticks are released. ::: The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)). @@ -18,7 +18,7 @@ The diagram below shows the mode behaviour visually (for a [mode 2 transmitter]( ## Technical Summary -RC/manual mode like [Manual/Stabilized (MC)](../flight_modes_mc/manual_stabilized.md) mode but with _altitude stabilization_ (centered sticks level vehicle and hold it to fixed altitude). +RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) but with _altitude stabilization_ (centred sticks level vehicle and hold it to fixed altitude). The horizontal position of the vehicle can move due to wind (or pre-existing momentum). - Centered sticks (inside deadband): diff --git a/en/flight_modes_mc/index.md b/en/flight_modes_mc/index.md index 2a5230d985a7..23677bbf0d05 100644 --- a/en/flight_modes_mc/index.md +++ b/en/flight_modes_mc/index.md @@ -18,8 +18,9 @@ Manual-Easy: This is primarily used to temporarily limit speed when flying near obstacles, or when required by regulation. - [Altitude mode](../flight_modes_mc/altitude.md) — Easiest and safest _non-GPS_ manual mode. The main difference when compared to _Position mode_ is that when the sticks are released the vehicle will level and maintain altitude, but there is no active breaking or holding of horizontal position (the vehicle moves with it's current momentum and drifts with wind). -- [Manual/Stabilized](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). +- [Stabilized mode](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). The vehicle will continue to move with momentum, and both altitude and horizontal position may be affected by wind. + This mode is also used if "Manual mode" is selected in a ground station. Manual-Acrobatic diff --git a/en/flight_modes_mc/manual_stabilized.md b/en/flight_modes_mc/manual_stabilized.md index 67160c08d81d..9d3f29112dbf 100644 --- a/en/flight_modes_mc/manual_stabilized.md +++ b/en/flight_modes_mc/manual_stabilized.md @@ -1,23 +1,30 @@ -# Manual/Stabilized Mode (Multicopter) +# Stabilized Mode (Multicopter)    -The _Manual/Stabilized_ mode stabilizes the multicopter when the RC control sticks are centred. To manually move/fly the vehicle you move the sticks outside of the centre. +The _Stabilized_ manual mode stabilizes and levels the multicopter when the RC control sticks are centred. +To move/fly the vehicle you move the sticks outside of the centre. ::: info -This multicopter mode is enabled if you set either _Manual_ or _Stabilized_ modes. +This mode is also enabled if you set the flight mode to _Manual_. ::: -When under manual control the roll and pitch sticks control the _angle_ of the vehicle (attitude) around the respective axes, the yaw stick controls the rate of rotation above the horizontal plane, and the throttle controls altitude/speed. +When sticks are outside the centre, the roll and pitch sticks control the _angle_ of the vehicle (attitude) around the respective axes, the yaw stick controls the rate of rotation above the horizontal plane, and the throttle controls altitude/speed. -As soon as you release the control sticks they will return to the center deadzone. The multicopter will level out and stop once the roll and pitch sticks are centered. -The vehicle will then hover in place/maintain altitude - provided it is properly balanced, throttle is set appropriately (see [below](#params)), and no external forces are applied (e.g. wind). The craft will drift in the direction of any wind and you have to control the throttle to hold altitude. +As soon as you release the control sticks they will return to the center deadzone. +The multicopter will level out and stop once the roll and pitch sticks are centered. +The vehicle will then hover in place/maintain altitude - provided it is properly balanced, throttle is set appropriately (see [below](#params)), and no external forces are applied (e.g. wind). +The craft will drift in the direction of any wind and you have to control the throttle to hold altitude. ![MC Manual Flight](../../assets/flight_modes/stabilized_mc.png) ## Technical Description -RC mode where centered sticks level vehicle (only - position is not stabilized). +RC mode where centered sticks level vehicle. + +::: info +[Altitude mode](../flight_modes_mc/altitude.md) additionally stabilizes the vehicle altitude when sticks are centred, and [Position mode](../flight_modes_mc/position.md) stabilizes both altitude and position over ground. +::: The pilot's inputs are passed as roll and pitch angle commands and a yaw rate command. Throttle is rescaled (see [below](#params)) and passed directly to control allocation. diff --git a/en/flight_modes_mc/position.md b/en/flight_modes_mc/position.md index 6f101486c4fe..cb85fc53acf0 100644 --- a/en/flight_modes_mc/position.md +++ b/en/flight_modes_mc/position.md @@ -8,7 +8,7 @@ With full stick deflection the vehicle accelerates initially with [MPC_ACC_HOR_M :::tip Position mode is the safest manual mode for new fliers. -Unlike [Altitude](../flight_modes_mc/altitude.md) and [Manual/Stabilized](../flight_modes_mc/manual_stabilized.md) modes the vehicle will stop when the sticks are centered rather than continuing until slowed by wind resistance. +Unlike [Altitude](../flight_modes_mc/altitude.md) and [Stabilized](../flight_modes_mc/manual_stabilized.md) modes the vehicle will stop when the sticks are centered rather than continuing until slowed by wind resistance. ::: The diagram below shows the mode behaviour visually (for a mode 2 transmitter). @@ -33,7 +33,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi The approach is the same as above, except that you must manually ensure that the vehicle stays above the landing spot using the roll and pitch stick. - After landing check GPS and magnetometer orientation, calibration. - If the vehicle does not detect the ground/landing and disarm: - - After the vehicle is on the ground switch to [Manual/Stabilized mode](../flight_modes_mc/manual_stabilized.md) keeping the throttle stick low, and manually disarm using a gesture or other command. + - After the vehicle is on the ground switch to [Stabilized mode](../flight_modes_mc/manual_stabilized.md) keeping the throttle stick low, and manually disarm using a gesture or other command. Alternatively you can also use the kill switch when the vehicle is already on the ground. ::: diff --git a/en/flying/basic_flying_mc.md b/en/flying/basic_flying_mc.md index fb21e8928b1f..cc2c87ef2182 100644 --- a/en/flying/basic_flying_mc.md +++ b/en/flying/basic_flying_mc.md @@ -86,7 +86,7 @@ The following three modes are highly recommended for new users: - [Position mode](../flight_modes_mc/position.md) - When sticks are released the vehicle will stop (and hold position against wind drift) - [Altitude mode](../flight_modes_mc/altitude.md) - Climb and drop are controlled to have a maximum rate. -- [Manual/Stabilized Mode](../flight_modes_mc/manual_stabilized.md) - Vehicle hard to flip, and will level-out if the sticks are released (but not hold position) +- [Stabilized mode](../flight_modes_mc/manual_stabilized.md) - Vehicle hard to flip, and will level-out if the sticks are released (but not hold position) ::: info You can also engage automatic modes on the _QGroundControl_ main flight screen. From f0057e4572b99d8aefe4f8613cd49e314bdc0403 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 22 Aug 2024 11:29:21 +1000 Subject: [PATCH 2/2] Fix up alt sidebar --- de/_sidebar.md | 20 +++++++++++++++----- en/_sidebar.md | 23 ++++++++++++++++------- ja/_sidebar.md | 20 +++++++++++++++----- ko/_sidebar.md | 20 +++++++++++++++----- ru/_sidebar.md | 20 +++++++++++++++----- tr/_sidebar.md | 20 +++++++++++++++----- uk/_sidebar.md | 24 +++++++++++++++++------- zh/_sidebar.md | 20 +++++++++++++++----- 8 files changed, 123 insertions(+), 44 deletions(-) diff --git a/de/_sidebar.md b/de/_sidebar.md index 85f9327b0bc1..2fd56804d3d9 100644 --- a/de/_sidebar.md +++ b/de/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [VTOL](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL Config/Tuning](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [QuadPlane Configuration](/config_vtol/vtol_quad_configuration.md) - [Back-transition Tuning](/config_vtol/vtol_back_transition_tuning.md) - [VTOL w/o Airspeed Sensor](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [Vehicle Status Notifications](/getting_started/vehicle_status.md) - [LED Meanings](/getting_started/led_meanings.md) - [Tune/Sound Meanings](/getting_started/tunes.md) - - [Preflight Checks](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [Flight Controllers (Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon Battery Smartification Kit](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [Companion Computers](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [Autotune](/config/autotune.md) - [Advanced Configuration](/advanced_config/index.md) - [ECL/EKF Overview & Tuning](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/en/_sidebar.md b/en/_sidebar.md index 9b33abb3e1d6..9f9b19208e54 100644 --- a/en/_sidebar.md +++ b/en/_sidebar.md @@ -8,7 +8,7 @@ - [Position Mode (MC)](/flight_modes_mc/position.md) - [Position Slow Mode (MC)](/flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](/flight_modes_mc/altitude.md) - - [Manual/Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) + - [Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](/flight_modes_mc/acro.md) - [Orbit Mode (MC)](/flight_modes_mc/orbit.md) - [Takeoff Mode (MC)](/flight_modes_mc/takeoff.md) @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [VTOL](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL Config/Tuning](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [QuadPlane Configuration](/config_vtol/vtol_quad_configuration.md) - [Back-transition Tuning](/config_vtol/vtol_back_transition_tuning.md) - [VTOL w/o Airspeed Sensor](/config_vtol/vtol_without_airspeed_sensor.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon Battery Smartification Kit](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [Companion Computers](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -353,8 +359,6 @@ - [Holybro Pixhawk RPI CM4 Baseboard](/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md) - [Auterion Skynode](/companion_computer/auterion_skynode.md) - [Computer Vision](/computer_vision/index.md) - - [Obstacle Avoidance](/computer_vision/obstacle_avoidance.md) - - [Safe Landing](/computer_vision/safe_landing.md) - [Collision Prevention](/computer_vision/collision_prevention.md) - [Path Planning Interface](/computer_vision/path_planning_interface.md) - [Motion Capture (MoCap)](/computer_vision/motion_capture.md) @@ -365,7 +369,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [Autotune](/config/autotune.md) - [Advanced Configuration](/advanced_config/index.md) - [ECL/EKF Overview & Tuning](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) @@ -379,9 +382,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -418,6 +423,7 @@ - [Gazebo Simulation](/sim_gazebo_gz/index.md) - [Vehicles](/sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md) + - [Worlds](/sim_gazebo_gz/worlds.md) - [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md) - [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md) - [Gazebo Classic Simulation](/sim_gazebo_classic/index.md) @@ -590,6 +596,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/ja/_sidebar.md b/ja/_sidebar.md index 8bd0e48178be..2a578c46ecb6 100644 --- a/ja/_sidebar.md +++ b/ja/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [VTOL](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL機設定/チューニング](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [クアッド型機の設定](/config_vtol/vtol_quad_configuration.md) - [バックトランジションチューニング](/config_vtol/vtol_back_transition_tuning.md) - [VTOL機/速度センサなし](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [機体ステータス表示](/getting_started/vehicle_status.md) - [LED表示の意味](/getting_started/led_meanings.md) - [通知音の意味](/getting_started/tunes.md) - - [飛行前チェック](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [Flight Controllers (Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon Battery Smartification Kit](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [Companion Computers](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [Autotune](/config/autotune.md) - [応用設定](/advanced_config/index.md) - [ECL/EKF 概要 & チューニング](/advanced_config/tuning_the_ecl_ekf.md) - [パラメータの検索/更新](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [機体構造一覧](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/ko/_sidebar.md b/ko/_sidebar.md index e2b9a90d1e3d..24c9988db64f 100644 --- a/ko/_sidebar.md +++ b/ko/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/README.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/README.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [수직이착륙기(VTOL)](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL 설정 및 튜닝](/config_vtol/README.md) + - [Auto-tune](/config/autotune_vtol.md) - [QuadPlane 설정](/config_vtol/vtol_quad_configuration.md) - [후방 이동 튜닝](/config_vtol/vtol_back_transition_tuning.md) - [항속 센서 미장착 VTOL](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [기체 상태 표시](/getting_started/vehicle_status.md) - [LED 신호 정의](/getting_started/led_meanings.md) - [알람 소리 정의](/getting_started/tunes.md) - - [사전 비행 점검](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [비행 컨트롤러 (오토파일럿)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon 배터리 스마트 키트](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [배선 개요](/assembly/cable_wiring.md) - [보조 컴퓨터](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [직렬 포트 설정 ](/peripherals/serial_configuration.md) - [PX4 이더넷 설정](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/README.md) - - [자동 튜닝](/config/autotune.md) - [고급 설정](/advanced_config/README.md) - [ECL/EKF 개요 및 튜닝](/advanced_config/tuning_the_ecl_ekf.md) - [매개변수 검색 및 수정](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [트락사스 Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [블루로브2](/frames_sub/bluerov2.md) - [기체 프레임 정의서](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/ru/_sidebar.md b/ru/_sidebar.md index 85f9327b0bc1..2fd56804d3d9 100644 --- a/ru/_sidebar.md +++ b/ru/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [VTOL](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL Config/Tuning](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [QuadPlane Configuration](/config_vtol/vtol_quad_configuration.md) - [Back-transition Tuning](/config_vtol/vtol_back_transition_tuning.md) - [VTOL w/o Airspeed Sensor](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [Vehicle Status Notifications](/getting_started/vehicle_status.md) - [LED Meanings](/getting_started/led_meanings.md) - [Tune/Sound Meanings](/getting_started/tunes.md) - - [Preflight Checks](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [Flight Controllers (Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon Battery Smartification Kit](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [Companion Computers](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [Autotune](/config/autotune.md) - [Advanced Configuration](/advanced_config/index.md) - [ECL/EKF Overview & Tuning](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/tr/_sidebar.md b/tr/_sidebar.md index 85f9327b0bc1..2fd56804d3d9 100644 --- a/tr/_sidebar.md +++ b/tr/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [VTOL](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [VTOL Config/Tuning](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [QuadPlane Configuration](/config_vtol/vtol_quad_configuration.md) - [Back-transition Tuning](/config_vtol/vtol_back_transition_tuning.md) - [VTOL w/o Airspeed Sensor](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [Vehicle Status Notifications](/getting_started/vehicle_status.md) - [LED Meanings](/getting_started/led_meanings.md) - [Tune/Sound Meanings](/getting_started/tunes.md) - - [Preflight Checks](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [Flight Controllers (Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon Battery Smartification Kit](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [Companion Computers](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [Autotune](/config/autotune.md) - [Advanced Configuration](/advanced_config/index.md) - [ECL/EKF Overview & Tuning](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/uk/_sidebar.md b/uk/_sidebar.md index d1ae3a34f2a4..08603b33910a 100644 --- a/uk/_sidebar.md +++ b/uk/_sidebar.md @@ -23,6 +23,7 @@ - [Запуск з катапульти чи підкиданням](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Конфігурація/Підлаштування](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Фільтрація та контроль налаштувань затримки](/config_mc/filter_tuning.md) - [Налаштування PID (Вручну/Базова)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID налаштування(Вручну/По-складному)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Літаки (з фіксованим крилом)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Конфігурація/підлаштування](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [ VTOL (Вертикальний зліт та посадка)](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [Конфігурація/Налаштування VTOL](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [Конфігурація Квадроплана](/config_vtol/vtol_quad_configuration.md) - [Настройка Зворотнього Переходу](/config_vtol/vtol_back_transition_tuning.md) - [ВЗІП Датчик польоту](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [Повідомлення про статус літального апарату](/getting_started/vehicle_status.md) - [Значення світлодіодів](/getting_started/led_meanings.md) - [Значення звуків та мелодій](/getting_started/tunes.md) - - [Перевірки перед польотом](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Вибір обладнання & Налаштування](/hardware/drone_parts.md) - [Flight Controllers (Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -223,7 +227,7 @@ - [Калібрування](/config/compass.md) - [Compass Power Compensation](/advanced_config/compass_power_compensation.md) - [Датчики швидкості повітря](/sensor/airspeed.md) - - [Калібрування](/config/airspeed.md) + - [Calibration](/config/airspeed.md) - [ВЗІП Датчик польоту](/sensor/airspeed_tfslot.md) - [Барометри](/sensor/barometer.md) - [Датчики відстані \(далекодобива\)](/sensor/rangefinders.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (цифровий)](/power_module/holybro_pm02d.md) - [Holybro PM03D (цифровий)](/power_module/holybro_pm03d.md) - [Силовий модуль Pomegranate Systems](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Акумулятори Smart/MAVLink](/smart_batteries/index.md) - [Rotoye Batmon Комплект інтелектуального акумулятора](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [Периферійні пристрої DroneCAN](/dronecan/index.md) - [Прошивка PX4 DroneCAN](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Підключення дротів](/assembly/cable_wiring.md) - [Комп’ютери-супутники](/companion_computer/index.md) - [Налаштування Pixhawk + Companion](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [Serial Port Configuration](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Стандартна конфігурація](/config/index.md) - - [Автоматичне підлаштування](/config/autotune.md) - [Розширені налаштування](/advanced_config/index.md) - [ECL/EKF Overview & Tuning](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -408,7 +415,7 @@ - [Діаграми контролера](/flight_stack/controller_diagrams.md) - [Параметри та налаштування](/advanced/parameters_and_configurations.md) - [Інтерфейс подій](/concept/events_interface.md) - - [Режими польоту](/concept/flight_modes.md) + - [Flight Modes](/concept/flight_modes.md) - [Польотні завдання](/concept/flight_tasks.md) - [Control Allocation](/concept/control_allocation.md) - [PWM limit state machine](/concept/pwm_limit.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md) diff --git a/zh/_sidebar.md b/zh/_sidebar.md index 304b6a00b84e..17591c13648b 100644 --- a/zh/_sidebar.md +++ b/zh/_sidebar.md @@ -23,6 +23,7 @@ - [Throw Launch](/flight_modes_mc/throw_launch.md) - [Assembly](/assembly/assembly_mc.md) - [Configuration/Tuning](/config_mc/index.md) + - [Auto-tune](/config/autotune_mc.md) - [Filter/Control Latency Tuning](/config_mc/filter_tuning.md) - [PID Tuning (Manual/Basic)](/config_mc/pid_tuning_guide_multicopter_basic.md) - [PID Tuning Guide (Manual/Advanced)](/config_mc/pid_tuning_guide_multicopter.md) @@ -55,6 +56,7 @@ - [Planes (Fixed-Wing)](/frames_plane/index.md) - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) + - [Auto-tune](/config/autotune_fw.md) - [Rate/Attitude Controller Tuning Guide](/config_fw/pid_tuning_guide_fixedwing.md) - [Altitude/Position Controller Tuning Guide](/config_fw/position_tuning_guide_fixedwing.md) - [Weight & Altitude Tuning](/config_fw/weight_and_altitude_tuning.md) @@ -81,6 +83,7 @@ - [垂直起降](/frames_vtol/index.md) - [Assembly](/assembly/assembly_vtol.md) - [垂直起降配置/调试](/config_vtol/index.md) + - [Auto-tune](/config/autotune_vtol.md) - [四旋翼型固定翼配置](/config_vtol/vtol_quad_configuration.md) - [VTOL后转换调参](/config_vtol/vtol_back_transition_tuning.md) - [没有空速传感器的VTOL ](/config_vtol/vtol_without_airspeed_sensor.md) @@ -119,7 +122,7 @@ - [载具状态通知](/getting_started/vehicle_status.md) - [LED灯含义](/getting_started/led_meanings.md) - [声调/声音含义](/getting_started/tunes.md) - - [飞行前检查](/flying/pre_flight_checks.md) + - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - [飞行控制器(Autopilots)](/flight_controller/index.md) @@ -141,6 +144,7 @@ - [Holybro Pixhawk 6X-RT (FMUv6X-RT)](/flight_controller/pixhawk6x-rt.md) - [Holybro Pixhawk 6X (FMUv6X)](/flight_controller/pixhawk6x.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6x.md) + - [RaccoonLab FMU6x](/flight_controller/raccoonlab_fmu6x.md) - [Holybro Pixhawk 6C (FMUv6C)](/flight_controller/pixhawk6c.md) - [Wiring Quickstart](/assembly/quick_start_pixhawk6c.md) - [Holybro Pixhawk 6C Mini(FMUv6C)](/flight_controller/pixhawk6c_mini.md) @@ -320,6 +324,7 @@ - [Holybro PM02D (digital)](/power_module/holybro_pm02d.md) - [Holybro PM03D (digital)](/power_module/holybro_pm03d.md) - [Pomegranate Systems Power Module](/dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Modules](/dronecan/raccoonlab_power.md) - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon 电池智能套装](/smart_batteries/rotoye_batmon.md) @@ -345,6 +350,7 @@ - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) + - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) - [Cable Wiring](/assembly/cable_wiring.md) - [机载电脑](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) @@ -365,7 +371,6 @@ - [串口配置](/peripherals/serial_configuration.md) - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) - [Standard Configuration](/config/index.md) - - [自动调参](/config/autotune.md) - [高级配置](/advanced_config/index.md) - [ECL/EKF 概述 &调试](/advanced_config/tuning_the_ecl_ekf.md) - [查找/更新参数](/advanced_config/parameters.md) @@ -379,9 +384,11 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Flight Modes](/flight_modes_rover/index.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Traxxas Stampede](/frames_rover/traxxas_stampede.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Differential-steering Rover](/frames_rover/differential_rover.md) + - [Aion Robotics R1](/frames_rover/aion_r1.md) + - [Ackermann Rover](/frames_rover/ackermann_rover.md) + - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [机架参考](/airframes/airframe_reference.md) @@ -590,6 +597,9 @@ - [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md) - [RegisterExtComponentRequest](/msg_docs/RegisterExtComponentRequest.md) - [RoverAckermannGuidanceStatus](/msg_docs/RoverAckermannGuidanceStatus.md) + - [RoverAckermannStatus](/msg_docs/RoverAckermannStatus.md) + - [RoverDifferentialGuidanceStatus](/msg_docs/RoverDifferentialGuidanceStatus.md) + - [RoverDifferentialStatus](/msg_docs/RoverDifferentialStatus.md) - [Rpm](/msg_docs/Rpm.md) - [RtlStatus](/msg_docs/RtlStatus.md) - [RtlTimeEstimate](/msg_docs/RtlTimeEstimate.md)