diff --git a/de/SUMMARY.md b/de/SUMMARY.md
index b6c944c1e6ce..089e8110176b 100644
--- a/de/SUMMARY.md
+++ b/de/SUMMARY.md
@@ -12,6 +12,7 @@
* [LED Meanings](getting_started/led_meanings.md)
* [Tune/Sound Meanings](getting_started/tunes.md)
* [Preflight Checks](flying/pre_flight_checks.md)
+ * [Payloads & Cameras](payloads/README.md)
* [Flight Reporting](getting_started/flight_reporting.md)
* [Basic Assembly](assembly/README.md)
* [Mounting the Flight Controller](assembly/mount_and_orient_controller.md)
@@ -229,10 +230,10 @@
* [FrSky Telemetry](peripherals/frsky_telemetry.md)
* [Power Modules](power_module/README.md)
* [CUAV HV pm](power_module/cuav_hv_pm.md)
- * [CUAV CAN PMU](power_module/cuav_can_pmu.md)
+ * [CUAV CAN PMU](uavcan/cuav_can_pmu.md)
* [Holybro PM07 (Pixhawk 4 PM)](power_module/holybro_pm07_pixhawk4_power_module.md)
* [Holybro PM06 (Micro Power Module)](power_module/holybro_pm06_pixhawk4mini_power_module.md)
- * [Pomegranate Systems Power Module](power_module/pomegranate_systems_pm.md)
+ * [Pomegranate Systems Power Module](uavcan/pomegranate_systems_pm.md)
* [Distance Sensors \(Rangefinders\)](sensor/rangefinders.md)
* [Lightware SFxx Lidar](sensor/sfxx_lidar.md)
* [Ainstein US-D1 Standard Radar Altimeter](sensor/ulanding_radar.md)
@@ -241,7 +242,7 @@
* [Lidar-Lite](sensor/lidar_lite.md)
* [TeraRanger](sensor/teraranger.md)
* [Lanbao PSK-CM8JL65-CC5](sensor/cm8jl65_ir_distance_sensor.md)
- * [Avionics Anonymous Laser Altimeter UAVCAN Interface](sensor/avanon_laser_interface.md)
+ * [Avionics Anonymous Laser Altimeter UAVCAN Interface](uavcan/avanon_laser_interface.md)
* [Tachometers (Revolution Counters)](sensor/tachometers.md)
* [ThunderFly TFRPM01 Tachometer Sensor](sensor/thunderfly_tachometer.md)
* [Airspeed Sensors](sensor/airspeed.md)
@@ -250,13 +251,15 @@
* [PMW3901](sensor/pmw3901.md)
* [ESCs & Motors](peripherals/esc_motors.md)
* [PWM ESCs and Servos](peripherals/pwm_escs_and_servo.md)
+ * [UAVCAN ESCs](uavcan/escs.md)
* [DShot ESCs](peripherals/dshot.md)
- * [UAVCAN ESCs](peripherals/uavcan_escs.md)
* [Camera](peripherals/camera.md)
* [Parachute](peripherals/parachute.md)
* [ADSB/FLARM (Traffic Avoidance)](peripherals/adsb_flarm.md)
* [Smart Batteries](smart_batteries/README.md)
* [Rotoye Batmon Battery Smartification Kit](smart_batteries/rotoye_batmon.md)
+ * [UAVCAN Peripherals](uavcan/README.md)
+ * [UAVCAN Configuration](uavcan/node_enumeration.md)
* [Companion Computer Peripherals](peripherals/companion_computer_peripherals.md)
* [Development](development/development.md)
* [Getting Started](dev_setup/getting_started.md)
@@ -310,11 +313,9 @@
* [SiK Radio](data_links/sik_radio.md)
* [Sensor and Actuator I/O](sensor_bus/README.md)
* [I2C Bus](sensor_bus/i2c.md)
- * [UAVCAN Bus](uavcan/README.md)
+ * [UAVCAN Bus](uavcan/developer.md)
* [UAVCAN Bootloader](uavcan/bootloader_installation.md)
* [UAVCAN Firmware Upgrades](uavcan/node_firmware.md)
- * [UAVCAN Configuration](uavcan/node_enumeration.md)
- * [UAVCAN Various Notes](uavcan/notes.md)
* [UART/Serial Ports](uart/README.md)
* [Port-Configurable Serial Drivers](uart/user_configurable_serial_driver.md)
* [RTK GPS (Integration)](advanced/rtk_gps.md)
diff --git a/de/flight_modes/mission.md b/de/flight_modes/mission.md
index 598f779dac58..a2490976b413 100644
--- a/de/flight_modes/mission.md
+++ b/de/flight_modes/mission.md
@@ -48,7 +48,7 @@ To automatically disarm the vehicle after it lands, in *QGroundControl* go to [V
Missions can be paused by activating [HOLD mode](../flight_modes/hold.md). The mission will then continue from the current mission command when you reactivate the MISSION flight mode. While flying in mission mode, if you decide to discontinue the mission and switch to any other mode e.g. position mode, fly the vehicle elsewhere with RC, and then switch back to mission mode, the vehicle will continue the mission from its current position and will fly to the next mission waypoint not visited yet.
:::warning
-Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash).We recommend you centre the control sticks before switching to any other mode.
+Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.
:::
For more information about mission planning, see:
@@ -77,7 +77,7 @@ Mission behaviour is affected by a number of parameters, most of which are docum
## Supported Mission Commands
-PX4 "accepts" the following MAVLink mission commands in Mission mode (note: caveats below list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
+PX4 "accepts" the following MAVLink mission commands in Mission mode (with some *caveats*, given after the list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
* [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT)
* *Param3* (flythrough) is ignored. Flythrough is always enabled if *param 1* (time_inside) > 0.
@@ -86,9 +86,6 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
* [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF)
* [MAV_CMD_NAV_LOITER_TO_ALT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TO_ALT)
-* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
-* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
-* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
* [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF)
* `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
@@ -104,6 +101,9 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -122,30 +122,36 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
-* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
-* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+* [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+* [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+* [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+* [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+* [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+* [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
Note:
* PX4 parses the above messages, but they are not necessary *acted* on. For example, some messages are vehicle-type specific.
-* PX4 generally does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) ).
+* PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* Not all messages/commands are exposed via *QGroundControl*.
-* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) (list generated in [this git changelist](https://github.com/PX4/PX4-Autopilot/commit/ca1f7a4a194c23303c23ca79b5905ff8bfb94c22)).
+* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-Please add an bug fix or PR if you find a missing/incorrect message.
+Please add an issue report or PR if you find a missing/incorrect message.
:::
## Inter-Waypoint Trajectory
PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).
-MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning.
+MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+![acc-rad](../../assets/flying/acceptance_radius_mission.png)
-Vehicles switch to the next waypoint as soon as they enter the acceptance radius.
+Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
-* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)
-* For FW the radius is defined by the "L1 distance".
+* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+* For FW the acceptance radius is defined by the "L1 distance".
* The L1 distance is computed from two parameters: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) and [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD), and the current ground speed.
* By default, it's about 70 meters.
* The equation is: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/de/flying/missions.md b/de/flying/missions.md
index 571135d77511..638bd7caa9b4 100644
--- a/de/flying/missions.md
+++ b/de/flying/missions.md
@@ -26,6 +26,22 @@ If **Heading** has not been explicitly set for the target waypoint (`param4=NaN`
Vehicle types that cannot independently control yaw and direction of travel will ignore yaw settings (e.g. Fixed Wing).
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## Flying Missions
Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
diff --git a/de/getting_started/README.md b/de/getting_started/README.md
index 158f802b676f..5374358474ed 100644
--- a/de/getting_started/README.md
+++ b/de/getting_started/README.md
@@ -14,4 +14,6 @@ This section provides an overview of the basic concepts you need to understand i
[Flight Modes](../getting_started/flight_modes.md) — Control modes for manual, assisted and autonomous movement.
+[Payloads & Cameras](../payloads/README.md)
+
[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/de/payloads/README.md b/de/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/de/payloads/README.md
+++ b/de/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/de/peripherals/uavcan_escs.md b/de/peripherals/uavcan_escs.md
index 37da24c9f172..8e8787388307 100644
--- a/de/peripherals/uavcan_escs.md
+++ b/de/peripherals/uavcan_escs.md
@@ -1,174 +1 @@
-# UAVCAN ESCs (Motor Controllers)
-
-PX4 supports the [UAVCAN](https://uavcan.org/) bus for connecting peripherals, including ESCs, GPS modules, various types of sensors, etc. However PX4 currently does not support UAVCAN Servos.
-
-UAVCAN ESCs have a number of advantages over [PWM ESCs](../peripherals/pwm_escs_and_servo.md):
-
-- UAVCAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
-- The bus is bi-directional, enabling health monitoring and diagnostics.
-- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other UAVCAN peripherals.
-- Setup is easier as you configure ESC numbering by manually spinning each motor (for most types of UAVCAN ESCs).
-
-## PX4 Supported ESC
-
-PX4 is compatible with any/all UAVCAN ESCs (UAVCAN is generally speaking a plug'n'play protocol).
-
-:::note
-At time of writing PX4 supports UAVCAN v0 (not v1.0).
-:::
-
-The only difference between UAVCAN ESCs from a setup perspective is that the physical connectors and the software tools used to configure the motor order and direction may be different.
-
-Some popular UAVCAN ESC firmware/products include:
-
-- [Sapog](#sapog) firmware; an advanced open source sensorless PMSM/BLDC motor controller firmware designed for use in propulsion systems of electric unmanned vehicles.
- - [Zubax Orel 20](https://zubax.com/products/orel_20)
- - [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
-- [Mitochondrik](https://zubax.com/products/mitochondrik) - integrated sensorless PMSM/BLDC motor controller chip (used in ESCs and integrated drives)
- - [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
-- [Myxa](https://zubax.com/products/myxa) - High-end PMSM/BLDC motor controller (FOC ESC) for light unmanned aircraft and watercraft.
-- [VESC Project ESCs](https://vesc-project.com/) (see also [Benjamin Vedder's blog](http://vedder.se) - project owner)
-- [OlliW’s UC4H ESC-Actuator Node](http://www.olliw.eu/2017/uavcan-for-hobbyists/#chapterescactuator)
-- A number of others are [listed here](https://forum.uavcan.org/t/uavcan-esc-options/452/3?u=pavel.kirienko)
-
-:::note
-This list is *not exhaustive/complete*. If you know of another ESC, please add it to the list!
-:::
-
-## Purchase
-
-Sapog-based ESCs:
-
-- [Zubax Orel 20](https://zubax.com/products/orel_20)
-
- ![Orel20 - Top](../../assets/peripherals/esc_uavcan_zubax_orel20/orel20_top.jpg)
-
-- [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
-
- ![Kotleta20 - Top](../../assets/peripherals/esc_uavcan_holybro_kotleta20/kotleta20_top.jpg) ![Kotleta20 - Bottom](../../assets/peripherals/esc_uavcan_holybro_kotleta20/kotleta20_bottom.jpg)
-
-Mitochondrik based drives and ESC:
-
-- [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
-
- ![Sadulli - Top](../../assets/peripherals/esc_usavcan_zubax_sadulli/sadulli_top.jpg)
-
-:::note
-There are many other commercially available ESCs; please add new links as you find them!
-:::
-
-
-
-## Wiring/Connections
-
-Connect all of the on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes. The order in which the ESCs are connected/chained does not matter.
-
-:::note
-All UAVCAN ESCs share the same connection architecture/are wired the same way. Note however that the actual connectors differ (e.g. *Zubax Orel 20* and *Holybro Kotleta20* use Dronecode standard connectors (JST-GH 4 Pin) - while VESCs do not).
-:::
-
-For more information about proper bus connections see [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB).
-
-## PX4 Configuration
-
-In order to use a UAVCAN ESC with PX4 you will need to enable the UAVCAN driver:
-
-1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller!) and connect *QGroundControl*.
-2. Navigate to the **Vehicle Setup > Parameters** screen > [Parameters](../advanced_config/parameters.md) explains how to find and set parameters.
-3. Set [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to the value *Sensors and Motors* (3) and then reboot the flight controller.
-
-If applicable (some systems will not benefit from this behavior, e.g. glider drones):
-
-1. Set [UAVCAN_ESC_IDLT](../advanced_config/parameter_reference.md#UAVCAN_ESC_IDLT) to 1 in order to ensure that the motors are always running at least at the idle throttle while the system is armed.
-
-## ESC Setup
-
-While UAVCAN devices are generally *plug'n'play* you will still need to enumerate (number) each of the ESC used in your system and set their direction so that they can be identified/controlled by PX4.
-
-:::note
-The ESC index and direction must match/map to the [Airframe Reference](../airframes/airframe_reference.md) for the vehicle type. ESC indexes from 0-7 map to MAIN 1-8, while ESC indexes 8-15 map to AUX 1-8.
-:::
-
-The mechanism for enumerating each type of UAVCAN ESC is different (look up the instructions in your ESC's manual). Setup information for some UAVCAN ESCs is provided below.
-
-
-
-### Sapog ESC setup
-
-The following sections explain how to enumerate [Sapog-based](https://github.com/PX4/sapog#px4-sapog)-based ESCs with PX4. The instructions should work for any Sapog-based ESC design.
-
-
-
-#### ESC Enumeration using QGroundControl
-
-:::tip
-You can skip this section if there is only one ESC in your setup, because the ESC index is already set to zero by default.
-:::
-
-To enumerate the ESC:
-
-1. Power the vehicle with a battery and connect to *QGroundControl*
-2. Navigate to **Vehicle Setup > Power** in QGC.
-3. Start the process of ESC auto-enumeration by pressing the **Start Assignment** button, as shown on the screenshot below.
-
- ![QGC - UAVCAN ESC auto-enumeration](../../assets/peripherals/esc_qgc/qgc_uavcan_settings.jpg)
-
- You will hear a sound indicating that the flight controller has entered the ESC enumeration mode.
-
-4. Manually turn each motor in the correct direction of its rotation, starting from the first motor and finishing with the last motor. Each time you turn a motor, you should hear a confirmation.
-
-:::note
-Make sure to turn each of the motors in the correct direction, because the ESC will automatically learn and remember the direction (i.e. motors that spin clockwise during normal operation must also be turned clockwise during enumeration).
-:::
-
-5. After the last motor is enumerated, the confirmation sound should change to indicate that the enumeration procedure is complete.
-
-The following video demonstrates the process:
-
-@[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ) @[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ)
-
-#### Manual ESC Enumeration using Sapog
-
-:::tip
-We recommend automated [ESC Enumeration using QGroundControl](#sapog_esc_qgc) rather than manual enumeration - it is easier and safer.
-:::
-
-You can manually configure the ESC index and direction using the [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/). This assigns the following Sapog configuration parameters for each enumerated ESC:
-
-- `esc_index`
-- `ctl_dir`
-
-:::note
-See [Sapog reference manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf) for more information about the parameters.
-:::
-
-### Myxa ESC Setup
-
-Motor enumeration for Myxa [Telega-based ESCs](https://zubax.com/products/telega) is usually performed using the [Kucher tool](https://files.zubax.com/products/com.zubax.kucher/) (or less "GUI-friendly" [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/)).
-
-There is some guidance here: [Quick start guide for Myxa v0.1](https://forum.zubax.com/t/quick-start-guide-for-myxa-v0-1/911) (Zubax blog).
-
-### VESC ESC Setup
-
-For [VESC ESCs](https://vesc-project.com/) the preferred tool for motor enumeration is the [VESC tool](https://vesc-project.com/vesc_tool). In addition to the normal motor configuration that you will have to setup in the VESC tool, you will also need to properly setup the app configuration. The recommended app setup is as follows:
-
-| Parameter | Option |
-| ----------------------- | ---------------------- |
-| App to use | `No App` |
-| VESC ID | `1,2,...` |
-| Can Status Message Mode | `CAN_STATUS_1_2_3_4_5` |
-| CAN Baud Rate | `CAN_BAUD_500K` |
-| CAN Mode | `UAVCAN` |
-| UAVCAN ESC Index | `0,1,...` |
-
-
-VESC ID should have the same motor numbering as in PX4 convention, starting at `1` for top-right motor, `2` for bottom-left motor etc. However the `UAVCAN ESC Index` starts from `0`, and as such it is always one index lower than the `VESC ID`. For example, in a quadcopter the bottom left motor will have `VESC ID = 2` and `UAVCAN ESC Index = 1`.
-
-Finally the `CAN Baud Rate` must match the value set in [UAVCAN_BITRATE](../advanced_config/parameter_reference.md#UAVCAN_BITRATE).
-
-## Further Information
-
-- [PX4/Sapog](https://github.com/PX4/sapog#px4-sapog) (Github)
-- [Sapog v2 Reference Manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf)
-- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
-- [Using Sapog based ESC with PX4](https://kb.zubax.com/display/MAINKB/Using+Sapog-based+ESC+with+PX4) (Zubax KB)
\ No newline at end of file
+
\ No newline at end of file
diff --git a/de/power_module/README.md b/de/power_module/README.md
index 53081ff61a81..b968e6eee153 100644
--- a/de/power_module/README.md
+++ b/de/power_module/README.md
@@ -14,6 +14,6 @@ This section provides links/information about supported power modules and power
* [CUAV HV PM](../power_module/cuav_hv_pm.md)
* [Holybro PM07 (Pixhawk 4 PM)](../power_module/holybro_pm07_pixhawk4_power_module.md)
* [Holybro PM06 (Pixhawk 4 Mini PM)](../power_module/holybro_pm06_pixhawk4mini_power_module.md)
-* [UAVCAN](https://new.uavcan.org/) power modules
- * [CUAV CAN PMU](../power_module/cuav_can_pmu.md)
- * [Pomegranate Systems Power Module](../power_module/pomegranate_systems_pm.md)
\ No newline at end of file
+* [UAVCAN](../uavcan/README.md) power modules
+ * [CUAV CAN PMU](../uavcan/cuav_can_pmu.md)
+ * [Pomegranate Systems Power Module](../uavcan/pomegranate_systems_pm.md)
\ No newline at end of file
diff --git a/de/power_module/cuav_can_pmu.md b/de/power_module/cuav_can_pmu.md
index ed1fb2336010..0ad669867be1 100644
--- a/de/power_module/cuav_can_pmu.md
+++ b/de/power_module/cuav_can_pmu.md
@@ -1,69 +1 @@
-# CAUV CAN PMU
-
-CAN PMU® is a high-precision power module developed by CUAV®. It uses the [UAVCAN](https://new.uavcan.org/) protocol and runs the CUAV ITT compensation algorithm, which enables drones to get the battery data more accurately.
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu.jpg)
-
-It is recommended for use in large commercial vehicles, but might also be used for research vehicles.
-
-## Specifications
-
-- **Processor:** STM32F412
-- **Voltage input**: 6~62V\(2-15S\)
-- **Max current:** 110A
-- **Voltage accuracy:** ±0.05V
-- **Current accuracy:** ±0.1A
-- **Resolution:** 0.01A/V
-- **Max output power:** 6000W/90S
-- **Max stable power:** 5000W
-- **Power port output:** 5.4V/5A
-- **Protocol:** UAVCAN
-- **Operating temp:** -20~+100
-- **Firmware upgrade:** Supported.
-* **Calibration:** Not needed.
-* **Interface Type:**
- - **IN/OUT:** XT90\(Cable)/Amass 8.0\(Module)
- - **Power port:** 5025850670
- - **CAN:** GHR-04V-S
-- **Appearance:**
- - **Size:** 46.5mm \* 38.5mm \* 22.5mm
- - **Weight:** 76g
-
-## Purchase
-
-- [CUAV store](https://store.cuav.net/index.php)
-- [CUAV aliexpress ](https://www.aliexpress.com/item/4000369700535.html)
-
-## Pinouts
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en.png)
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en2.png)
-
-## Connection
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_connection_en.png)
-
-The connection steps are:
-* Connect the flight control CAN1/2 and the module CAN interface.
-* Connect the V5 series power cable to the V5 Flight Control Power2 (if other flight controllers are connect to the Power interface) and the module Power interface.
-
-## Enable CAN PMU
-
-Set the following parameters in the *QGroundControl* [parameter list](../advanced_config/parameters.md) and then restart:
-
-* `UAVCAN_ENABLE`: set to: *Sensors Automatic Config*
-
- ![qgc set](../../assets/hardware/power_module/cuav_can/qgc_set_en.png)
-
-# Package Contents
-
-![CAN PMU list](../../assets/hardware/power_module/cuav_can/can_pmu_list.png)
-
-## Further Information
-
-[CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf)
-
-[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs)
-
-[UAVCAN](https://new.uavcan.org/)
\ No newline at end of file
+
diff --git a/de/power_module/pomegranate_systems_pm.md b/de/power_module/pomegranate_systems_pm.md
index fb28d03e56ab..ea1549c370ba 100644
--- a/de/power_module/pomegranate_systems_pm.md
+++ b/de/power_module/pomegranate_systems_pm.md
@@ -1,55 +1 @@
-# Pomegranate Systems Power Module
-
-![Module Image](../../assets/hardware/power_module/pomegranate_systems_pm/main_image.jpg)
-
-Digital Power Module with high resolution current integration, 5V/2A supply with power monitoring, single UAVCAN v0 CANbus interface, and an RGB status LED.
-
-Detailed setup, configuration, and troubleshooting information can be found on the [manufacturer's device home page](https://p-systems.io/product/power_module).
-
-## Specifications
-
- - **Input Voltage:** 6-26V \(2-6S\)
- - **Max Continuous Current:**
- - **Benchtop:** 40A
- - **Forced Cooling:** 100A
- - **Max 5V Output Current:** 2A
- - **Voltage Resolution:** 0.04 ΔV
- - **Current Resolution:**
- - **Primary / Battery Bus:** 0.02 ΔA
- - **5V bus:** 0.001 ΔA
- - **CANbus Termination:** Electronic (on by default)
- - **MCU:** STM32 F302K8U
- - **Firmware:** [Open Source](https://bitbucket.org/p-systems/firmware/)
- - **Electrical Interface:**
- - **Power:** Solder pads or XT60PW (right angle, board-mounted connectors)
- - **CANbus** Dual JST GH-4 (standard UAVCAN micro-connector)
- - **I2C / Serial:** JST GH-5
- - **5V Output:** Solder pads or CANbus / I2C connectors
- - **Device Mass:**
- - **Without Connectors:** 9g
- - **With XT60PW Connectors:** 16g
-
-
- ![Dimensions](../../assets/hardware/power_module/pomegranate_systems_pm/mechanical.png)
-
-## Configuration
-
- 1. Enable UAVCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`.
- 2. Set the following module parameters using the [Mavlink console](https://docs.qgroundcontrol.com/en/analyze_view/mavlink_console.html):
- * Battery capacity in mAh: `battery_capacity_mAh`
- * Battery voltage when *full*: `battery_full_V`,
- * Battery voltage when *empty*: `battery_empty_V`
- * Turn on current integration: `enable_current_track`
- * (optional) Turn Off CANbus termination resistor :`enable_can_term`
-
-**Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands:
-
-```
-uavcan param set 125 battery_capacity_mAh 5000
-uavcan param set 125 battery_full_V 12.5
-uavcan param set 125 battery_empty_V 11.2
-uavcan param set 125 enable_current_track 1
-uavcan param save 125
-```
-
-See [device configuration page](https://p-systems.io/product/power_module/configuration) for a full list of parameters.
+
diff --git a/de/releases/1.12.md b/de/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/de/releases/1.12.md
+++ b/de/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/de/ros/ros2_offboard_control.md b/de/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/de/ros/ros2_offboard_control.md
+++ b/de/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).
diff --git a/de/sensor/avanon_laser_interface.md b/de/sensor/avanon_laser_interface.md
index 863ab645051b..f418f98c96ac 100644
--- a/de/sensor/avanon_laser_interface.md
+++ b/de/sensor/avanon_laser_interface.md
@@ -1,57 +1 @@
-# Avionics Anonymous Laser Altimeter UAVCAN Interface
-
-The [Avionics Anonymous Laser Altimeter Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/) allows a [number of common rangefinders](#supported_rangefinders) to be connected via the UAVCAN bus (this is a more robust interface than I2C).
-
-![Avionics Anonymous Laser Altimeter UAVCAN Interface](../../assets/hardware/sensors/avionics_anon_uavcan_alt_interface/avionics_anon_altimeter_uavcan_interface.jpg)
-
-## Where to Buy
-
-* [AvAnon Laser Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/)
-
-
-## Supported Rangefinders
-
-A full list supported rangefinders can be found on the link above.
-
-At time of writing the following rangefinders are supported:
-
-- Lightware SF30/D
-- Lightware SF10/a
-- Lightware SF10/b
-- Lightware SF10/c
-- Lightware SF11/c
-- Lightware SF/LW20/b
-- Lightware SF/LW20/c
-
-
-## Pinouts
-
-### CAN Connector
-| Pin | Name | Description |
-| --- | -------- | ----------------------------------------------------------------------------------- |
-| 1 | POWER_IN | Power Supply. 4.0-5.5V supported, but must also be compatible with connected laser. |
-| 2 | TX/SCL | TX for serial mode, Clock for I2C mode |
-| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
-| 4 | GND | Signal/power ground. |
-
-### Laser Connector
-
-| Pin | Name | Description |
-| --- | --------- | -------------------------------------- |
-| 1 | POWER_OUT | Filtered power at the supply voltage. |
-| 2 | CAN+ | TX for serial mode, Clock for I2C mode |
-| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
-| 4 | GND | Signal/power ground. |
-
-
-## Wiring
-
-The rangefinder (laser) is connected to the AvAnon interface board, which is connected to one of the CAN ports on your autopilot. The wiring is as per the pinout above, or the necessary cables can be purchased to connect to your system right out of the box. These are available at the links [here](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/).
-
-The interface board provides a filtered power output for the laser, but does not provide its own regulation. Therefore the laser must be compatible with whatever voltage is supplied to the board.
-
-## Software Configuration
-
-UAVCAN must be enabled by setting [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) non zero.
-
-The minimum and maximum valid range for the laser must be set in the parameters [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) and [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX).
+
diff --git a/de/sensor/rangefinders.md b/de/sensor/rangefinders.md
index 3789dae1870e..a1c9d5a11ac5 100644
--- a/de/sensor/rangefinders.md
+++ b/de/sensor/rangefinders.md
@@ -48,7 +48,7 @@ The [Lanbao PSK-CM8JL65-CC5 ToF Infrared Distance Measuring Sensor](../sensor/cm
### Avionics Anonymous UAVCAN Laser Altimeter Interface
-The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../sensor/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the UAVCAN bus, a more robust interface than I2C.
+The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../uavcan/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the [UAVCAN](../uavcan/README.md) bus, a more robust interface than I2C.
diff --git a/de/simulation/airsim.md b/de/simulation/airsim.md
index 2d3854f8392b..401b169bc8b3 100644
--- a/de/simulation/airsim.md
+++ b/de/simulation/airsim.md
@@ -2,9 +2,9 @@
AirSim is a open-source, cross platform simulator for drones, built on Unreal Engine. It provides physically and visually realistic simulations of Pixhawk/PX4 using either Hardware-In-The-Loop \(HITL\) or Software-In-The-Loop \(SITL\).
-The main entry point for the documentation is the [Github AirSim README](https://github.com/Microsoft/AirSim/blob/master/README.md).
+The main entry point for the documentation is the [AirSim Documentation](https://microsoft.github.io/AirSim/).
-The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://github.com/Microsoft/AirSim/blob/master/docs/px4_setup.md) (covering both HITL and SITL).
+The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://microsoft.github.io/AirSim/px4_setup/) (covering both HITL and SITL).
## Further Information
diff --git a/de/uavcan/README.md b/de/uavcan/README.md
index f7705f999823..b492dc80d6a7 100644
--- a/de/uavcan/README.md
+++ b/de/uavcan/README.md
@@ -1,53 +1,82 @@
-# UAVCAN Introduction
+# UAVCAN
-![UAVCAN Logo](../../assets/uavcan/uavcan_logo_transparent.png)
+ [UAVCAN](http://uavcan.org) is an onboard network which allows the autopilot to connect to avionics/peripherals. It uses rugged, differential signalling, and supports firmware upgrades over the bus and status feedback from peripherals.
-[UAVCAN](http://uavcan.org) is an onboard network which allows the autopilot to connect to avionics. It supports hardware like:
-
-* Motor controllers
- * [Zubax Orel 20](https://zubax.com/product/zubax-orel-20) :::note Runs [Sapog Firmware](https://github.com/px4/sapog) (open source). Based on [Sapog Reference Hardware](https://github.com/PX4/Hardware/tree/master/sapog_reference_hardware).
+:::note PX4 requires an SD card for UAVCAN node allocation and firmware upgrade. It is not used during flight by UAVCAN.
:::
+
+## Supported Hardware
+
+It supports hardware like:
+
+* [ESC/Motor controllers](../uavcan/escs.html)
* Airspeed sensors
* [Thiemar airspeed sensor](https://github.com/thiemar/airspeed)
* GNSS receivers for GPS and GLONASS
* [Zubax GNSS](https://zubax.com/products/gnss_2)
* Power monitors
- * [Pomegranate Systems Power Module](../power_module/pomegranate_systems_pm.md)
- * [CUAV CAN PMU Power Module](../power_module/cuav_can_pmu.md)
+ * [Pomegranate Systems Power Module](../uavcan/pomegranate_systems_pm.md)
+ * [CUAV CAN PMU Power Module](../uavcan/cuav_can_pmu.md)
+* Distance sensors
+ - [Avionics Anonymous Laser Altimeter UAVCAN Interface](../uavcan/avanon_laser_interface.md)
-In contrast to hobby-grade devices it uses rugged, differential signalling and supports firmware upgrades over the bus. All motor controllers provide status feedback and implement field-oriented-control \(FOC\).
-
-:::note PX4 requires an SD card for UAVCAN node allocation and firmware upgrade. It is not used during flight by UAVCAN.
+:::note PX4 does not support UAVCAN servos (at time of writing).
:::
-## Initial Setup
-The following instructions provide a step-by-step guide to connect and setup a quadcopter with ESCs and GPS connected via UAVCAN. The hardware of choice is a Pixhawk 2.1, Zubax Orel 20 ESCs and a Zubax GNSS GPS module.
+## Wiring
-### Wiring
+All UAVCAN components share the same connection architecture/are wired the same way. Connect all on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes (the order in which the nodes are connected/chained does not matter).
-The first step is to connect all UAVCAN enabled devices with the flight controller. The following diagram displays how to wire all components. The used Zubax devices all support a redundant CAN interface in which the second bus is optional but increases the robustness of the connection.
+The following diagram shows this for a flight controller connected to [UAVCAN motor controllers (ESCs)](../uavcan/escs.html) and a UAVCAN GNSS.
![UAVCAN Wiring](../../assets/uavcan/uavcan_wiring.png)
-It is important to mention that some devices require an external power supply \(e.g. Zubax Orel 20\) and others can be powered by the CAN connection \(e.g Zubax GNSS\) itself. Please refer to the documentation of your hardware before continuing with the setup.
+The diagram does not show any power wiring. Refer to your manufacturer instructions to confirm whether components require separate power or can be powered from the CAN bus itself.
+
+For more information about proper bus connections see [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB).
+
+:::note
+- While the connections are the same, the _connectors_ may differ across devices.
+- An second/redundant" CAN interface may be used, as shown above (CAN2). This is optional, but can increase the robustness of the connection.
+:::
+
+
+## PX4 Configuration
+
+In order to use UAVCAN components with PX4 you will first need to enable the UAVCAN driver:
+
+1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller) and connect *QGroundControl*.
+1. Navigate to the **Vehicle Setup > Parameters** screen.
+1. [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) must be [set](../advanced_config/parameters.md) to one of the non-zero values.
+
+ The values are:
+ - `0`: UAVCAN driver disabled.
+ - `1`: Sensors Manual Config.
+ - `2`: Sensors Automatic Config.
+ - `3`: Sensors and Actuators (ESCs) Automatic Config
+
+ Use `1` if _none_ of the connected UAVCAN devices support automatic configuration (check the manual!), `2` or `3` if _some_ of them support automatic configuration, and `3` if you're using UAVCAN ESCs (this assigns motor controls to the UAVCAN bus rather than PWM).
+
+:::note
+You will need to manually allocate static ids for any nodes that don't support automatic configuration. When using dynamic configuration, any manually allocated ids should be given a value greater than the number of UAVCAN devices (to avoid clashes).
+:::
+
+Most UAVCAN sensors require no further setup (they are plug'n'play, unless specifically noted in their documentation).
-### Firmware Setup
+[UAVCAN motor controllers (ESCs)](../uavcan/escs.md) additionally require the motor order be set, and may require a few other parameters be set. Whether this can be done using the simple QGroundControl setup UI depends on the type of ESC (see link for information).
-Next, follow the instructions in [UAVCAN Configuration](../uavcan/node_enumeration.md) to activate the UAVCAN functionalities in the firmware. Disconnect your power supply and reconnect it. After the power cycle all UAVCAN devices should be detected which is confirmed by a beeping motor on the Orel 20 ESCs. You can now continue with the general setup and calibration.
-Depending on the used hardware, it can be reasonable to perform an update of the firmware on the UAVCAN devices. This can be done via the UAVCAN itself and the PX4 firmware. For more details please refer to the instructions in [UAVCAN Firmware](../uavcan/node_firmware.md).
+## Troubleshooting
-## Upgrading Node Firmware
+### UAVCAN devices dont get node ID/Firmware Update Fails
-The PX4 middleware will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied. The process and requirements are described on the [UAVCAN Firmware](../uavcan/node_firmware.md) page.
+PX4 requires an SD card for UAVCAN node allocation and during firmware update (which happen during boot). Check that there is a (working) SD card present and reboot.
-## Enumerating and Configuring Motor Controllers
+### Motors not spinning when armed
-The ID and rotational direction of each motor controller can be assigned after installation in a simple setup routine: [UAVCAN Node Enumeration](../uavcan/node_enumeration.md). The routine can be started by the user through QGroundControl.
+If the PX4 Firmware arms but the motors do not start to rotate, check that parameter `UAVCAN_ENABLE=3` to use UAVCAN ESCs. If the motors do not start spinning before thrust is increased, check `UAVCAN_ESC_IDLT=1`.
-## Useful links
+## Developer Information
-* [Homepage](http://uavcan.org)
-* [Specification](https://uavcan.org/specification/)
-* [Implementations and tutorials](http://uavcan.org/Implementations)
+- [UAVCAN Development](../uavcan/developer.md): Topics related to development and integration of new UAVCAN hardware into PX4.
diff --git a/de/uavcan/avanon_laser_interface.md b/de/uavcan/avanon_laser_interface.md
new file mode 100644
index 000000000000..863ab645051b
--- /dev/null
+++ b/de/uavcan/avanon_laser_interface.md
@@ -0,0 +1,57 @@
+# Avionics Anonymous Laser Altimeter UAVCAN Interface
+
+The [Avionics Anonymous Laser Altimeter Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/) allows a [number of common rangefinders](#supported_rangefinders) to be connected via the UAVCAN bus (this is a more robust interface than I2C).
+
+![Avionics Anonymous Laser Altimeter UAVCAN Interface](../../assets/hardware/sensors/avionics_anon_uavcan_alt_interface/avionics_anon_altimeter_uavcan_interface.jpg)
+
+## Where to Buy
+
+* [AvAnon Laser Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/)
+
+
+## Supported Rangefinders
+
+A full list supported rangefinders can be found on the link above.
+
+At time of writing the following rangefinders are supported:
+
+- Lightware SF30/D
+- Lightware SF10/a
+- Lightware SF10/b
+- Lightware SF10/c
+- Lightware SF11/c
+- Lightware SF/LW20/b
+- Lightware SF/LW20/c
+
+
+## Pinouts
+
+### CAN Connector
+| Pin | Name | Description |
+| --- | -------- | ----------------------------------------------------------------------------------- |
+| 1 | POWER_IN | Power Supply. 4.0-5.5V supported, but must also be compatible with connected laser. |
+| 2 | TX/SCL | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+### Laser Connector
+
+| Pin | Name | Description |
+| --- | --------- | -------------------------------------- |
+| 1 | POWER_OUT | Filtered power at the supply voltage. |
+| 2 | CAN+ | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+
+## Wiring
+
+The rangefinder (laser) is connected to the AvAnon interface board, which is connected to one of the CAN ports on your autopilot. The wiring is as per the pinout above, or the necessary cables can be purchased to connect to your system right out of the box. These are available at the links [here](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/).
+
+The interface board provides a filtered power output for the laser, but does not provide its own regulation. Therefore the laser must be compatible with whatever voltage is supplied to the board.
+
+## Software Configuration
+
+UAVCAN must be enabled by setting [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) non zero.
+
+The minimum and maximum valid range for the laser must be set in the parameters [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) and [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX).
diff --git a/de/uavcan/cuav_can_pmu.md b/de/uavcan/cuav_can_pmu.md
new file mode 100644
index 000000000000..9b0ff94be464
--- /dev/null
+++ b/de/uavcan/cuav_can_pmu.md
@@ -0,0 +1,69 @@
+# CAUV CAN PMU
+
+CAN PMU® is a high-precision [UAVCAN](../uavcan/README.md) power module developed by CUAV®. It runs the CUAV ITT compensation algorithm, which enables drones to get the battery data more accurately.
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu.jpg)
+
+It is recommended for use in large commercial vehicles, but might also be used for research vehicles.
+
+## Specifications
+
+- **Processor:** STM32F412
+- **Voltage input**: 6~62V\(2-15S\)
+- **Max current:** 110A
+- **Voltage accuracy:** ±0.05V
+- **Current accuracy:** ±0.1A
+- **Resolution:** 0.01A/V
+- **Max output power:** 6000W/90S
+- **Max stable power:** 5000W
+- **Power port output:** 5.4V/5A
+- **Protocol:** UAVCAN
+- **Operating temp:** -20~+100
+- **Firmware upgrade:** Supported.
+* **Calibration:** Not needed.
+* **Interface Type:**
+ - **IN/OUT:** XT90\(Cable)/Amass 8.0\(Module)
+ - **Power port:** 5025850670
+ - **CAN:** GHR-04V-S
+- **Appearance:**
+ - **Size:** 46.5mm \* 38.5mm \* 22.5mm
+ - **Weight:** 76g
+
+## Purchase
+
+- [CUAV store](https://store.cuav.net/index.php)
+- [CUAV aliexpress ](https://www.aliexpress.com/item/4000369700535.html)
+
+## Pinouts
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en.png)
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en2.png)
+
+## Connection
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_connection_en.png)
+
+The connection steps are:
+* Connect the flight control CAN1/2 and the module CAN interface.
+* Connect the V5 series power cable to the V5 Flight Control Power2 (if other flight controllers are connect to the Power interface) and the module Power interface.
+
+## Enable CAN PMU
+
+Set the following parameters in the *QGroundControl* [parameter list](../advanced_config/parameters.md) and then restart:
+
+* `UAVCAN_ENABLE`: set to: *Sensors Automatic Config*
+
+ ![qgc set](../../assets/hardware/power_module/cuav_can/qgc_set_en.png)
+
+# Package Contents
+
+![CAN PMU list](../../assets/hardware/power_module/cuav_can/can_pmu_list.png)
+
+## Further Information
+
+[CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf)
+
+[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs)
+
+[UAVCAN](https://new.uavcan.org/)
\ No newline at end of file
diff --git a/de/uavcan/developer.md b/de/uavcan/developer.md
new file mode 100644
index 000000000000..010f77ae8766
--- /dev/null
+++ b/de/uavcan/developer.md
@@ -0,0 +1,28 @@
+# UAVCAN Development
+
+This topic/section has information that is relevant to developers who want to add support for new [UAVCAN](http://uavcan.org) hardware to the PX4 Autopilot.
+
+:::note
+[Hardware > UAVCAN Peripherals](../uavcan/README.md) contains information about using existing/supported UAVCAN components with PX4.
+:::
+
+## Upgrading Node Firmware
+
+The PX4 middleware will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied. The process and requirements are described on the [UAVCAN Firmware](../uavcan/node_firmware.md) page.
+
+### Debugging with Zubax Babel
+
+A great tool to debug the transmission on the UAVCAN bus is the [Zubax Babel](https://zubax.com/products/babel) in combination with the [GUI tool](http://uavcan.org/GUI_Tool/Overview/).
+
+They can also be used independently from Pixhawk hardware in order to test a node or manually control UAVCAN enabled ESCs.
+
+
+## Useful Links
+
+- [UAVCAN Bootloader](../uavcan/bootloader_installation.md)
+- [UAVCAN Firmware Upgrades](../uavcan/node_firmware.md)
+- [Home page](http://uavcan.org) (uavcan.org)
+- [Specification](https://uavcan.org/specification/) (uavcan.org)
+- [Implementations and tutorials](http://uavcan.org/Implementations) (uavcan.org)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+
diff --git a/de/uavcan/escs.md b/de/uavcan/escs.md
new file mode 100644
index 000000000000..fb495d595843
--- /dev/null
+++ b/de/uavcan/escs.md
@@ -0,0 +1,205 @@
+# UAVCAN ESCs (Motor Controllers)
+
+PX4 supports [UAVCAN](../uavcan/README.md) ESCs. These have a number of advantages over [PWM ESCs](../peripherals/pwm_escs_and_servo.md):
+- UAVCAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
+- The bus is bi-directional, enabling health monitoring and diagnostics.
+- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other UAVCAN peripherals.
+- Setup is easier as you configure ESC numbering by manually spinning each motor (for most types of UAVCAN ESCs).
+
+
+
+
+
+## PX4 Supported ESC
+
+PX4 is compatible with any/all UAVCAN ESCs (UAVCAN is generally speaking a plug'n'play protocol).
+
+:::note
+At time of writing PX4 supports UAVCAN v0 (not v1.0).
+:::
+
+The only difference between UAVCAN ESCs from a setup perspective is that the physical connectors and the software tools used to configure the motor order and direction may be different.
+
+
+Some popular UAVCAN ESC firmware/products include:
+- [Sapog](https://github.com/PX4/sapog#px4-sapog) firmware; an advanced open source sensorless PMSM/BLDC motor controller firmware designed for use in propulsion systems of electric unmanned vehicles.
+ - [Zubax Orel 20](https://zubax.com/products/orel_20)
+ - [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+- [Mitochondrik](https://zubax.com/products/mitochondrik) - integrated sensorless PMSM/BLDC motor controller chip (used in ESCs and integrated drives)
+ - [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+- [Myxa](https://zubax.com/products/myxa) - High-end PMSM/BLDC motor controller (FOC ESC) for light unmanned aircraft and watercraft.
+- [VESC Project ESCs](https://vesc-project.com/) (see also [Benjamin Vedder's blog](http://vedder.se) - project owner)
+- [OlliW’s UC4H ESC-Actuator Node](http://www.olliw.eu/2017/uavcan-for-hobbyists/#chapterescactuator)
+- A number of others are [listed here](https://forum.uavcan.org/t/uavcan-esc-options/452/3?u=pavel.kirienko)
+
+:::note
+This list is *not exhaustive/complete*. If you know of another ESC, please add it to the list!
+:::
+
+## Purchase
+
+Sapog-based ESCs:
+- [Zubax Orel 20](https://zubax.com/products/orel_20)
+- [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+
+Mitochondrik based drives and ESC:
+- [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+
+:::note
+There are many other commercially available ESCs; please add new links as you find them!
+:::
+
+
+
+
+
+## Wiring/Connections
+
+Connect all of the on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes. The order in which the ESCs are connected/chained does not matter.
+
+For more information see [UAVCAN > Wiring](../uavcan/README.md#wiring).
+
+:::note
+All UAVCAN ESCs share the same connection architecture/are wired the same way. Note however that the actual connectors differ (e.g. *Zubax Orel 20* and *Holybro Kotleta20* use Dronecode standard connectors (JST-GH 4 Pin) - while VESCs do not).
+:::
+
+
+## PX4 Configuration
+
+In order to use a UAVCAN ESC with PX4 you will need to enable the UAVCAN driver:
+1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller) and connect *QGroundControl*.
+1. Navigate to the **Vehicle Setup > Parameters** screen. :::note [Parameters](../advanced_config/parameters.md) explains how to find and set parameters.
+:::
+1. Set [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to the value *Sensors and Motors* (3) and then reboot the flight controller. This enables automatic enumeration of the motors (ESC) as described in the [next section](#esc-setup).
+1. (Optional) Set [UAVCAN_ESC_IDLT](../advanced_config/parameter_reference.md#UAVCAN_ESC_IDLT) to 1 in order to ensure that the motors are always running at least at the idle throttle while the system is armed. :::note Some systems will not benefit from this behavior, e.g. glider drones).
+:::
+
+
+## ESC Setup
+
+While UAVCAN devices are generally *plug'n'play* you will still need to enumerate (number) each of the ESC used in your system and set their direction so that they can be identified/controlled by PX4.
+
+:::note
+The ESC index and direction must match/map to the [Airframe Reference](../airframes/airframe_reference.md) for the vehicle type. ESC indexes from 0-7 map to MAIN 1-8, while ESC indexes 8-15 map to AUX 1-8.
+:::
+
+The mechanism for enumerating each type of UAVCAN ESC is different (look up the instructions in your ESC's manual). Setup information for some UAVCAN ESCs is provided below.
+
+
+### Sapog ESC Enumeration using QGroundControl
+
+This section shows how to enumerate any [Sapog-based](https://github.com/PX4/sapog#px4-sapog)-based ESCs "automatically" using *QGroundControl*.
+
+:::tip
+You can skip this section if there is only one ESC in your setup, because the ESC index is already set to zero by default.
+:::
+
+To enumerate the ESC:
+1. Power the vehicle with a battery and connect to *QGroundControl*
+1. Navigate to **Vehicle Setup > Power** in QGC.
+1. Start the process of ESC auto-enumeration by pressing the **Start Assignment** button, as shown on the screenshot below.
+
+ ![QGC - UAVCAN ESC auto-enumeration](../../assets/peripherals/esc_qgc/qgc_uavcan_settings.jpg)
+
+ You will hear a sound indicating that the flight controller has entered the ESC enumeration mode.
+1. Manually turn each motor in the correct direction of its rotation (as specified in the [Airframe Reference](../airframes/airframe_reference.md)), starting from the first motor and finishing with the last motor. Each time you turn a motor, you should hear a confirmation beep.
+
+:::note
+Make sure to turn each of the motors in the correct direction, as the ESC will automatically learn and remember the direction (i.e. motors that spin clockwise during normal operation must also be turned clockwise during enumeration).
+:::
+
+1. After the last motor is enumerated, the confirmation sound should change to indicate that the enumeration procedure is complete.
+1. Reboot PX4 and the Sapog ESCs to apply the new enumeration IDs.
+
+The following video demonstrates the process:
+
+@[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ)
+
+### Manual ESC Enumeration using Sapog
+
+:::tip
+We recommend automated [Sapog ESC Enumeration using QGroundControl](#sapog-esc-enumeration-using-qgroundcontrol) shown above rather than manual enumeration (as it is easier and safer).
+:::
+
+You can manually configure the ESC index and direction using the [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/). This assigns the following Sapog configuration parameters for each enumerated ESC:
+- `esc_index`
+- `ctl_dir`
+
+:::note
+See [Sapog reference manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf) for more information about the parameters.
+:::
+
+### Myxa ESC Setup
+
+Motor enumeration for Myxa [Telega-based ESCs](https://zubax.com/products/telega) is usually performed using the [Kucher tool](https://files.zubax.com/products/com.zubax.kucher/) (or less "GUI-friendly" [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/)).
+
+There is some guidance here: [Quick start guide for Myxa v0.1](https://forum.zubax.com/t/quick-start-guide-for-myxa-v0-1/911) (Zubax blog).
+
+
+### VESC ESC Setup
+
+For [VESC ESCs](https://vesc-project.com/) the preferred tool for motor enumeration is the [VESC tool](https://vesc-project.com/vesc_tool). In addition to the normal motor configuration that you will have to setup in the VESC tool, you will also need to properly setup the app configuration. The recommended app setup is as follows:
+
+| Parameter | Option |
+| ----------------------- | ---------------------- |
+| App to use | `No App` |
+| VESC ID | `1,2,...` |
+| Can Status Message Mode | `CAN_STATUS_1_2_3_4_5` |
+| CAN Baud Rate | `CAN_BAUD_500K` |
+| CAN Mode | `UAVCAN` |
+| UAVCAN ESC Index | `0,1,...` |
+
+
+VESC ID should have the same motor numbering as in PX4 convention, starting at `1` for top-right motor, `2` for bottom-left motor etc. However the `UAVCAN ESC Index` starts from `0`, and as such it is always one index lower than the `VESC ID`. For example, in a quadcopter the bottom left motor will have `VESC ID = 2` and `UAVCAN ESC Index = 1`.
+
+Finally the `CAN Baud Rate` must match the value set in [UAVCAN_BITRATE](../advanced_config/parameter_reference.md#UAVCAN_BITRATE).
+
+
+## Troubleshooting
+
+#### Motors not spinning when armed
+
+If the PX4 Firmware arms but the motors do not start to rotate, check that parameter `UAVCAN_ENABLE=3` to use UAVCAN ESCs. If the motors do not start spinning before thrust is increased, check `UAVCAN_ESC_IDLT=1`.
+
+#### UAVCAN devices dont get node ID/Firmware Update Fails
+
+PX4 requires an SD card for UAVCAN node allocation and during firmware update (which happen during boot). Check that there is a (working) SD card present and reboot.
+
+
+## Further Information
+
+- [PX4/Sapog](https://github.com/PX4/sapog#px4-sapog) (Github)
+- [Sapog v2 Reference Manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+- [Using Sapog based ESC with PX4](https://kb.zubax.com/display/MAINKB/Using+Sapog-based+ESC+with+PX4) (Zubax KB)
+
diff --git a/de/uavcan/node_firmware.md b/de/uavcan/node_firmware.md
index 241f486e2c51..35b231c9431d 100644
--- a/de/uavcan/node_firmware.md
+++ b/de/uavcan/node_firmware.md
@@ -1,5 +1,11 @@
# UAVCAN Firmware Upgrading
+PX4 will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied.
+
+:::warning UAVCAN
+devices typically ship with appropriate firmware preinstalled. These instructions are primarily needed when developing UAVCAN devices.
+:::
+
## Vectorcontrol ESC Codebase (Pixhawk ESC 1.6 and S2740VC)
Download the ESC code:
diff --git a/de/uavcan/pomegranate_systems_pm.md b/de/uavcan/pomegranate_systems_pm.md
new file mode 100644
index 000000000000..fb28d03e56ab
--- /dev/null
+++ b/de/uavcan/pomegranate_systems_pm.md
@@ -0,0 +1,55 @@
+# Pomegranate Systems Power Module
+
+![Module Image](../../assets/hardware/power_module/pomegranate_systems_pm/main_image.jpg)
+
+Digital Power Module with high resolution current integration, 5V/2A supply with power monitoring, single UAVCAN v0 CANbus interface, and an RGB status LED.
+
+Detailed setup, configuration, and troubleshooting information can be found on the [manufacturer's device home page](https://p-systems.io/product/power_module).
+
+## Specifications
+
+ - **Input Voltage:** 6-26V \(2-6S\)
+ - **Max Continuous Current:**
+ - **Benchtop:** 40A
+ - **Forced Cooling:** 100A
+ - **Max 5V Output Current:** 2A
+ - **Voltage Resolution:** 0.04 ΔV
+ - **Current Resolution:**
+ - **Primary / Battery Bus:** 0.02 ΔA
+ - **5V bus:** 0.001 ΔA
+ - **CANbus Termination:** Electronic (on by default)
+ - **MCU:** STM32 F302K8U
+ - **Firmware:** [Open Source](https://bitbucket.org/p-systems/firmware/)
+ - **Electrical Interface:**
+ - **Power:** Solder pads or XT60PW (right angle, board-mounted connectors)
+ - **CANbus** Dual JST GH-4 (standard UAVCAN micro-connector)
+ - **I2C / Serial:** JST GH-5
+ - **5V Output:** Solder pads or CANbus / I2C connectors
+ - **Device Mass:**
+ - **Without Connectors:** 9g
+ - **With XT60PW Connectors:** 16g
+
+
+ ![Dimensions](../../assets/hardware/power_module/pomegranate_systems_pm/mechanical.png)
+
+## Configuration
+
+ 1. Enable UAVCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`.
+ 2. Set the following module parameters using the [Mavlink console](https://docs.qgroundcontrol.com/en/analyze_view/mavlink_console.html):
+ * Battery capacity in mAh: `battery_capacity_mAh`
+ * Battery voltage when *full*: `battery_full_V`,
+ * Battery voltage when *empty*: `battery_empty_V`
+ * Turn on current integration: `enable_current_track`
+ * (optional) Turn Off CANbus termination resistor :`enable_can_term`
+
+**Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands:
+
+```
+uavcan param set 125 battery_capacity_mAh 5000
+uavcan param set 125 battery_full_V 12.5
+uavcan param set 125 battery_empty_V 11.2
+uavcan param set 125 enable_current_track 1
+uavcan param save 125
+```
+
+See [device configuration page](https://p-systems.io/product/power_module/configuration) for a full list of parameters.
diff --git a/ja/SUMMARY.md b/ja/SUMMARY.md
index f215f243bbfe..98d7cd254faa 100644
--- a/ja/SUMMARY.md
+++ b/ja/SUMMARY.md
@@ -12,7 +12,8 @@
* [LED表示の意味](getting_started/led_meanings.md)
* [通知音の意味](getting_started/tunes.md)
* [飛行前チェック](flying/pre_flight_checks.md)
- * [フライトの報告](getting_started/flight_reporting.md)
+ * [Payloads & Cameras](payloads/README.md)
+ * [Flight Reporting](getting_started/flight_reporting.md)
* [基本構成](assembly/README.md)
* [フライトコントローラのマウント](assembly/mount_and_orient_controller.md)
* [振動除去](assembly/vibration_isolation.md)
@@ -229,10 +230,10 @@
* [FrSky Telemetry](peripherals/frsky_telemetry.md)
* [Power Modules](power_module/README.md)
* [CUAV HV pm](power_module/cuav_hv_pm.md)
- * [CUAV CAN PMU](power_module/cuav_can_pmu.md)
+ * [CUAV CAN PMU](uavcan/cuav_can_pmu.md)
* [Holybro PM07 (Pixhawk 4 PM)](power_module/holybro_pm07_pixhawk4_power_module.md)
* [Holybro PM06 (Micro Power Module)](power_module/holybro_pm06_pixhawk4mini_power_module.md)
- * [Pomegranate Systems Power Module](power_module/pomegranate_systems_pm.md)
+ * [Pomegranate Systems Power Module](uavcan/pomegranate_systems_pm.md)
* [Distance Sensors \(Rangefinders\)](sensor/rangefinders.md)
* [Lightware SFxx Lidar](sensor/sfxx_lidar.md)
* [Ainstein US-D1 Standard Radar Altimeter](sensor/ulanding_radar.md)
@@ -241,7 +242,7 @@
* [Lidar-Lite](sensor/lidar_lite.md)
* [TeraRanger](sensor/teraranger.md)
* [Lanbao PSK-CM8JL65-CC5](sensor/cm8jl65_ir_distance_sensor.md)
- * [Avionics Anonymous Laser Altimeter UAVCAN Interface](sensor/avanon_laser_interface.md)
+ * [Avionics Anonymous Laser Altimeter UAVCAN Interface](uavcan/avanon_laser_interface.md)
* [Tachometers (Revolution Counters)](sensor/tachometers.md)
* [ThunderFly TFRPM01 Tachometer Sensor](sensor/thunderfly_tachometer.md)
* [Airspeed Sensors](sensor/airspeed.md)
@@ -250,13 +251,15 @@
* [PMW3901](sensor/pmw3901.md)
* [ESCs & Motors](peripherals/esc_motors.md)
* [PWM ESCs and Servos](peripherals/pwm_escs_and_servo.md)
+ * [UAVCAN ESCs](uavcan/escs.md)
* [DShot ESCs](peripherals/dshot.md)
- * [UAVCAN ESCs](peripherals/uavcan_escs.md)
* [Camera](peripherals/camera.md)
* [Parachute](peripherals/parachute.md)
* [ADSB/FLARM (Traffic Avoidance)](peripherals/adsb_flarm.md)
* [Smart Batteries](smart_batteries/README.md)
* [Rotoye Batmon Battery Smartification Kit](smart_batteries/rotoye_batmon.md)
+ * [UAVCAN Peripherals](uavcan/README.md)
+ * [UAVCAN Configuration](uavcan/node_enumeration.md)
* [Companion Computer Peripherals](peripherals/companion_computer_peripherals.md)
* [Development](development/development.md)
* [Getting Started](dev_setup/getting_started.md)
@@ -310,11 +313,9 @@
* [SiK Radio](data_links/sik_radio.md)
* [Sensor and Actuator I/O](sensor_bus/README.md)
* [I2C Bus](sensor_bus/i2c.md)
- * [UAVCAN Bus](uavcan/README.md)
+ * [UAVCAN Bus](uavcan/developer.md)
* [UAVCAN Bootloader](uavcan/bootloader_installation.md)
* [UAVCAN Firmware Upgrades](uavcan/node_firmware.md)
- * [UAVCAN Configuration](uavcan/node_enumeration.md)
- * [UAVCAN Various Notes](uavcan/notes.md)
* [UART/Serial Ports](uart/README.md)
* [Port-Configurable Serial Drivers](uart/user_configurable_serial_driver.md)
* [RTK GPS (Integration)](advanced/rtk_gps.md)
diff --git a/ja/flight_modes/mission.md b/ja/flight_modes/mission.md
index 598f779dac58..a2490976b413 100644
--- a/ja/flight_modes/mission.md
+++ b/ja/flight_modes/mission.md
@@ -48,7 +48,7 @@ To automatically disarm the vehicle after it lands, in *QGroundControl* go to [V
Missions can be paused by activating [HOLD mode](../flight_modes/hold.md). The mission will then continue from the current mission command when you reactivate the MISSION flight mode. While flying in mission mode, if you decide to discontinue the mission and switch to any other mode e.g. position mode, fly the vehicle elsewhere with RC, and then switch back to mission mode, the vehicle will continue the mission from its current position and will fly to the next mission waypoint not visited yet.
:::warning
-Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash).We recommend you centre the control sticks before switching to any other mode.
+Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.
:::
For more information about mission planning, see:
@@ -77,7 +77,7 @@ Mission behaviour is affected by a number of parameters, most of which are docum
## Supported Mission Commands
-PX4 "accepts" the following MAVLink mission commands in Mission mode (note: caveats below list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
+PX4 "accepts" the following MAVLink mission commands in Mission mode (with some *caveats*, given after the list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
* [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT)
* *Param3* (flythrough) is ignored. Flythrough is always enabled if *param 1* (time_inside) > 0.
@@ -86,9 +86,6 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
* [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF)
* [MAV_CMD_NAV_LOITER_TO_ALT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TO_ALT)
-* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
-* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
-* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
* [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF)
* `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
@@ -104,6 +101,9 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -122,30 +122,36 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
-* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
-* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+* [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+* [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+* [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+* [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+* [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+* [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
Note:
* PX4 parses the above messages, but they are not necessary *acted* on. For example, some messages are vehicle-type specific.
-* PX4 generally does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) ).
+* PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* Not all messages/commands are exposed via *QGroundControl*.
-* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) (list generated in [this git changelist](https://github.com/PX4/PX4-Autopilot/commit/ca1f7a4a194c23303c23ca79b5905ff8bfb94c22)).
+* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-Please add an bug fix or PR if you find a missing/incorrect message.
+Please add an issue report or PR if you find a missing/incorrect message.
:::
## Inter-Waypoint Trajectory
PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).
-MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning.
+MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+![acc-rad](../../assets/flying/acceptance_radius_mission.png)
-Vehicles switch to the next waypoint as soon as they enter the acceptance radius.
+Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
-* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)
-* For FW the radius is defined by the "L1 distance".
+* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+* For FW the acceptance radius is defined by the "L1 distance".
* The L1 distance is computed from two parameters: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) and [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD), and the current ground speed.
* By default, it's about 70 meters.
* The equation is: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/ja/flying/missions.md b/ja/flying/missions.md
index 571135d77511..638bd7caa9b4 100644
--- a/ja/flying/missions.md
+++ b/ja/flying/missions.md
@@ -26,6 +26,22 @@ If **Heading** has not been explicitly set for the target waypoint (`param4=NaN`
Vehicle types that cannot independently control yaw and direction of travel will ignore yaw settings (e.g. Fixed Wing).
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## Flying Missions
Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
diff --git a/ja/getting_started/README.md b/ja/getting_started/README.md
index f5ec4e41a66f..513520c68444 100644
--- a/ja/getting_started/README.md
+++ b/ja/getting_started/README.md
@@ -14,4 +14,6 @@
[フライトモード](../getting_started/flight_modes.md) — 手動・操縦アシスト・自動操縦用のフライトモードについて.
-[フライトの報告](../getting_started/flight_reporting.md) — デバッグ・分析のための詳細なフライトログのダウンロード方法について.
\ No newline at end of file
+[Payloads & Cameras](../payloads/README.md)
+
+[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/ja/payloads/README.md b/ja/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/ja/payloads/README.md
+++ b/ja/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/ja/peripherals/uavcan_escs.md b/ja/peripherals/uavcan_escs.md
index 37da24c9f172..8e8787388307 100644
--- a/ja/peripherals/uavcan_escs.md
+++ b/ja/peripherals/uavcan_escs.md
@@ -1,174 +1 @@
-# UAVCAN ESCs (Motor Controllers)
-
-PX4 supports the [UAVCAN](https://uavcan.org/) bus for connecting peripherals, including ESCs, GPS modules, various types of sensors, etc. However PX4 currently does not support UAVCAN Servos.
-
-UAVCAN ESCs have a number of advantages over [PWM ESCs](../peripherals/pwm_escs_and_servo.md):
-
-- UAVCAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
-- The bus is bi-directional, enabling health monitoring and diagnostics.
-- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other UAVCAN peripherals.
-- Setup is easier as you configure ESC numbering by manually spinning each motor (for most types of UAVCAN ESCs).
-
-## PX4 Supported ESC
-
-PX4 is compatible with any/all UAVCAN ESCs (UAVCAN is generally speaking a plug'n'play protocol).
-
-:::note
-At time of writing PX4 supports UAVCAN v0 (not v1.0).
-:::
-
-The only difference between UAVCAN ESCs from a setup perspective is that the physical connectors and the software tools used to configure the motor order and direction may be different.
-
-Some popular UAVCAN ESC firmware/products include:
-
-- [Sapog](#sapog) firmware; an advanced open source sensorless PMSM/BLDC motor controller firmware designed for use in propulsion systems of electric unmanned vehicles.
- - [Zubax Orel 20](https://zubax.com/products/orel_20)
- - [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
-- [Mitochondrik](https://zubax.com/products/mitochondrik) - integrated sensorless PMSM/BLDC motor controller chip (used in ESCs and integrated drives)
- - [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
-- [Myxa](https://zubax.com/products/myxa) - High-end PMSM/BLDC motor controller (FOC ESC) for light unmanned aircraft and watercraft.
-- [VESC Project ESCs](https://vesc-project.com/) (see also [Benjamin Vedder's blog](http://vedder.se) - project owner)
-- [OlliW’s UC4H ESC-Actuator Node](http://www.olliw.eu/2017/uavcan-for-hobbyists/#chapterescactuator)
-- A number of others are [listed here](https://forum.uavcan.org/t/uavcan-esc-options/452/3?u=pavel.kirienko)
-
-:::note
-This list is *not exhaustive/complete*. If you know of another ESC, please add it to the list!
-:::
-
-## Purchase
-
-Sapog-based ESCs:
-
-- [Zubax Orel 20](https://zubax.com/products/orel_20)
-
- ![Orel20 - Top](../../assets/peripherals/esc_uavcan_zubax_orel20/orel20_top.jpg)
-
-- [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
-
- ![Kotleta20 - Top](../../assets/peripherals/esc_uavcan_holybro_kotleta20/kotleta20_top.jpg) ![Kotleta20 - Bottom](../../assets/peripherals/esc_uavcan_holybro_kotleta20/kotleta20_bottom.jpg)
-
-Mitochondrik based drives and ESC:
-
-- [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
-
- ![Sadulli - Top](../../assets/peripherals/esc_usavcan_zubax_sadulli/sadulli_top.jpg)
-
-:::note
-There are many other commercially available ESCs; please add new links as you find them!
-:::
-
-
-
-## Wiring/Connections
-
-Connect all of the on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes. The order in which the ESCs are connected/chained does not matter.
-
-:::note
-All UAVCAN ESCs share the same connection architecture/are wired the same way. Note however that the actual connectors differ (e.g. *Zubax Orel 20* and *Holybro Kotleta20* use Dronecode standard connectors (JST-GH 4 Pin) - while VESCs do not).
-:::
-
-For more information about proper bus connections see [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB).
-
-## PX4 Configuration
-
-In order to use a UAVCAN ESC with PX4 you will need to enable the UAVCAN driver:
-
-1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller!) and connect *QGroundControl*.
-2. Navigate to the **Vehicle Setup > Parameters** screen > [Parameters](../advanced_config/parameters.md) explains how to find and set parameters.
-3. Set [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to the value *Sensors and Motors* (3) and then reboot the flight controller.
-
-If applicable (some systems will not benefit from this behavior, e.g. glider drones):
-
-1. Set [UAVCAN_ESC_IDLT](../advanced_config/parameter_reference.md#UAVCAN_ESC_IDLT) to 1 in order to ensure that the motors are always running at least at the idle throttle while the system is armed.
-
-## ESC Setup
-
-While UAVCAN devices are generally *plug'n'play* you will still need to enumerate (number) each of the ESC used in your system and set their direction so that they can be identified/controlled by PX4.
-
-:::note
-The ESC index and direction must match/map to the [Airframe Reference](../airframes/airframe_reference.md) for the vehicle type. ESC indexes from 0-7 map to MAIN 1-8, while ESC indexes 8-15 map to AUX 1-8.
-:::
-
-The mechanism for enumerating each type of UAVCAN ESC is different (look up the instructions in your ESC's manual). Setup information for some UAVCAN ESCs is provided below.
-
-
-
-### Sapog ESC setup
-
-The following sections explain how to enumerate [Sapog-based](https://github.com/PX4/sapog#px4-sapog)-based ESCs with PX4. The instructions should work for any Sapog-based ESC design.
-
-
-
-#### ESC Enumeration using QGroundControl
-
-:::tip
-You can skip this section if there is only one ESC in your setup, because the ESC index is already set to zero by default.
-:::
-
-To enumerate the ESC:
-
-1. Power the vehicle with a battery and connect to *QGroundControl*
-2. Navigate to **Vehicle Setup > Power** in QGC.
-3. Start the process of ESC auto-enumeration by pressing the **Start Assignment** button, as shown on the screenshot below.
-
- ![QGC - UAVCAN ESC auto-enumeration](../../assets/peripherals/esc_qgc/qgc_uavcan_settings.jpg)
-
- You will hear a sound indicating that the flight controller has entered the ESC enumeration mode.
-
-4. Manually turn each motor in the correct direction of its rotation, starting from the first motor and finishing with the last motor. Each time you turn a motor, you should hear a confirmation.
-
-:::note
-Make sure to turn each of the motors in the correct direction, because the ESC will automatically learn and remember the direction (i.e. motors that spin clockwise during normal operation must also be turned clockwise during enumeration).
-:::
-
-5. After the last motor is enumerated, the confirmation sound should change to indicate that the enumeration procedure is complete.
-
-The following video demonstrates the process:
-
-@[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ) @[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ)
-
-#### Manual ESC Enumeration using Sapog
-
-:::tip
-We recommend automated [ESC Enumeration using QGroundControl](#sapog_esc_qgc) rather than manual enumeration - it is easier and safer.
-:::
-
-You can manually configure the ESC index and direction using the [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/). This assigns the following Sapog configuration parameters for each enumerated ESC:
-
-- `esc_index`
-- `ctl_dir`
-
-:::note
-See [Sapog reference manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf) for more information about the parameters.
-:::
-
-### Myxa ESC Setup
-
-Motor enumeration for Myxa [Telega-based ESCs](https://zubax.com/products/telega) is usually performed using the [Kucher tool](https://files.zubax.com/products/com.zubax.kucher/) (or less "GUI-friendly" [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/)).
-
-There is some guidance here: [Quick start guide for Myxa v0.1](https://forum.zubax.com/t/quick-start-guide-for-myxa-v0-1/911) (Zubax blog).
-
-### VESC ESC Setup
-
-For [VESC ESCs](https://vesc-project.com/) the preferred tool for motor enumeration is the [VESC tool](https://vesc-project.com/vesc_tool). In addition to the normal motor configuration that you will have to setup in the VESC tool, you will also need to properly setup the app configuration. The recommended app setup is as follows:
-
-| Parameter | Option |
-| ----------------------- | ---------------------- |
-| App to use | `No App` |
-| VESC ID | `1,2,...` |
-| Can Status Message Mode | `CAN_STATUS_1_2_3_4_5` |
-| CAN Baud Rate | `CAN_BAUD_500K` |
-| CAN Mode | `UAVCAN` |
-| UAVCAN ESC Index | `0,1,...` |
-
-
-VESC ID should have the same motor numbering as in PX4 convention, starting at `1` for top-right motor, `2` for bottom-left motor etc. However the `UAVCAN ESC Index` starts from `0`, and as such it is always one index lower than the `VESC ID`. For example, in a quadcopter the bottom left motor will have `VESC ID = 2` and `UAVCAN ESC Index = 1`.
-
-Finally the `CAN Baud Rate` must match the value set in [UAVCAN_BITRATE](../advanced_config/parameter_reference.md#UAVCAN_BITRATE).
-
-## Further Information
-
-- [PX4/Sapog](https://github.com/PX4/sapog#px4-sapog) (Github)
-- [Sapog v2 Reference Manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf)
-- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
-- [Using Sapog based ESC with PX4](https://kb.zubax.com/display/MAINKB/Using+Sapog-based+ESC+with+PX4) (Zubax KB)
\ No newline at end of file
+
\ No newline at end of file
diff --git a/ja/power_module/README.md b/ja/power_module/README.md
index 53081ff61a81..b968e6eee153 100644
--- a/ja/power_module/README.md
+++ b/ja/power_module/README.md
@@ -14,6 +14,6 @@ This section provides links/information about supported power modules and power
* [CUAV HV PM](../power_module/cuav_hv_pm.md)
* [Holybro PM07 (Pixhawk 4 PM)](../power_module/holybro_pm07_pixhawk4_power_module.md)
* [Holybro PM06 (Pixhawk 4 Mini PM)](../power_module/holybro_pm06_pixhawk4mini_power_module.md)
-* [UAVCAN](https://new.uavcan.org/) power modules
- * [CUAV CAN PMU](../power_module/cuav_can_pmu.md)
- * [Pomegranate Systems Power Module](../power_module/pomegranate_systems_pm.md)
\ No newline at end of file
+* [UAVCAN](../uavcan/README.md) power modules
+ * [CUAV CAN PMU](../uavcan/cuav_can_pmu.md)
+ * [Pomegranate Systems Power Module](../uavcan/pomegranate_systems_pm.md)
\ No newline at end of file
diff --git a/ja/power_module/cuav_can_pmu.md b/ja/power_module/cuav_can_pmu.md
index ed1fb2336010..0ad669867be1 100644
--- a/ja/power_module/cuav_can_pmu.md
+++ b/ja/power_module/cuav_can_pmu.md
@@ -1,69 +1 @@
-# CAUV CAN PMU
-
-CAN PMU® is a high-precision power module developed by CUAV®. It uses the [UAVCAN](https://new.uavcan.org/) protocol and runs the CUAV ITT compensation algorithm, which enables drones to get the battery data more accurately.
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu.jpg)
-
-It is recommended for use in large commercial vehicles, but might also be used for research vehicles.
-
-## Specifications
-
-- **Processor:** STM32F412
-- **Voltage input**: 6~62V\(2-15S\)
-- **Max current:** 110A
-- **Voltage accuracy:** ±0.05V
-- **Current accuracy:** ±0.1A
-- **Resolution:** 0.01A/V
-- **Max output power:** 6000W/90S
-- **Max stable power:** 5000W
-- **Power port output:** 5.4V/5A
-- **Protocol:** UAVCAN
-- **Operating temp:** -20~+100
-- **Firmware upgrade:** Supported.
-* **Calibration:** Not needed.
-* **Interface Type:**
- - **IN/OUT:** XT90\(Cable)/Amass 8.0\(Module)
- - **Power port:** 5025850670
- - **CAN:** GHR-04V-S
-- **Appearance:**
- - **Size:** 46.5mm \* 38.5mm \* 22.5mm
- - **Weight:** 76g
-
-## Purchase
-
-- [CUAV store](https://store.cuav.net/index.php)
-- [CUAV aliexpress ](https://www.aliexpress.com/item/4000369700535.html)
-
-## Pinouts
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en.png)
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en2.png)
-
-## Connection
-
-![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_connection_en.png)
-
-The connection steps are:
-* Connect the flight control CAN1/2 and the module CAN interface.
-* Connect the V5 series power cable to the V5 Flight Control Power2 (if other flight controllers are connect to the Power interface) and the module Power interface.
-
-## Enable CAN PMU
-
-Set the following parameters in the *QGroundControl* [parameter list](../advanced_config/parameters.md) and then restart:
-
-* `UAVCAN_ENABLE`: set to: *Sensors Automatic Config*
-
- ![qgc set](../../assets/hardware/power_module/cuav_can/qgc_set_en.png)
-
-# Package Contents
-
-![CAN PMU list](../../assets/hardware/power_module/cuav_can/can_pmu_list.png)
-
-## Further Information
-
-[CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf)
-
-[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs)
-
-[UAVCAN](https://new.uavcan.org/)
\ No newline at end of file
+
diff --git a/ja/power_module/pomegranate_systems_pm.md b/ja/power_module/pomegranate_systems_pm.md
index fb28d03e56ab..ea1549c370ba 100644
--- a/ja/power_module/pomegranate_systems_pm.md
+++ b/ja/power_module/pomegranate_systems_pm.md
@@ -1,55 +1 @@
-# Pomegranate Systems Power Module
-
-![Module Image](../../assets/hardware/power_module/pomegranate_systems_pm/main_image.jpg)
-
-Digital Power Module with high resolution current integration, 5V/2A supply with power monitoring, single UAVCAN v0 CANbus interface, and an RGB status LED.
-
-Detailed setup, configuration, and troubleshooting information can be found on the [manufacturer's device home page](https://p-systems.io/product/power_module).
-
-## Specifications
-
- - **Input Voltage:** 6-26V \(2-6S\)
- - **Max Continuous Current:**
- - **Benchtop:** 40A
- - **Forced Cooling:** 100A
- - **Max 5V Output Current:** 2A
- - **Voltage Resolution:** 0.04 ΔV
- - **Current Resolution:**
- - **Primary / Battery Bus:** 0.02 ΔA
- - **5V bus:** 0.001 ΔA
- - **CANbus Termination:** Electronic (on by default)
- - **MCU:** STM32 F302K8U
- - **Firmware:** [Open Source](https://bitbucket.org/p-systems/firmware/)
- - **Electrical Interface:**
- - **Power:** Solder pads or XT60PW (right angle, board-mounted connectors)
- - **CANbus** Dual JST GH-4 (standard UAVCAN micro-connector)
- - **I2C / Serial:** JST GH-5
- - **5V Output:** Solder pads or CANbus / I2C connectors
- - **Device Mass:**
- - **Without Connectors:** 9g
- - **With XT60PW Connectors:** 16g
-
-
- ![Dimensions](../../assets/hardware/power_module/pomegranate_systems_pm/mechanical.png)
-
-## Configuration
-
- 1. Enable UAVCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`.
- 2. Set the following module parameters using the [Mavlink console](https://docs.qgroundcontrol.com/en/analyze_view/mavlink_console.html):
- * Battery capacity in mAh: `battery_capacity_mAh`
- * Battery voltage when *full*: `battery_full_V`,
- * Battery voltage when *empty*: `battery_empty_V`
- * Turn on current integration: `enable_current_track`
- * (optional) Turn Off CANbus termination resistor :`enable_can_term`
-
-**Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands:
-
-```
-uavcan param set 125 battery_capacity_mAh 5000
-uavcan param set 125 battery_full_V 12.5
-uavcan param set 125 battery_empty_V 11.2
-uavcan param set 125 enable_current_track 1
-uavcan param save 125
-```
-
-See [device configuration page](https://p-systems.io/product/power_module/configuration) for a full list of parameters.
+
diff --git a/ja/releases/1.12.md b/ja/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/ja/releases/1.12.md
+++ b/ja/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/ja/ros/ros2_offboard_control.md b/ja/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/ja/ros/ros2_offboard_control.md
+++ b/ja/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).
diff --git a/ja/sensor/rangefinders.md b/ja/sensor/rangefinders.md
index 3789dae1870e..a1c9d5a11ac5 100644
--- a/ja/sensor/rangefinders.md
+++ b/ja/sensor/rangefinders.md
@@ -48,7 +48,7 @@ The [Lanbao PSK-CM8JL65-CC5 ToF Infrared Distance Measuring Sensor](../sensor/cm
### Avionics Anonymous UAVCAN Laser Altimeter Interface
-The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../sensor/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the UAVCAN bus, a more robust interface than I2C.
+The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../uavcan/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the [UAVCAN](../uavcan/README.md) bus, a more robust interface than I2C.
diff --git a/ja/simulation/airsim.md b/ja/simulation/airsim.md
index 2d3854f8392b..401b169bc8b3 100644
--- a/ja/simulation/airsim.md
+++ b/ja/simulation/airsim.md
@@ -2,9 +2,9 @@
AirSim is a open-source, cross platform simulator for drones, built on Unreal Engine. It provides physically and visually realistic simulations of Pixhawk/PX4 using either Hardware-In-The-Loop \(HITL\) or Software-In-The-Loop \(SITL\).
-The main entry point for the documentation is the [Github AirSim README](https://github.com/Microsoft/AirSim/blob/master/README.md).
+The main entry point for the documentation is the [AirSim Documentation](https://microsoft.github.io/AirSim/).
-The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://github.com/Microsoft/AirSim/blob/master/docs/px4_setup.md) (covering both HITL and SITL).
+The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://microsoft.github.io/AirSim/px4_setup/) (covering both HITL and SITL).
## Further Information
diff --git a/ja/uavcan/README.md b/ja/uavcan/README.md
index f7705f999823..b492dc80d6a7 100644
--- a/ja/uavcan/README.md
+++ b/ja/uavcan/README.md
@@ -1,53 +1,82 @@
-# UAVCAN Introduction
+# UAVCAN
-![UAVCAN Logo](../../assets/uavcan/uavcan_logo_transparent.png)
+ [UAVCAN](http://uavcan.org) is an onboard network which allows the autopilot to connect to avionics/peripherals. It uses rugged, differential signalling, and supports firmware upgrades over the bus and status feedback from peripherals.
-[UAVCAN](http://uavcan.org) is an onboard network which allows the autopilot to connect to avionics. It supports hardware like:
-
-* Motor controllers
- * [Zubax Orel 20](https://zubax.com/product/zubax-orel-20) :::note Runs [Sapog Firmware](https://github.com/px4/sapog) (open source). Based on [Sapog Reference Hardware](https://github.com/PX4/Hardware/tree/master/sapog_reference_hardware).
+:::note PX4 requires an SD card for UAVCAN node allocation and firmware upgrade. It is not used during flight by UAVCAN.
:::
+
+## Supported Hardware
+
+It supports hardware like:
+
+* [ESC/Motor controllers](../uavcan/escs.html)
* Airspeed sensors
* [Thiemar airspeed sensor](https://github.com/thiemar/airspeed)
* GNSS receivers for GPS and GLONASS
* [Zubax GNSS](https://zubax.com/products/gnss_2)
* Power monitors
- * [Pomegranate Systems Power Module](../power_module/pomegranate_systems_pm.md)
- * [CUAV CAN PMU Power Module](../power_module/cuav_can_pmu.md)
+ * [Pomegranate Systems Power Module](../uavcan/pomegranate_systems_pm.md)
+ * [CUAV CAN PMU Power Module](../uavcan/cuav_can_pmu.md)
+* Distance sensors
+ - [Avionics Anonymous Laser Altimeter UAVCAN Interface](../uavcan/avanon_laser_interface.md)
-In contrast to hobby-grade devices it uses rugged, differential signalling and supports firmware upgrades over the bus. All motor controllers provide status feedback and implement field-oriented-control \(FOC\).
-
-:::note PX4 requires an SD card for UAVCAN node allocation and firmware upgrade. It is not used during flight by UAVCAN.
+:::note PX4 does not support UAVCAN servos (at time of writing).
:::
-## Initial Setup
-The following instructions provide a step-by-step guide to connect and setup a quadcopter with ESCs and GPS connected via UAVCAN. The hardware of choice is a Pixhawk 2.1, Zubax Orel 20 ESCs and a Zubax GNSS GPS module.
+## Wiring
-### Wiring
+All UAVCAN components share the same connection architecture/are wired the same way. Connect all on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes (the order in which the nodes are connected/chained does not matter).
-The first step is to connect all UAVCAN enabled devices with the flight controller. The following diagram displays how to wire all components. The used Zubax devices all support a redundant CAN interface in which the second bus is optional but increases the robustness of the connection.
+The following diagram shows this for a flight controller connected to [UAVCAN motor controllers (ESCs)](../uavcan/escs.html) and a UAVCAN GNSS.
![UAVCAN Wiring](../../assets/uavcan/uavcan_wiring.png)
-It is important to mention that some devices require an external power supply \(e.g. Zubax Orel 20\) and others can be powered by the CAN connection \(e.g Zubax GNSS\) itself. Please refer to the documentation of your hardware before continuing with the setup.
+The diagram does not show any power wiring. Refer to your manufacturer instructions to confirm whether components require separate power or can be powered from the CAN bus itself.
+
+For more information about proper bus connections see [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB).
+
+:::note
+- While the connections are the same, the _connectors_ may differ across devices.
+- An second/redundant" CAN interface may be used, as shown above (CAN2). This is optional, but can increase the robustness of the connection.
+:::
+
+
+## PX4 Configuration
+
+In order to use UAVCAN components with PX4 you will first need to enable the UAVCAN driver:
+
+1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller) and connect *QGroundControl*.
+1. Navigate to the **Vehicle Setup > Parameters** screen.
+1. [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) must be [set](../advanced_config/parameters.md) to one of the non-zero values.
+
+ The values are:
+ - `0`: UAVCAN driver disabled.
+ - `1`: Sensors Manual Config.
+ - `2`: Sensors Automatic Config.
+ - `3`: Sensors and Actuators (ESCs) Automatic Config
+
+ Use `1` if _none_ of the connected UAVCAN devices support automatic configuration (check the manual!), `2` or `3` if _some_ of them support automatic configuration, and `3` if you're using UAVCAN ESCs (this assigns motor controls to the UAVCAN bus rather than PWM).
+
+:::note
+You will need to manually allocate static ids for any nodes that don't support automatic configuration. When using dynamic configuration, any manually allocated ids should be given a value greater than the number of UAVCAN devices (to avoid clashes).
+:::
+
+Most UAVCAN sensors require no further setup (they are plug'n'play, unless specifically noted in their documentation).
-### Firmware Setup
+[UAVCAN motor controllers (ESCs)](../uavcan/escs.md) additionally require the motor order be set, and may require a few other parameters be set. Whether this can be done using the simple QGroundControl setup UI depends on the type of ESC (see link for information).
-Next, follow the instructions in [UAVCAN Configuration](../uavcan/node_enumeration.md) to activate the UAVCAN functionalities in the firmware. Disconnect your power supply and reconnect it. After the power cycle all UAVCAN devices should be detected which is confirmed by a beeping motor on the Orel 20 ESCs. You can now continue with the general setup and calibration.
-Depending on the used hardware, it can be reasonable to perform an update of the firmware on the UAVCAN devices. This can be done via the UAVCAN itself and the PX4 firmware. For more details please refer to the instructions in [UAVCAN Firmware](../uavcan/node_firmware.md).
+## Troubleshooting
-## Upgrading Node Firmware
+### UAVCAN devices dont get node ID/Firmware Update Fails
-The PX4 middleware will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied. The process and requirements are described on the [UAVCAN Firmware](../uavcan/node_firmware.md) page.
+PX4 requires an SD card for UAVCAN node allocation and during firmware update (which happen during boot). Check that there is a (working) SD card present and reboot.
-## Enumerating and Configuring Motor Controllers
+### Motors not spinning when armed
-The ID and rotational direction of each motor controller can be assigned after installation in a simple setup routine: [UAVCAN Node Enumeration](../uavcan/node_enumeration.md). The routine can be started by the user through QGroundControl.
+If the PX4 Firmware arms but the motors do not start to rotate, check that parameter `UAVCAN_ENABLE=3` to use UAVCAN ESCs. If the motors do not start spinning before thrust is increased, check `UAVCAN_ESC_IDLT=1`.
-## Useful links
+## Developer Information
-* [Homepage](http://uavcan.org)
-* [Specification](https://uavcan.org/specification/)
-* [Implementations and tutorials](http://uavcan.org/Implementations)
+- [UAVCAN Development](../uavcan/developer.md): Topics related to development and integration of new UAVCAN hardware into PX4.
diff --git a/ja/uavcan/avanon_laser_interface.md b/ja/uavcan/avanon_laser_interface.md
new file mode 100644
index 000000000000..863ab645051b
--- /dev/null
+++ b/ja/uavcan/avanon_laser_interface.md
@@ -0,0 +1,57 @@
+# Avionics Anonymous Laser Altimeter UAVCAN Interface
+
+The [Avionics Anonymous Laser Altimeter Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/) allows a [number of common rangefinders](#supported_rangefinders) to be connected via the UAVCAN bus (this is a more robust interface than I2C).
+
+![Avionics Anonymous Laser Altimeter UAVCAN Interface](../../assets/hardware/sensors/avionics_anon_uavcan_alt_interface/avionics_anon_altimeter_uavcan_interface.jpg)
+
+## Where to Buy
+
+* [AvAnon Laser Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/)
+
+
+## Supported Rangefinders
+
+A full list supported rangefinders can be found on the link above.
+
+At time of writing the following rangefinders are supported:
+
+- Lightware SF30/D
+- Lightware SF10/a
+- Lightware SF10/b
+- Lightware SF10/c
+- Lightware SF11/c
+- Lightware SF/LW20/b
+- Lightware SF/LW20/c
+
+
+## Pinouts
+
+### CAN Connector
+| Pin | Name | Description |
+| --- | -------- | ----------------------------------------------------------------------------------- |
+| 1 | POWER_IN | Power Supply. 4.0-5.5V supported, but must also be compatible with connected laser. |
+| 2 | TX/SCL | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+### Laser Connector
+
+| Pin | Name | Description |
+| --- | --------- | -------------------------------------- |
+| 1 | POWER_OUT | Filtered power at the supply voltage. |
+| 2 | CAN+ | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+
+## Wiring
+
+The rangefinder (laser) is connected to the AvAnon interface board, which is connected to one of the CAN ports on your autopilot. The wiring is as per the pinout above, or the necessary cables can be purchased to connect to your system right out of the box. These are available at the links [here](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/).
+
+The interface board provides a filtered power output for the laser, but does not provide its own regulation. Therefore the laser must be compatible with whatever voltage is supplied to the board.
+
+## Software Configuration
+
+UAVCAN must be enabled by setting [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) non zero.
+
+The minimum and maximum valid range for the laser must be set in the parameters [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) and [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX).
diff --git a/ja/uavcan/cuav_can_pmu.md b/ja/uavcan/cuav_can_pmu.md
new file mode 100644
index 000000000000..9b0ff94be464
--- /dev/null
+++ b/ja/uavcan/cuav_can_pmu.md
@@ -0,0 +1,69 @@
+# CAUV CAN PMU
+
+CAN PMU® is a high-precision [UAVCAN](../uavcan/README.md) power module developed by CUAV®. It runs the CUAV ITT compensation algorithm, which enables drones to get the battery data more accurately.
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu.jpg)
+
+It is recommended for use in large commercial vehicles, but might also be used for research vehicles.
+
+## Specifications
+
+- **Processor:** STM32F412
+- **Voltage input**: 6~62V\(2-15S\)
+- **Max current:** 110A
+- **Voltage accuracy:** ±0.05V
+- **Current accuracy:** ±0.1A
+- **Resolution:** 0.01A/V
+- **Max output power:** 6000W/90S
+- **Max stable power:** 5000W
+- **Power port output:** 5.4V/5A
+- **Protocol:** UAVCAN
+- **Operating temp:** -20~+100
+- **Firmware upgrade:** Supported.
+* **Calibration:** Not needed.
+* **Interface Type:**
+ - **IN/OUT:** XT90\(Cable)/Amass 8.0\(Module)
+ - **Power port:** 5025850670
+ - **CAN:** GHR-04V-S
+- **Appearance:**
+ - **Size:** 46.5mm \* 38.5mm \* 22.5mm
+ - **Weight:** 76g
+
+## Purchase
+
+- [CUAV store](https://store.cuav.net/index.php)
+- [CUAV aliexpress ](https://www.aliexpress.com/item/4000369700535.html)
+
+## Pinouts
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en.png)
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en2.png)
+
+## Connection
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_connection_en.png)
+
+The connection steps are:
+* Connect the flight control CAN1/2 and the module CAN interface.
+* Connect the V5 series power cable to the V5 Flight Control Power2 (if other flight controllers are connect to the Power interface) and the module Power interface.
+
+## Enable CAN PMU
+
+Set the following parameters in the *QGroundControl* [parameter list](../advanced_config/parameters.md) and then restart:
+
+* `UAVCAN_ENABLE`: set to: *Sensors Automatic Config*
+
+ ![qgc set](../../assets/hardware/power_module/cuav_can/qgc_set_en.png)
+
+# Package Contents
+
+![CAN PMU list](../../assets/hardware/power_module/cuav_can/can_pmu_list.png)
+
+## Further Information
+
+[CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf)
+
+[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs)
+
+[UAVCAN](https://new.uavcan.org/)
\ No newline at end of file
diff --git a/ja/uavcan/developer.md b/ja/uavcan/developer.md
new file mode 100644
index 000000000000..010f77ae8766
--- /dev/null
+++ b/ja/uavcan/developer.md
@@ -0,0 +1,28 @@
+# UAVCAN Development
+
+This topic/section has information that is relevant to developers who want to add support for new [UAVCAN](http://uavcan.org) hardware to the PX4 Autopilot.
+
+:::note
+[Hardware > UAVCAN Peripherals](../uavcan/README.md) contains information about using existing/supported UAVCAN components with PX4.
+:::
+
+## Upgrading Node Firmware
+
+The PX4 middleware will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied. The process and requirements are described on the [UAVCAN Firmware](../uavcan/node_firmware.md) page.
+
+### Debugging with Zubax Babel
+
+A great tool to debug the transmission on the UAVCAN bus is the [Zubax Babel](https://zubax.com/products/babel) in combination with the [GUI tool](http://uavcan.org/GUI_Tool/Overview/).
+
+They can also be used independently from Pixhawk hardware in order to test a node or manually control UAVCAN enabled ESCs.
+
+
+## Useful Links
+
+- [UAVCAN Bootloader](../uavcan/bootloader_installation.md)
+- [UAVCAN Firmware Upgrades](../uavcan/node_firmware.md)
+- [Home page](http://uavcan.org) (uavcan.org)
+- [Specification](https://uavcan.org/specification/) (uavcan.org)
+- [Implementations and tutorials](http://uavcan.org/Implementations) (uavcan.org)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+
diff --git a/ja/uavcan/escs.md b/ja/uavcan/escs.md
new file mode 100644
index 000000000000..fb495d595843
--- /dev/null
+++ b/ja/uavcan/escs.md
@@ -0,0 +1,205 @@
+# UAVCAN ESCs (Motor Controllers)
+
+PX4 supports [UAVCAN](../uavcan/README.md) ESCs. These have a number of advantages over [PWM ESCs](../peripherals/pwm_escs_and_servo.md):
+- UAVCAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
+- The bus is bi-directional, enabling health monitoring and diagnostics.
+- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other UAVCAN peripherals.
+- Setup is easier as you configure ESC numbering by manually spinning each motor (for most types of UAVCAN ESCs).
+
+
+
+
+
+## PX4 Supported ESC
+
+PX4 is compatible with any/all UAVCAN ESCs (UAVCAN is generally speaking a plug'n'play protocol).
+
+:::note
+At time of writing PX4 supports UAVCAN v0 (not v1.0).
+:::
+
+The only difference between UAVCAN ESCs from a setup perspective is that the physical connectors and the software tools used to configure the motor order and direction may be different.
+
+
+Some popular UAVCAN ESC firmware/products include:
+- [Sapog](https://github.com/PX4/sapog#px4-sapog) firmware; an advanced open source sensorless PMSM/BLDC motor controller firmware designed for use in propulsion systems of electric unmanned vehicles.
+ - [Zubax Orel 20](https://zubax.com/products/orel_20)
+ - [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+- [Mitochondrik](https://zubax.com/products/mitochondrik) - integrated sensorless PMSM/BLDC motor controller chip (used in ESCs and integrated drives)
+ - [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+- [Myxa](https://zubax.com/products/myxa) - High-end PMSM/BLDC motor controller (FOC ESC) for light unmanned aircraft and watercraft.
+- [VESC Project ESCs](https://vesc-project.com/) (see also [Benjamin Vedder's blog](http://vedder.se) - project owner)
+- [OlliW’s UC4H ESC-Actuator Node](http://www.olliw.eu/2017/uavcan-for-hobbyists/#chapterescactuator)
+- A number of others are [listed here](https://forum.uavcan.org/t/uavcan-esc-options/452/3?u=pavel.kirienko)
+
+:::note
+This list is *not exhaustive/complete*. If you know of another ESC, please add it to the list!
+:::
+
+## Purchase
+
+Sapog-based ESCs:
+- [Zubax Orel 20](https://zubax.com/products/orel_20)
+- [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+
+Mitochondrik based drives and ESC:
+- [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+
+:::note
+There are many other commercially available ESCs; please add new links as you find them!
+:::
+
+
+
+
+
+## Wiring/Connections
+
+Connect all of the on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes. The order in which the ESCs are connected/chained does not matter.
+
+For more information see [UAVCAN > Wiring](../uavcan/README.md#wiring).
+
+:::note
+All UAVCAN ESCs share the same connection architecture/are wired the same way. Note however that the actual connectors differ (e.g. *Zubax Orel 20* and *Holybro Kotleta20* use Dronecode standard connectors (JST-GH 4 Pin) - while VESCs do not).
+:::
+
+
+## PX4 Configuration
+
+In order to use a UAVCAN ESC with PX4 you will need to enable the UAVCAN driver:
+1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller) and connect *QGroundControl*.
+1. Navigate to the **Vehicle Setup > Parameters** screen. :::note [Parameters](../advanced_config/parameters.md) explains how to find and set parameters.
+:::
+1. Set [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to the value *Sensors and Motors* (3) and then reboot the flight controller. This enables automatic enumeration of the motors (ESC) as described in the [next section](#esc-setup).
+1. (Optional) Set [UAVCAN_ESC_IDLT](../advanced_config/parameter_reference.md#UAVCAN_ESC_IDLT) to 1 in order to ensure that the motors are always running at least at the idle throttle while the system is armed. :::note Some systems will not benefit from this behavior, e.g. glider drones).
+:::
+
+
+## ESC Setup
+
+While UAVCAN devices are generally *plug'n'play* you will still need to enumerate (number) each of the ESC used in your system and set their direction so that they can be identified/controlled by PX4.
+
+:::note
+The ESC index and direction must match/map to the [Airframe Reference](../airframes/airframe_reference.md) for the vehicle type. ESC indexes from 0-7 map to MAIN 1-8, while ESC indexes 8-15 map to AUX 1-8.
+:::
+
+The mechanism for enumerating each type of UAVCAN ESC is different (look up the instructions in your ESC's manual). Setup information for some UAVCAN ESCs is provided below.
+
+
+### Sapog ESC Enumeration using QGroundControl
+
+This section shows how to enumerate any [Sapog-based](https://github.com/PX4/sapog#px4-sapog)-based ESCs "automatically" using *QGroundControl*.
+
+:::tip
+You can skip this section if there is only one ESC in your setup, because the ESC index is already set to zero by default.
+:::
+
+To enumerate the ESC:
+1. Power the vehicle with a battery and connect to *QGroundControl*
+1. Navigate to **Vehicle Setup > Power** in QGC.
+1. Start the process of ESC auto-enumeration by pressing the **Start Assignment** button, as shown on the screenshot below.
+
+ ![QGC - UAVCAN ESC auto-enumeration](../../assets/peripherals/esc_qgc/qgc_uavcan_settings.jpg)
+
+ You will hear a sound indicating that the flight controller has entered the ESC enumeration mode.
+1. Manually turn each motor in the correct direction of its rotation (as specified in the [Airframe Reference](../airframes/airframe_reference.md)), starting from the first motor and finishing with the last motor. Each time you turn a motor, you should hear a confirmation beep.
+
+:::note
+Make sure to turn each of the motors in the correct direction, as the ESC will automatically learn and remember the direction (i.e. motors that spin clockwise during normal operation must also be turned clockwise during enumeration).
+:::
+
+1. After the last motor is enumerated, the confirmation sound should change to indicate that the enumeration procedure is complete.
+1. Reboot PX4 and the Sapog ESCs to apply the new enumeration IDs.
+
+The following video demonstrates the process:
+
+@[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ)
+
+### Manual ESC Enumeration using Sapog
+
+:::tip
+We recommend automated [Sapog ESC Enumeration using QGroundControl](#sapog-esc-enumeration-using-qgroundcontrol) shown above rather than manual enumeration (as it is easier and safer).
+:::
+
+You can manually configure the ESC index and direction using the [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/). This assigns the following Sapog configuration parameters for each enumerated ESC:
+- `esc_index`
+- `ctl_dir`
+
+:::note
+See [Sapog reference manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf) for more information about the parameters.
+:::
+
+### Myxa ESC Setup
+
+Motor enumeration for Myxa [Telega-based ESCs](https://zubax.com/products/telega) is usually performed using the [Kucher tool](https://files.zubax.com/products/com.zubax.kucher/) (or less "GUI-friendly" [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/)).
+
+There is some guidance here: [Quick start guide for Myxa v0.1](https://forum.zubax.com/t/quick-start-guide-for-myxa-v0-1/911) (Zubax blog).
+
+
+### VESC ESC Setup
+
+For [VESC ESCs](https://vesc-project.com/) the preferred tool for motor enumeration is the [VESC tool](https://vesc-project.com/vesc_tool). In addition to the normal motor configuration that you will have to setup in the VESC tool, you will also need to properly setup the app configuration. The recommended app setup is as follows:
+
+| Parameter | Option |
+| ----------------------- | ---------------------- |
+| App to use | `No App` |
+| VESC ID | `1,2,...` |
+| Can Status Message Mode | `CAN_STATUS_1_2_3_4_5` |
+| CAN Baud Rate | `CAN_BAUD_500K` |
+| CAN Mode | `UAVCAN` |
+| UAVCAN ESC Index | `0,1,...` |
+
+
+VESC ID should have the same motor numbering as in PX4 convention, starting at `1` for top-right motor, `2` for bottom-left motor etc. However the `UAVCAN ESC Index` starts from `0`, and as such it is always one index lower than the `VESC ID`. For example, in a quadcopter the bottom left motor will have `VESC ID = 2` and `UAVCAN ESC Index = 1`.
+
+Finally the `CAN Baud Rate` must match the value set in [UAVCAN_BITRATE](../advanced_config/parameter_reference.md#UAVCAN_BITRATE).
+
+
+## Troubleshooting
+
+#### Motors not spinning when armed
+
+If the PX4 Firmware arms but the motors do not start to rotate, check that parameter `UAVCAN_ENABLE=3` to use UAVCAN ESCs. If the motors do not start spinning before thrust is increased, check `UAVCAN_ESC_IDLT=1`.
+
+#### UAVCAN devices dont get node ID/Firmware Update Fails
+
+PX4 requires an SD card for UAVCAN node allocation and during firmware update (which happen during boot). Check that there is a (working) SD card present and reboot.
+
+
+## Further Information
+
+- [PX4/Sapog](https://github.com/PX4/sapog#px4-sapog) (Github)
+- [Sapog v2 Reference Manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+- [Using Sapog based ESC with PX4](https://kb.zubax.com/display/MAINKB/Using+Sapog-based+ESC+with+PX4) (Zubax KB)
+
diff --git a/ja/uavcan/node_firmware.md b/ja/uavcan/node_firmware.md
index 241f486e2c51..35b231c9431d 100644
--- a/ja/uavcan/node_firmware.md
+++ b/ja/uavcan/node_firmware.md
@@ -1,5 +1,11 @@
# UAVCAN Firmware Upgrading
+PX4 will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied.
+
+:::warning UAVCAN
+devices typically ship with appropriate firmware preinstalled. These instructions are primarily needed when developing UAVCAN devices.
+:::
+
## Vectorcontrol ESC Codebase (Pixhawk ESC 1.6 and S2740VC)
Download the ESC code:
diff --git a/ja/uavcan/pomegranate_systems_pm.md b/ja/uavcan/pomegranate_systems_pm.md
new file mode 100644
index 000000000000..fb28d03e56ab
--- /dev/null
+++ b/ja/uavcan/pomegranate_systems_pm.md
@@ -0,0 +1,55 @@
+# Pomegranate Systems Power Module
+
+![Module Image](../../assets/hardware/power_module/pomegranate_systems_pm/main_image.jpg)
+
+Digital Power Module with high resolution current integration, 5V/2A supply with power monitoring, single UAVCAN v0 CANbus interface, and an RGB status LED.
+
+Detailed setup, configuration, and troubleshooting information can be found on the [manufacturer's device home page](https://p-systems.io/product/power_module).
+
+## Specifications
+
+ - **Input Voltage:** 6-26V \(2-6S\)
+ - **Max Continuous Current:**
+ - **Benchtop:** 40A
+ - **Forced Cooling:** 100A
+ - **Max 5V Output Current:** 2A
+ - **Voltage Resolution:** 0.04 ΔV
+ - **Current Resolution:**
+ - **Primary / Battery Bus:** 0.02 ΔA
+ - **5V bus:** 0.001 ΔA
+ - **CANbus Termination:** Electronic (on by default)
+ - **MCU:** STM32 F302K8U
+ - **Firmware:** [Open Source](https://bitbucket.org/p-systems/firmware/)
+ - **Electrical Interface:**
+ - **Power:** Solder pads or XT60PW (right angle, board-mounted connectors)
+ - **CANbus** Dual JST GH-4 (standard UAVCAN micro-connector)
+ - **I2C / Serial:** JST GH-5
+ - **5V Output:** Solder pads or CANbus / I2C connectors
+ - **Device Mass:**
+ - **Without Connectors:** 9g
+ - **With XT60PW Connectors:** 16g
+
+
+ ![Dimensions](../../assets/hardware/power_module/pomegranate_systems_pm/mechanical.png)
+
+## Configuration
+
+ 1. Enable UAVCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`.
+ 2. Set the following module parameters using the [Mavlink console](https://docs.qgroundcontrol.com/en/analyze_view/mavlink_console.html):
+ * Battery capacity in mAh: `battery_capacity_mAh`
+ * Battery voltage when *full*: `battery_full_V`,
+ * Battery voltage when *empty*: `battery_empty_V`
+ * Turn on current integration: `enable_current_track`
+ * (optional) Turn Off CANbus termination resistor :`enable_can_term`
+
+**Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands:
+
+```
+uavcan param set 125 battery_capacity_mAh 5000
+uavcan param set 125 battery_full_V 12.5
+uavcan param set 125 battery_empty_V 11.2
+uavcan param set 125 enable_current_track 1
+uavcan param save 125
+```
+
+See [device configuration page](https://p-systems.io/product/power_module/configuration) for a full list of parameters.
diff --git a/ko/SUMMARY.md b/ko/SUMMARY.md
index b82f257fd315..f69f009c5ca1 100644
--- a/ko/SUMMARY.md
+++ b/ko/SUMMARY.md
@@ -12,7 +12,8 @@
* [LED 신호의 의미](getting_started/led_meanings.md)
* [음향/소리의 의미](getting_started/tunes.md)
* [비행 사전 점검](flying/pre_flight_checks.md)
- * [비행 기록](getting_started/flight_reporting.md)
+ * [Payloads & Cameras](payloads/README.md)
+ * [Flight Reporting](getting_started/flight_reporting.md)
* [조립 기초](assembly/README.md)
* [비행 컨트롤러 설치](assembly/mount_and_orient_controller.md)
* [진동 방지](assembly/vibration_isolation.md)
diff --git a/ko/flight_modes/acro_mc.md b/ko/flight_modes/acro_mc.md
index 09444cea37b7..eb325c2bf2a8 100644
--- a/ko/flight_modes/acro_mc.md
+++ b/ko/flight_modes/acro_mc.md
@@ -2,7 +2,7 @@
[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual)
-* 아크로 모드 *는 뒤집기, 롤 및 루프등과 같은 곡예 비행을 위한 RC 모드입니다.
+*아크로 모드*는 뒤집기, 롤 및 루프등과 같은 곡예 비행을 위한 RC 모드입니다.
롤, 피치 및 요 스틱은 각 축을 중심으로 한 각도 회전 속도를 제어하고 조절판은 직접 출력 믹서로 전달됩니다. 스틱이 중앙에 놓여지면 기체는 회전을 멈추지만 현재 방향 (측면, 반전 등)과 현재 모멘텀에 따라 움직입니다.
diff --git a/ko/flight_modes/altitude_fw.md b/ko/flight_modes/altitude_fw.md
index cf999104b47f..d10cbd87306d 100644
--- a/ko/flight_modes/altitude_fw.md
+++ b/ko/flight_modes/altitude_fw.md
@@ -1,44 +1,44 @@
# 고도 모드(고정익)
-[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual) [](../getting_started/flight_modes.md#altitude_only)
+[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual) [](../getting_started/flight_modes.md#altitude_only)
*고도* 비행모드는 사용자가 기체의 고도를 제어하거나 특정 고도를 유지하는것을 용이하게 합니다. 이 모드 하에서 바람이 있을 때 기체는 방향을 유지하지 않습니다.
-기체의 상승/하강률을 피치/엘리베이터 스틱을 이용하여 제어할 수 있습니다. Once centered the autopilot latches onto the current altitude and will maintain it during yaw/roll, and at any airspeed.
+기체의 상승/하강률을 피치/엘리베이터 스틱을 이용하여 제어할 수 있습니다. 일단 중앙에 위치하면 자동조종장치가 현재 고도에 고정되고 요/롤 및 모든 대기 속도에서 이 고도를 유지합니다.
-The throttle input controls airspeed. Roll and pitch are angle-controlled (so it is impossible to roll over or loop the vehicle).
+스로틀 입력은 대기 속도를 제어합니다. 롤과 피치는 각도로 제어됩니다 (따라서 차량을 롤오버하거나 루프할 수 없습니다).
-When all remote control inputs are centered (no roll, pitch, yaw, and ~50% throttle) the aircraft will return to straight, level flight (subject to wind) and keep its current altitude.
+모든 원격 제어 입력이 중앙에 있을 때 (롤, 피치, 요 및 ~ 50 % 스로틀 없음) 기체는 직선, 수평 비행 (바람에 따라)으로 돌아가 현재 고도를 유지합니다.
-The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)).
+아래 다이어그램은 모드 동작을 시각적으로 보여줍니다 ([모드 2 송신기](../getting_started/rc_transmitter_receiver.md#transmitter_modes)의 경우).
-![Altitude Control FW](../../assets/flight_modes/altitude_control_mode_fw.png)
+![고정익 고도 제어](../../assets/flight_modes/altitude_control_mode_fw.png)
-## Technical Summary
+## 기술 요약
-RC/manual mode like Stabilized mode but with altitude stabilization (centered sticks put vehicle into straight and level flight and maintain current altitude). The vehicle course is not maintained, and can drift due to wind.
+RC 수동 모드는 안정화 모드와 같지만 고도 안정화를 사용합니다 (중앙 스틱은 차량을 직선 및 수평 비행 상태로 만들고 현재 고도를 유지합니다). 기체의 경로가 유지되지 않고 바람에 표류할 수 있습니다.
-* Centered Roll/Pitch/Yaw inputs (inside deadband):
- * Autopilot levels vehicle/wings and maintains altitude.
- * Throttle stick controls the airspeed of the aircraft if an airspeed sensor is connected. Without an airspeed sensor the user cannot control throttle (in which case the vehicle will fly level at cruise throttle ([FW_THR_CRUISE](../advanced_config/parameter_reference.md#FW_THR_CRUISE)), increasing or decreasing throttle as needed to climb or descend).
-* Outside center:
- * Pitch stick controls altitude.
- * Throttle stick controls the airspeed of the aircraft (as for centered Roll/Pitch/Yaw inputs).
- * Roll stick controls roll angle. Autopilot will maintain [coordinated flight](https://en.wikipedia.org/wiki/Coordinated_flight). This is same as in [Stabilized mode](../flight_modes/stabilized_fw.md).
- * Yaw stick actuates the rudder (signal will be added to the one calculated by the autopilot to maintain [coordinated flight](https://en.wikipedia.org/wiki/Coordinated_flight)). This is same as in [Stabilized mode](../flight_modes/stabilized_fw.md).
+* 중앙 롤/피치/요 입력 (데드 밴드 내부) :
+ * 자동조종장치는 기체/날개를 수평으로 유지하고 고도를 유지합니다.
+ * 스로틀 스틱은 대기 속도 센서가 연결된 경우 기체의 대기 속도를 제어합니다. 대기 속도 센서가 없으면 사용자는 스로틀을 제어할 수 없습니다 (이 경우 기체는 크루즈 스로틀 ([FW_THR_CRUISE](../advanced_config/parameter_reference.md#FW_THR_CRUISE))에서 수평으로 날아 오르거나 내리는 데 필요한만큼 스로틀을 높이거나 낮춥니 다).
+* 센터 외부:
+ * 피치 스틱은 고도를 제어합니다.
+ * 스로틀 스틱은 기체의 대기 속도를 제어합니다 (중앙 롤/피치/요 입력의 경우).
+ * 롤 스틱은 롤 각도를 제어합니다. 자동 조종 장치는 [조정 비행](https://en.wikipedia.org/wiki/Coordinated_flight)을 유지합니다. 이것은 [안정화 모드](../flight_modes/stabilized_fw.md)와 동일합니다.
+ * 요 스틱은 방향타를 작동합니다 ([조정 비행](https://en.wikipedia.org/wiki/Coordinated_flight)을 유지하기 위해 자동 조종 장치에 의해 계산된 신호에 신호가 추가됩니다). 이것은 [안정화 모드](../flight_modes/stabilized_fw.md)와 동일합니다.
:::note
-* Manual input is required (RC controller, or gamepad/thumbsticks through MAVLink).
-* The altitude is normally measured using a barometer, which may become inaccurate in extreme weather conditions. Vehicles that include a LIDAR/range sensor will be able to control altitude with greater reliability and accuracy.
+* 수동 입력이 필요합니다 (RC 컨트롤러 또는 MAVLink를 통한 게임 패드/엄지 스틱).
+* 고도는 일반적으로 기압계로 측정되며 극단적인 기상 조건에서는 정확하지 않을 수 있습니다. LIDAR/거리 센서가 장착된 기체는 높은 정확도로 고도를 제어할 수 있습니다.
:::
-## Parameters
+## 매개 변수
-The mode is affected by the following parameters:FW_MAN_P_MAX
+이 모드는 아래의 매개 변수의 영향을받습니다.FW_MAN_P_MAX
- Max pitch for manual control in attitude stabilized mode. Default: 45 degrees.
+ 자세 안정화 모드에서 수동 제어를위한 최대 피치. 기본값: 45도.
|
@@ -46,7 +46,7 @@ The mode is affected by the following parameters:FW_MAN_R_MAX
- Max roll for manual control in attitude stabilized mode. Default: 45 degrees.
+ 자세 안정화 모드에서 수동 제어를 위한 최대 롤. 기본값: 45도.
|
@@ -54,7 +54,7 @@ The mode is affected by the following parameters:FW L1 Control
- The roll/yaw needed to maintain the commanded altitude and airspeed are also affected by the FW L1 Control parameters.
+ 명령된 고도 및 대기 속도를 유지하는 데 필요한 롤/요는 FW L1 제어 매개 변수의 영향을 받습니다.
|
@@ -104,6 +101,9 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -122,30 +122,36 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
-* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
-* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+* [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+* [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+* [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+* [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+* [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+* [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
Note:
* PX4 parses the above messages, but they are not necessary *acted* on. For example, some messages are vehicle-type specific.
-* PX4 generally does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) ).
+* PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* Not all messages/commands are exposed via *QGroundControl*.
-* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) (list generated in [this git changelist](https://github.com/PX4/PX4-Autopilot/commit/ca1f7a4a194c23303c23ca79b5905ff8bfb94c22)).
+* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-Please add an bug fix or PR if you find a missing/incorrect message.
+Please add an issue report or PR if you find a missing/incorrect message.
:::
## Inter-Waypoint Trajectory
PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).
-MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning.
+MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+![acc-rad](../../assets/flying/acceptance_radius_mission.png)
-Vehicles switch to the next waypoint as soon as they enter the acceptance radius.
+Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
-* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)
-* For FW the radius is defined by the "L1 distance".
+* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+* For FW the acceptance radius is defined by the "L1 distance".
* The L1 distance is computed from two parameters: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) and [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD), and the current ground speed.
* By default, it's about 70 meters.
* The equation is: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/ko/flight_modes/orbit.md b/ko/flight_modes/orbit.md
index 82da6e1e5376..7a93d1a1fa9e 100644
--- a/ko/flight_modes/orbit.md
+++ b/ko/flight_modes/orbit.md
@@ -1,49 +1,49 @@
# 궤도 모드(멀티콥터)
-[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_position_fixed)
+[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_position_fixed)
-*궤도* 유도 비행 모드를 사용하면 멀티콥터 (또는 멀티 콥터 모드의 VTOL)가 항상 중앙을 향하도록 [기본](https://mavlink.io/en/messages/common.html#ORBIT_YAW_BEHAVIOUR) 요잉으로 원을 그리며 비행하도록 명령할 수 있습니다.
+*궤도* 유도 비행 모드를 사용하면 멀티콥터 (또는 멀티 콥터 모드의 VTOL)가 항상 중앙을 향하도록 [기본](https://mavlink.io/en/messages/common.html#ORBIT_YAW_BEHAVIOUR) 요잉으로 원을 그리는 비행하도록 명령할 수 있습니다.
-![Orbit Mode - MC](../../assets/flying/orbit.jpg)
+![궤도 모드 (멀티콥터)](../../assets/flying/orbit.jpg)
-*QGroundControl* (or other compatible GCS or MAVLink API) is *required* to enable the mode, and to set the center position, initial radius and altitude of the orbit. Once enabled the vehicle will fly as fast as possible to the closest point on the commanded circle trajectory and do a slow (1m/s) clockwise orbit on the planned circle, facing the center.
+모드를 활성화하고 궤도의 중심 위치, 초기 반경 및 고도를 설정하려면 *QGroundControl* (또는 기타 호환 가능한 GCS 또는 MAVLink API)이 *필요*합니다. 활성화되면 기체는 명령된 원 궤적에서 가장 가까운 지점까지 최대한 빠르게 비행하고 계획된 원에서 시계 방향으로 천천히 (1m / s) 궤도를 돌면서 중앙을 향합니다.
-Instructions for how to start an orbit can be found here: [FlyView > Orbit Location](https://docs.qgroundcontrol.com/en/FlyView/FlyView.html#orbit) (*QGroundControl* guide).
+궤도를 시작하는 방법에 대한 지침은 [FlyView > 궤도 위치](https://docs.qgroundcontrol.com/en/FlyView/FlyView.html#orbit) (*QGroundControl* 가이드)에서 찾을 수 있습니다.
-:::note
-The use of an RC control is *optional*. If no RC control is present the orbit will proceed as described above. RC control cannot be used to start the mode (if you switch to the mode via RC it will sit idle).
+:::note RC
+무선 조종기 사용은 *선택 사항*입니다. RC 제어가 없는 경우 궤도는 위에서 설명한 대로 진행됩니다. RC 제어를 사용하여 모드를 시작할 수 없습니다 (RC를 통해 모드로 전환하면 유휴 상태가됩니다).
:::
-RC control can be used to change the orbit altitude, radius, speed, and orbit direction:
+RC 제어를 사용하여 궤도 고도, 반경, 속도 및 궤도 방향을 변경할 수 있습니다.
-- **Left stick:**
- - *up/down:* controls speed of ascent/descent, as in [Position mode](../flight_modes/position_mc.md). When in center deadzone, altitude is locked.
- - *left/right:* no effect.
-- **Right stick:**
- - *left/right:* controls acceleration of orbit in clockwise/counter-clockwise directions. When centered the current speed is locked.
- - Maximum velocity is 10m/s and further limited to keep the centripetal acceleration below 2m/s^2.
- - *up/down:* controls orbit radius (smaller/bigger). When centered the current radius is locked.
- - Minimum radius is 1m. Maximum radius is 100m.
+- **왼쪽 스틱:**
+ - *위/아래 :*는 [위치 모드](../flight_modes/position_mc.md)에서와 같이 상승/하강 속도를 제어합니다. 중앙 데드 존에 있으면 현재 고도가 유지됩니다.
+ - *왼쪽/오른쪽 :* 효과 없음.
+- **오른쪽 스틱:**
+ - *좌/우* 시계 방향/반시계 방향으로 궤도의 가속도를 제어합니다. 중앙에 위치하면 현재 속도가 고정됩니다.
+ - 최대 속도는 10m/s이며 구심 가속도를 2m/s ^ 2 미만으로 유지하도록 제한됩니다.
+ - *상/하* 궤도 반경을 제어합니다 (더 작게 / 더 크게). 중앙에 위치하면 현재 반경이 유지됩니다.
+ - 최소 반경은 1m 입니다. 최대 반경은 1m 입니다.
-The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)).
+아래 다이어그램은 모드 동작을 시각적으로 보여줍니다 ([모드 2 송신기](../getting_started/rc_transmitter_receiver.md#transmitter_modes)의 경우).
-![Orbit Mode - MC](../../assets/flight_modes/orbit_MC.png)
+![궤도 모드 (멀티콥터)](../../assets/flight_modes/orbit_MC.png)
-The mode can be stopped by switching to any other flight mode (using RC or QGC).
+다른 비행 모드 (RC 또는 QGC 사용)로 전환하여 모드를 중지할 수 있습니다.
-## Parameters/Limits
+## 매개 변수 / 제약 사항
-There are no orbit mode-specific parameters.
+궤도 모드 별 매개 변수는 없습니다.
-The following limits are hard coded:
+다음의 제약 사항들은 하드 코딩되어 있습니다.
-- Initial/default rotation is 1 m/s in a clockwise direction.
-- The maximum acceleration is limited to 2 m/s^2, with priority on keeping the commanded circle trajectory rather than commanded ground speed (i.e. the vehicle will slow down in order to achieve the correct circle if the acceleration exceeds 2m/s^2).
-- Maximum radius is 100m.
+- 초기 기본 회전은 시계 방향으로 1m/s 입니다.
+- 최대 가속도는 2m/s ^ 2로 제한되며, 명령된 지면 속도보다는 명령된 원 궤적을 유지하는 것이 우선입니다 (즉, 가속이 2m/s^ 2를 초과하면 정확한 원을 달성하기 위해 기체가 감속됩니다).
+- 최대 반경은 1m 입니다.
-## MAVLink Messages (Developers)
+## MAVLink 메시지 (개발자)
-Orbit mode uses the following MAVLink commands:
+궤도 모드는 다음 MAVLink 명령을 사용합니다.
-- [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) - Start an orbit with specified center point, radius, direction, altitude, speed and [yaw direction](https://mavlink.io/en/messages/common.html#ORBIT_YAW_BEHAVIOUR) (vehicle defaults to faceing centre of orbit).
-- [ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) - Orbit status emitted during orbit to update GCS of current orbit parameters (these may be changed by the RC controller).
\ No newline at end of file
+- [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT)-지정된 중심점, 반경, 방향, 고도, 속도 및 [요 방향](https://mavlink.io/en/messages/common.html#ORBIT_YAW_BEHAVIOUR)으로 궤도를 시작합니다 (차량은 기본적으로 궤도 중심을 향함).
+- [ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) - 현재 궤도 매개 변수의 GCS를 업데이트하기 위해 궤도 중에 방출되는 궤도 상태입니다 (RC 컨트롤러에 의해 변경 될 수 있음).
\ No newline at end of file
diff --git a/ko/flight_modes/position_fw.md b/ko/flight_modes/position_fw.md
index a060e41bb6e3..095694fcb14c 100644
--- a/ko/flight_modes/position_fw.md
+++ b/ko/flight_modes/position_fw.md
@@ -1,25 +1,25 @@
-# Position Mode (Fixed Wing)
+# 위치 모드(고정익)
-[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual) [](../getting_started/flight_modes.md#key_position_fixed)
+[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual) [](../getting_started/flight_modes.md#key_position_fixed)
-*Position mode* is an easy-to-fly RC mode in which, when the sticks are released/centered, the vehicle will level and fly a straight line ground track in the current direction — compensating for wind and other forces.
+*위치모드*는 스틱을 놓거나 중앙에 놓을 때 기체가 바람 등의 외부 요인에도 지면 트랙에 대하여 수평과 직진 방향의 비행이 용이한 RC 모드입니다.
-The throttle determines airspeed (at 50% throttle the aircraft will hold its current altitude with a preset cruise speed). Pitch is used to ascend/descend. Roll, pitch and yaw are all angle-controlled (so it is impossible to roll over or loop the vehicle).
+스로틀은 대기 속도를 결정합니다 (스로틀 50 %에서 기체는 사전 설정된 순항 속도로 현재 고도를 유지합니다). 피치는 상승/하강하는 데 사용됩니다. 롤, 피치 및 요는 모두 각도로 제어됩니다 (따라서 차량을 롤오버하거나 루프 할 수 없음).
:::tip
-Position mode is the safest fixed-wing manual mode for new fliers.
+위치 모드는 고정익 초보 비행자에게 가장 안전한 수동 모드입니다.
:::
-The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)).
+아래 다이어그램은 모드 동작을 시각적으로 보여줍니다 ([모드 2 송신기](../getting_started/rc_transmitter_receiver.md#transmitter_modes)의 경우).
-![FW Position Mode](../../assets/flight_modes/position_FW.png)
+![고정익 위치 모드](../../assets/flight_modes/position_FW.png)
-## Technical Description
+## 기술적 설명
-Centered RC RPY sticks – gives level flight that follows a straight line ground track in the current direction against any wind.
+중앙 RC RPY 스틱 – 바람에 대항하여 현재 방향으로 직선 지상 트랙을 따라가는 수평 비행.
-## Parameters
+## 매개 변수
-| Parameter | Description |
-| --------- | ----------- |
-| | |
\ No newline at end of file
+| 매개 변수 | 설명 |
+| ------ | -- |
+| | |
\ No newline at end of file
diff --git a/ko/flight_modes/stabilized_fw.md b/ko/flight_modes/stabilized_fw.md
index d14e69464ae2..8a76e1e24a05 100644
--- a/ko/flight_modes/stabilized_fw.md
+++ b/ko/flight_modes/stabilized_fw.md
@@ -1,32 +1,32 @@
-# Stabilized Mode (Fixed Wing)
+# 안정화 모드 (고정익)
-[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual)
+[](../getting_started/flight_modes.md#key_difficulty) [](../getting_started/flight_modes.md#key_manual)
-*Stabilized mode* puts the vehicle into straight and level flight when the RC sticks are centered, maintaining the horizontal posture against wind (but not vehicle heading and altitude).
+* 안정화 모드 *는 RC 스틱이 중앙에있을 때 차량을 똑바로 수평 비행으로 전환하여 바람에 대한 수평 자세를 유지합니다 (차량 방향 및 고도 제외).
-The vehicle climb/descends based on pitch input and performs a coordinated turn if the roll/pitch sticks are non-zero. Roll and pitch are angle controlled (you can't roll upside down or loop).
+기체는 피치 입력을 기반으로 상승/하강하며, 롤/피치 스틱이 0이 아닌 경우 회전합니다. 롤과 피치는 각도가 제어됩니다 (거꾸로 굴리거나 반복할 수 없음).
:::tip
-*Stabilized mode* is much easier to fly than [Manual mode](../flight_modes/manual_fw.md) because you can't roll or flip it, and it is easy to level the vehicle by centering the control sticks.
+*안정화 모드*는 굴리거나 뒤집을 수 없기 때문에 [수동 모드](../flight_modes/manual_fw.md)보다 비행하기 훨씬 쉽고 조종 스틱을 중앙에 배치하여 기체의 수평을 유지가 용이합니다.
:::
-The vehicle will glide if the throttle is lowered to 0% (motor stops). In order to perform a turn the command must beheld throughout the maneuver because if the roll is released the plane will stop turning and level itself (the same is true for pitch and yaw commands).
+스로틀을 0%로 낮추면 기체가 미끄러집니다 (모터 정지). 회전을 수행하기 위해 명령은 기동 내내 지켜 져야합니다. 롤이 풀리면 비행기는 회전을 멈추고 스스로 수평을 맞출 것입니다 (피치 및 요 명령도 마찬가지입니다).
-The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)).
+아래 다이어그램은 모드 동작을 시각적으로 보여줍니다 ([모드 2 송신기](../getting_started/rc_transmitter_receiver.md#transmitter_modes)의 경우).
-![FW Manual Flight](../../assets/flight_modes/manual_stabilized_FW.png)
+![고정익 수동 비행](../../assets/flight_modes/manual_stabilized_FW.png)
-## Technical Description
+## 기술적 설명
-RC/manual mode where centered RP sticks level vehicle.
+중앙 RP가 기체의 수평을 고정하는 RC 수동 모드.
-* Centered sticks put vehicle into straight and level flight. The vehicle course and altitude are not maintained, and can drift due to wind.
-* If roll/pitch sticks are non-zero the vehicle does a coordinated turn (manual yaw input is added to rudder control input to control sideslip).
+* 중앙 스틱은 기체를 직선 및 수평 비행 상태로 만듭니다. 기체의 고도와 경로가가 유지되지 않고 바람에 표류할 수 있습니다.
+* 롤/피치 스틱이 0이 아닌 경우 차량은 조정된 회전을 수행합니다 (사이드 슬립을 제어하기 위해 수동 요 입력이 방향타 제어 입력에 추가됨).
-## Parameters
+## 매개 변수
-| Parameter | Description |
-| --------- | ----------- |
-| | |
+| 매개 변수 | 설명 |
+| ------ | -- |
+| | |
\ No newline at end of file
diff --git a/ko/flying/missions.md b/ko/flying/missions.md
index 4cbc6354e2f2..815c27de7226 100644
--- a/ko/flying/missions.md
+++ b/ko/flying/missions.md
@@ -26,8 +26,24 @@
고정익과 같이 요 및 이동 방향을 제어할 수 없는 기체는 요 설정을 무시합니다.
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## 임무 비행
-임무가 업로드되면 비행 보기로 전환합니다. 미션은 진행 상황을 쉽게 추적하도록 표시됩니다. 이보기에서 미션을 수정할 수 없습니다.
+Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
-![임무 비행](../../assets/flying/flying_mission.jpg)
\ No newline at end of file
+![flying-mission](../../assets/flying/flying_mission.jpg)
\ No newline at end of file
diff --git a/ko/getting_started/README.md b/ko/getting_started/README.md
index 8144279ba781..6f30925f0b64 100644
--- a/ko/getting_started/README.md
+++ b/ko/getting_started/README.md
@@ -14,4 +14,6 @@ PX4를 이용한 기체 조립 및 조종 방법의 기본 개념을 설명합
[비행 모드](../getting_started/flight_modes.md) — 수동 및 자율 비행을 위한 비행 모드
-[비행 기록](../getting_started/flight_reporting.md) — 비행 기록 다운로드/디버깅/분석
\ No newline at end of file
+[Payloads & Cameras](../payloads/README.md)
+
+[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/ko/payloads/README.md b/ko/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/ko/payloads/README.md
+++ b/ko/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/ko/releases/1.12.md b/ko/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/ko/releases/1.12.md
+++ b/ko/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/ko/ros/ros2_offboard_control.md b/ko/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/ko/ros/ros2_offboard_control.md
+++ b/ko/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).
diff --git a/ko/sensor/rangefinders.md b/ko/sensor/rangefinders.md
index 3789dae1870e..a1c9d5a11ac5 100644
--- a/ko/sensor/rangefinders.md
+++ b/ko/sensor/rangefinders.md
@@ -48,7 +48,7 @@ The [Lanbao PSK-CM8JL65-CC5 ToF Infrared Distance Measuring Sensor](../sensor/cm
### Avionics Anonymous UAVCAN Laser Altimeter Interface
-The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../sensor/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the UAVCAN bus, a more robust interface than I2C.
+The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../uavcan/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the [UAVCAN](../uavcan/README.md) bus, a more robust interface than I2C.
diff --git a/ko/uavcan/avanon_laser_interface.md b/ko/uavcan/avanon_laser_interface.md
new file mode 100644
index 000000000000..863ab645051b
--- /dev/null
+++ b/ko/uavcan/avanon_laser_interface.md
@@ -0,0 +1,57 @@
+# Avionics Anonymous Laser Altimeter UAVCAN Interface
+
+The [Avionics Anonymous Laser Altimeter Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/) allows a [number of common rangefinders](#supported_rangefinders) to be connected via the UAVCAN bus (this is a more robust interface than I2C).
+
+![Avionics Anonymous Laser Altimeter UAVCAN Interface](../../assets/hardware/sensors/avionics_anon_uavcan_alt_interface/avionics_anon_altimeter_uavcan_interface.jpg)
+
+## Where to Buy
+
+* [AvAnon Laser Interface](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/)
+
+
+## Supported Rangefinders
+
+A full list supported rangefinders can be found on the link above.
+
+At time of writing the following rangefinders are supported:
+
+- Lightware SF30/D
+- Lightware SF10/a
+- Lightware SF10/b
+- Lightware SF10/c
+- Lightware SF11/c
+- Lightware SF/LW20/b
+- Lightware SF/LW20/c
+
+
+## Pinouts
+
+### CAN Connector
+| Pin | Name | Description |
+| --- | -------- | ----------------------------------------------------------------------------------- |
+| 1 | POWER_IN | Power Supply. 4.0-5.5V supported, but must also be compatible with connected laser. |
+| 2 | TX/SCL | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+### Laser Connector
+
+| Pin | Name | Description |
+| --- | --------- | -------------------------------------- |
+| 1 | POWER_OUT | Filtered power at the supply voltage. |
+| 2 | CAN+ | TX for serial mode, Clock for I2C mode |
+| 3 | RX/SDA | RX for serial mode, Data for I2C mode |
+| 4 | GND | Signal/power ground. |
+
+
+## Wiring
+
+The rangefinder (laser) is connected to the AvAnon interface board, which is connected to one of the CAN ports on your autopilot. The wiring is as per the pinout above, or the necessary cables can be purchased to connect to your system right out of the box. These are available at the links [here](https://www.tindie.com/products/avionicsanonymous/uavcan-laser-altimeter-interface/).
+
+The interface board provides a filtered power output for the laser, but does not provide its own regulation. Therefore the laser must be compatible with whatever voltage is supplied to the board.
+
+## Software Configuration
+
+UAVCAN must be enabled by setting [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) non zero.
+
+The minimum and maximum valid range for the laser must be set in the parameters [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) and [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX).
diff --git a/ko/uavcan/cuav_can_pmu.md b/ko/uavcan/cuav_can_pmu.md
new file mode 100644
index 000000000000..9b0ff94be464
--- /dev/null
+++ b/ko/uavcan/cuav_can_pmu.md
@@ -0,0 +1,69 @@
+# CAUV CAN PMU
+
+CAN PMU® is a high-precision [UAVCAN](../uavcan/README.md) power module developed by CUAV®. It runs the CUAV ITT compensation algorithm, which enables drones to get the battery data more accurately.
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu.jpg)
+
+It is recommended for use in large commercial vehicles, but might also be used for research vehicles.
+
+## Specifications
+
+- **Processor:** STM32F412
+- **Voltage input**: 6~62V\(2-15S\)
+- **Max current:** 110A
+- **Voltage accuracy:** ±0.05V
+- **Current accuracy:** ±0.1A
+- **Resolution:** 0.01A/V
+- **Max output power:** 6000W/90S
+- **Max stable power:** 5000W
+- **Power port output:** 5.4V/5A
+- **Protocol:** UAVCAN
+- **Operating temp:** -20~+100
+- **Firmware upgrade:** Supported.
+* **Calibration:** Not needed.
+* **Interface Type:**
+ - **IN/OUT:** XT90\(Cable)/Amass 8.0\(Module)
+ - **Power port:** 5025850670
+ - **CAN:** GHR-04V-S
+- **Appearance:**
+ - **Size:** 46.5mm \* 38.5mm \* 22.5mm
+ - **Weight:** 76g
+
+## Purchase
+
+- [CUAV store](https://store.cuav.net/index.php)
+- [CUAV aliexpress ](https://www.aliexpress.com/item/4000369700535.html)
+
+## Pinouts
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en.png)
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_pinouts_en2.png)
+
+## Connection
+
+![CAN PMU](../../assets/hardware/power_module/cuav_can/can_pmu_connection_en.png)
+
+The connection steps are:
+* Connect the flight control CAN1/2 and the module CAN interface.
+* Connect the V5 series power cable to the V5 Flight Control Power2 (if other flight controllers are connect to the Power interface) and the module Power interface.
+
+## Enable CAN PMU
+
+Set the following parameters in the *QGroundControl* [parameter list](../advanced_config/parameters.md) and then restart:
+
+* `UAVCAN_ENABLE`: set to: *Sensors Automatic Config*
+
+ ![qgc set](../../assets/hardware/power_module/cuav_can/qgc_set_en.png)
+
+# Package Contents
+
+![CAN PMU list](../../assets/hardware/power_module/cuav_can/can_pmu_list.png)
+
+## Further Information
+
+[CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf)
+
+[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs)
+
+[UAVCAN](https://new.uavcan.org/)
\ No newline at end of file
diff --git a/ko/uavcan/developer.md b/ko/uavcan/developer.md
new file mode 100644
index 000000000000..010f77ae8766
--- /dev/null
+++ b/ko/uavcan/developer.md
@@ -0,0 +1,28 @@
+# UAVCAN Development
+
+This topic/section has information that is relevant to developers who want to add support for new [UAVCAN](http://uavcan.org) hardware to the PX4 Autopilot.
+
+:::note
+[Hardware > UAVCAN Peripherals](../uavcan/README.md) contains information about using existing/supported UAVCAN components with PX4.
+:::
+
+## Upgrading Node Firmware
+
+The PX4 middleware will automatically upgrade firmware on UAVCAN nodes if the matching firmware is supplied. The process and requirements are described on the [UAVCAN Firmware](../uavcan/node_firmware.md) page.
+
+### Debugging with Zubax Babel
+
+A great tool to debug the transmission on the UAVCAN bus is the [Zubax Babel](https://zubax.com/products/babel) in combination with the [GUI tool](http://uavcan.org/GUI_Tool/Overview/).
+
+They can also be used independently from Pixhawk hardware in order to test a node or manually control UAVCAN enabled ESCs.
+
+
+## Useful Links
+
+- [UAVCAN Bootloader](../uavcan/bootloader_installation.md)
+- [UAVCAN Firmware Upgrades](../uavcan/node_firmware.md)
+- [Home page](http://uavcan.org) (uavcan.org)
+- [Specification](https://uavcan.org/specification/) (uavcan.org)
+- [Implementations and tutorials](http://uavcan.org/Implementations) (uavcan.org)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+
diff --git a/ko/uavcan/escs.md b/ko/uavcan/escs.md
new file mode 100644
index 000000000000..fb495d595843
--- /dev/null
+++ b/ko/uavcan/escs.md
@@ -0,0 +1,205 @@
+# UAVCAN ESCs (Motor Controllers)
+
+PX4 supports [UAVCAN](../uavcan/README.md) ESCs. These have a number of advantages over [PWM ESCs](../peripherals/pwm_escs_and_servo.md):
+- UAVCAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
+- The bus is bi-directional, enabling health monitoring and diagnostics.
+- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other UAVCAN peripherals.
+- Setup is easier as you configure ESC numbering by manually spinning each motor (for most types of UAVCAN ESCs).
+
+
+
+
+
+## PX4 Supported ESC
+
+PX4 is compatible with any/all UAVCAN ESCs (UAVCAN is generally speaking a plug'n'play protocol).
+
+:::note
+At time of writing PX4 supports UAVCAN v0 (not v1.0).
+:::
+
+The only difference between UAVCAN ESCs from a setup perspective is that the physical connectors and the software tools used to configure the motor order and direction may be different.
+
+
+Some popular UAVCAN ESC firmware/products include:
+- [Sapog](https://github.com/PX4/sapog#px4-sapog) firmware; an advanced open source sensorless PMSM/BLDC motor controller firmware designed for use in propulsion systems of electric unmanned vehicles.
+ - [Zubax Orel 20](https://zubax.com/products/orel_20)
+ - [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+- [Mitochondrik](https://zubax.com/products/mitochondrik) - integrated sensorless PMSM/BLDC motor controller chip (used in ESCs and integrated drives)
+ - [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+- [Myxa](https://zubax.com/products/myxa) - High-end PMSM/BLDC motor controller (FOC ESC) for light unmanned aircraft and watercraft.
+- [VESC Project ESCs](https://vesc-project.com/) (see also [Benjamin Vedder's blog](http://vedder.se) - project owner)
+- [OlliW’s UC4H ESC-Actuator Node](http://www.olliw.eu/2017/uavcan-for-hobbyists/#chapterescactuator)
+- A number of others are [listed here](https://forum.uavcan.org/t/uavcan-esc-options/452/3?u=pavel.kirienko)
+
+:::note
+This list is *not exhaustive/complete*. If you know of another ESC, please add it to the list!
+:::
+
+## Purchase
+
+Sapog-based ESCs:
+- [Zubax Orel 20](https://zubax.com/products/orel_20)
+- [Holybro Kotleta20](https://shop.holybro.com/kotleta20_p1156.html)
+
+Mitochondrik based drives and ESC:
+- [Zubax Sadulli Integrated Drive](https://shop.zubax.com/collections/integrated-drives/products/sadulli-integrated-drive-open-hardware-reference-design-for-mitochondrik?variant=27740841181283)
+
+:::note
+There are many other commercially available ESCs; please add new links as you find them!
+:::
+
+
+
+
+
+## Wiring/Connections
+
+Connect all of the on-board UAVCAN devices into a chain and make sure the bus is terminated at the end nodes. The order in which the ESCs are connected/chained does not matter.
+
+For more information see [UAVCAN > Wiring](../uavcan/README.md#wiring).
+
+:::note
+All UAVCAN ESCs share the same connection architecture/are wired the same way. Note however that the actual connectors differ (e.g. *Zubax Orel 20* and *Holybro Kotleta20* use Dronecode standard connectors (JST-GH 4 Pin) - while VESCs do not).
+:::
+
+
+## PX4 Configuration
+
+In order to use a UAVCAN ESC with PX4 you will need to enable the UAVCAN driver:
+1. Power the vehicle using the battery (you must power the whole vehicle, not just the flight controller) and connect *QGroundControl*.
+1. Navigate to the **Vehicle Setup > Parameters** screen. :::note [Parameters](../advanced_config/parameters.md) explains how to find and set parameters.
+:::
+1. Set [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to the value *Sensors and Motors* (3) and then reboot the flight controller. This enables automatic enumeration of the motors (ESC) as described in the [next section](#esc-setup).
+1. (Optional) Set [UAVCAN_ESC_IDLT](../advanced_config/parameter_reference.md#UAVCAN_ESC_IDLT) to 1 in order to ensure that the motors are always running at least at the idle throttle while the system is armed. :::note Some systems will not benefit from this behavior, e.g. glider drones).
+:::
+
+
+## ESC Setup
+
+While UAVCAN devices are generally *plug'n'play* you will still need to enumerate (number) each of the ESC used in your system and set their direction so that they can be identified/controlled by PX4.
+
+:::note
+The ESC index and direction must match/map to the [Airframe Reference](../airframes/airframe_reference.md) for the vehicle type. ESC indexes from 0-7 map to MAIN 1-8, while ESC indexes 8-15 map to AUX 1-8.
+:::
+
+The mechanism for enumerating each type of UAVCAN ESC is different (look up the instructions in your ESC's manual). Setup information for some UAVCAN ESCs is provided below.
+
+
+### Sapog ESC Enumeration using QGroundControl
+
+This section shows how to enumerate any [Sapog-based](https://github.com/PX4/sapog#px4-sapog)-based ESCs "automatically" using *QGroundControl*.
+
+:::tip
+You can skip this section if there is only one ESC in your setup, because the ESC index is already set to zero by default.
+:::
+
+To enumerate the ESC:
+1. Power the vehicle with a battery and connect to *QGroundControl*
+1. Navigate to **Vehicle Setup > Power** in QGC.
+1. Start the process of ESC auto-enumeration by pressing the **Start Assignment** button, as shown on the screenshot below.
+
+ ![QGC - UAVCAN ESC auto-enumeration](../../assets/peripherals/esc_qgc/qgc_uavcan_settings.jpg)
+
+ You will hear a sound indicating that the flight controller has entered the ESC enumeration mode.
+1. Manually turn each motor in the correct direction of its rotation (as specified in the [Airframe Reference](../airframes/airframe_reference.md)), starting from the first motor and finishing with the last motor. Each time you turn a motor, you should hear a confirmation beep.
+
+:::note
+Make sure to turn each of the motors in the correct direction, as the ESC will automatically learn and remember the direction (i.e. motors that spin clockwise during normal operation must also be turned clockwise during enumeration).
+:::
+
+1. After the last motor is enumerated, the confirmation sound should change to indicate that the enumeration procedure is complete.
+1. Reboot PX4 and the Sapog ESCs to apply the new enumeration IDs.
+
+The following video demonstrates the process:
+
+@[youtube](https://www.youtube.com/watch?v=4nSa8tvpbgQ)
+
+### Manual ESC Enumeration using Sapog
+
+:::tip
+We recommend automated [Sapog ESC Enumeration using QGroundControl](#sapog-esc-enumeration-using-qgroundcontrol) shown above rather than manual enumeration (as it is easier and safer).
+:::
+
+You can manually configure the ESC index and direction using the [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/). This assigns the following Sapog configuration parameters for each enumerated ESC:
+- `esc_index`
+- `ctl_dir`
+
+:::note
+See [Sapog reference manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf) for more information about the parameters.
+:::
+
+### Myxa ESC Setup
+
+Motor enumeration for Myxa [Telega-based ESCs](https://zubax.com/products/telega) is usually performed using the [Kucher tool](https://files.zubax.com/products/com.zubax.kucher/) (or less "GUI-friendly" [UAVCAN GUI Tool](https://uavcan.org/GUI_Tool/Overview/)).
+
+There is some guidance here: [Quick start guide for Myxa v0.1](https://forum.zubax.com/t/quick-start-guide-for-myxa-v0-1/911) (Zubax blog).
+
+
+### VESC ESC Setup
+
+For [VESC ESCs](https://vesc-project.com/) the preferred tool for motor enumeration is the [VESC tool](https://vesc-project.com/vesc_tool). In addition to the normal motor configuration that you will have to setup in the VESC tool, you will also need to properly setup the app configuration. The recommended app setup is as follows:
+
+| Parameter | Option |
+| ----------------------- | ---------------------- |
+| App to use | `No App` |
+| VESC ID | `1,2,...` |
+| Can Status Message Mode | `CAN_STATUS_1_2_3_4_5` |
+| CAN Baud Rate | `CAN_BAUD_500K` |
+| CAN Mode | `UAVCAN` |
+| UAVCAN ESC Index | `0,1,...` |
+
+
+VESC ID should have the same motor numbering as in PX4 convention, starting at `1` for top-right motor, `2` for bottom-left motor etc. However the `UAVCAN ESC Index` starts from `0`, and as such it is always one index lower than the `VESC ID`. For example, in a quadcopter the bottom left motor will have `VESC ID = 2` and `UAVCAN ESC Index = 1`.
+
+Finally the `CAN Baud Rate` must match the value set in [UAVCAN_BITRATE](../advanced_config/parameter_reference.md#UAVCAN_BITRATE).
+
+
+## Troubleshooting
+
+#### Motors not spinning when armed
+
+If the PX4 Firmware arms but the motors do not start to rotate, check that parameter `UAVCAN_ENABLE=3` to use UAVCAN ESCs. If the motors do not start spinning before thrust is increased, check `UAVCAN_ESC_IDLT=1`.
+
+#### UAVCAN devices dont get node ID/Firmware Update Fails
+
+PX4 requires an SD card for UAVCAN node allocation and during firmware update (which happen during boot). Check that there is a (working) SD card present and reboot.
+
+
+## Further Information
+
+- [PX4/Sapog](https://github.com/PX4/sapog#px4-sapog) (Github)
+- [Sapog v2 Reference Manual](https://files.zubax.com/products/io.px4.sapog/Sapog_v2_Reference_Manual.pdf)
+- [UAVCAN Device Interconnection](https://kb.zubax.com/display/MAINKB/UAVCAN+device+interconnection) (Zubax KB)
+- [Using Sapog based ESC with PX4](https://kb.zubax.com/display/MAINKB/Using+Sapog-based+ESC+with+PX4) (Zubax KB)
+
diff --git a/ru/SUMMARY.md b/ru/SUMMARY.md
index b6c944c1e6ce..458fa12a8779 100644
--- a/ru/SUMMARY.md
+++ b/ru/SUMMARY.md
@@ -12,6 +12,7 @@
* [LED Meanings](getting_started/led_meanings.md)
* [Tune/Sound Meanings](getting_started/tunes.md)
* [Preflight Checks](flying/pre_flight_checks.md)
+ * [Payloads & Cameras](payloads/README.md)
* [Flight Reporting](getting_started/flight_reporting.md)
* [Basic Assembly](assembly/README.md)
* [Mounting the Flight Controller](assembly/mount_and_orient_controller.md)
diff --git a/ru/flight_modes/mission.md b/ru/flight_modes/mission.md
index 598f779dac58..a2490976b413 100644
--- a/ru/flight_modes/mission.md
+++ b/ru/flight_modes/mission.md
@@ -48,7 +48,7 @@ To automatically disarm the vehicle after it lands, in *QGroundControl* go to [V
Missions can be paused by activating [HOLD mode](../flight_modes/hold.md). The mission will then continue from the current mission command when you reactivate the MISSION flight mode. While flying in mission mode, if you decide to discontinue the mission and switch to any other mode e.g. position mode, fly the vehicle elsewhere with RC, and then switch back to mission mode, the vehicle will continue the mission from its current position and will fly to the next mission waypoint not visited yet.
:::warning
-Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash).We recommend you centre the control sticks before switching to any other mode.
+Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.
:::
For more information about mission planning, see:
@@ -77,7 +77,7 @@ Mission behaviour is affected by a number of parameters, most of which are docum
## Supported Mission Commands
-PX4 "accepts" the following MAVLink mission commands in Mission mode (note: caveats below list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
+PX4 "accepts" the following MAVLink mission commands in Mission mode (with some *caveats*, given after the list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
* [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT)
* *Param3* (flythrough) is ignored. Flythrough is always enabled if *param 1* (time_inside) > 0.
@@ -86,9 +86,6 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
* [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF)
* [MAV_CMD_NAV_LOITER_TO_ALT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TO_ALT)
-* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
-* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
-* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
* [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF)
* `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
@@ -104,6 +101,9 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -122,30 +122,36 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
-* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
-* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+* [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+* [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+* [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+* [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+* [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+* [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
Note:
* PX4 parses the above messages, but they are not necessary *acted* on. For example, some messages are vehicle-type specific.
-* PX4 generally does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) ).
+* PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* Not all messages/commands are exposed via *QGroundControl*.
-* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) (list generated in [this git changelist](https://github.com/PX4/PX4-Autopilot/commit/ca1f7a4a194c23303c23ca79b5905ff8bfb94c22)).
+* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-Please add an bug fix or PR if you find a missing/incorrect message.
+Please add an issue report or PR if you find a missing/incorrect message.
:::
## Inter-Waypoint Trajectory
PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).
-MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning.
+MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+![acc-rad](../../assets/flying/acceptance_radius_mission.png)
-Vehicles switch to the next waypoint as soon as they enter the acceptance radius.
+Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
-* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)
-* For FW the radius is defined by the "L1 distance".
+* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+* For FW the acceptance radius is defined by the "L1 distance".
* The L1 distance is computed from two parameters: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) and [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD), and the current ground speed.
* By default, it's about 70 meters.
* The equation is: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/ru/flying/missions.md b/ru/flying/missions.md
index 571135d77511..638bd7caa9b4 100644
--- a/ru/flying/missions.md
+++ b/ru/flying/missions.md
@@ -26,6 +26,22 @@ If **Heading** has not been explicitly set for the target waypoint (`param4=NaN`
Vehicle types that cannot independently control yaw and direction of travel will ignore yaw settings (e.g. Fixed Wing).
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## Flying Missions
Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
diff --git a/ru/getting_started/README.md b/ru/getting_started/README.md
index 158f802b676f..5374358474ed 100644
--- a/ru/getting_started/README.md
+++ b/ru/getting_started/README.md
@@ -14,4 +14,6 @@ This section provides an overview of the basic concepts you need to understand i
[Flight Modes](../getting_started/flight_modes.md) — Control modes for manual, assisted and autonomous movement.
+[Payloads & Cameras](../payloads/README.md)
+
[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/ru/payloads/README.md b/ru/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/ru/payloads/README.md
+++ b/ru/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/ru/releases/1.12.md b/ru/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/ru/releases/1.12.md
+++ b/ru/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/ru/ros/ros2_offboard_control.md b/ru/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/ru/ros/ros2_offboard_control.md
+++ b/ru/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).
diff --git a/ru/simulation/airsim.md b/ru/simulation/airsim.md
index 2d3854f8392b..401b169bc8b3 100644
--- a/ru/simulation/airsim.md
+++ b/ru/simulation/airsim.md
@@ -2,9 +2,9 @@
AirSim is a open-source, cross platform simulator for drones, built on Unreal Engine. It provides physically and visually realistic simulations of Pixhawk/PX4 using either Hardware-In-The-Loop \(HITL\) or Software-In-The-Loop \(SITL\).
-The main entry point for the documentation is the [Github AirSim README](https://github.com/Microsoft/AirSim/blob/master/README.md).
+The main entry point for the documentation is the [AirSim Documentation](https://microsoft.github.io/AirSim/).
-The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://github.com/Microsoft/AirSim/blob/master/docs/px4_setup.md) (covering both HITL and SITL).
+The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://microsoft.github.io/AirSim/px4_setup/) (covering both HITL and SITL).
## Further Information
diff --git a/tr/SUMMARY.md b/tr/SUMMARY.md
index b6c944c1e6ce..458fa12a8779 100644
--- a/tr/SUMMARY.md
+++ b/tr/SUMMARY.md
@@ -12,6 +12,7 @@
* [LED Meanings](getting_started/led_meanings.md)
* [Tune/Sound Meanings](getting_started/tunes.md)
* [Preflight Checks](flying/pre_flight_checks.md)
+ * [Payloads & Cameras](payloads/README.md)
* [Flight Reporting](getting_started/flight_reporting.md)
* [Basic Assembly](assembly/README.md)
* [Mounting the Flight Controller](assembly/mount_and_orient_controller.md)
diff --git a/tr/flight_modes/mission.md b/tr/flight_modes/mission.md
index 598f779dac58..a2490976b413 100644
--- a/tr/flight_modes/mission.md
+++ b/tr/flight_modes/mission.md
@@ -48,7 +48,7 @@ To automatically disarm the vehicle after it lands, in *QGroundControl* go to [V
Missions can be paused by activating [HOLD mode](../flight_modes/hold.md). The mission will then continue from the current mission command when you reactivate the MISSION flight mode. While flying in mission mode, if you decide to discontinue the mission and switch to any other mode e.g. position mode, fly the vehicle elsewhere with RC, and then switch back to mission mode, the vehicle will continue the mission from its current position and will fly to the next mission waypoint not visited yet.
:::warning
-Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash).We recommend you centre the control sticks before switching to any other mode.
+Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.
:::
For more information about mission planning, see:
@@ -77,7 +77,7 @@ Mission behaviour is affected by a number of parameters, most of which are docum
## Supported Mission Commands
-PX4 "accepts" the following MAVLink mission commands in Mission mode (note: caveats below list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
+PX4 "accepts" the following MAVLink mission commands in Mission mode (with some *caveats*, given after the list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.
* [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT)
* *Param3* (flythrough) is ignored. Flythrough is always enabled if *param 1* (time_inside) > 0.
@@ -86,9 +86,6 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
* [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF)
* [MAV_CMD_NAV_LOITER_TO_ALT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TO_ALT)
-* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
-* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
-* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
* [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF)
* `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
@@ -104,6 +101,9 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+* [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -122,30 +122,36 @@ PX4 "accepts" the following MAVLink mission commands in Mission mode (note: cave
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
-* [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
-* [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+* [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+* [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+* [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+* [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+* [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+* [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
Note:
* PX4 parses the above messages, but they are not necessary *acted* on. For example, some messages are vehicle-type specific.
-* PX4 generally does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) ).
+* PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* Not all messages/commands are exposed via *QGroundControl*.
-* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) (list generated in [this git changelist](https://github.com/PX4/PX4-Autopilot/commit/ca1f7a4a194c23303c23ca79b5905ff8bfb94c22)).
+* The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-Please add an bug fix or PR if you find a missing/incorrect message.
+Please add an issue report or PR if you find a missing/incorrect message.
:::
## Inter-Waypoint Trajectory
PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).
-MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning.
+MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+![acc-rad](../../assets/flying/acceptance_radius_mission.png)
-Vehicles switch to the next waypoint as soon as they enter the acceptance radius.
+Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
-* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)
-* For FW the radius is defined by the "L1 distance".
+* For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+* For FW the acceptance radius is defined by the "L1 distance".
* The L1 distance is computed from two parameters: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) and [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD), and the current ground speed.
* By default, it's about 70 meters.
* The equation is: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/tr/flying/missions.md b/tr/flying/missions.md
index 571135d77511..638bd7caa9b4 100644
--- a/tr/flying/missions.md
+++ b/tr/flying/missions.md
@@ -26,6 +26,22 @@ If **Heading** has not been explicitly set for the target waypoint (`param4=NaN`
Vehicle types that cannot independently control yaw and direction of travel will ignore yaw settings (e.g. Fixed Wing).
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## Flying Missions
Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
diff --git a/tr/getting_started/README.md b/tr/getting_started/README.md
index 158f802b676f..5374358474ed 100644
--- a/tr/getting_started/README.md
+++ b/tr/getting_started/README.md
@@ -14,4 +14,6 @@ This section provides an overview of the basic concepts you need to understand i
[Flight Modes](../getting_started/flight_modes.md) — Control modes for manual, assisted and autonomous movement.
+[Payloads & Cameras](../payloads/README.md)
+
[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/tr/payloads/README.md b/tr/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/tr/payloads/README.md
+++ b/tr/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/tr/releases/1.12.md b/tr/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/tr/releases/1.12.md
+++ b/tr/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/tr/ros/ros2_offboard_control.md b/tr/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/tr/ros/ros2_offboard_control.md
+++ b/tr/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).
diff --git a/tr/simulation/airsim.md b/tr/simulation/airsim.md
index 2d3854f8392b..401b169bc8b3 100644
--- a/tr/simulation/airsim.md
+++ b/tr/simulation/airsim.md
@@ -2,9 +2,9 @@
AirSim is a open-source, cross platform simulator for drones, built on Unreal Engine. It provides physically and visually realistic simulations of Pixhawk/PX4 using either Hardware-In-The-Loop \(HITL\) or Software-In-The-Loop \(SITL\).
-The main entry point for the documentation is the [Github AirSim README](https://github.com/Microsoft/AirSim/blob/master/README.md).
+The main entry point for the documentation is the [AirSim Documentation](https://microsoft.github.io/AirSim/).
-The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://github.com/Microsoft/AirSim/blob/master/docs/px4_setup.md) (covering both HITL and SITL).
+The main entry point for documentation on working with PX4 is [PX4 Setup for AirSim](https://microsoft.github.io/AirSim/px4_setup/) (covering both HITL and SITL).
## Further Information
diff --git a/zh/SUMMARY.md b/zh/SUMMARY.md
index b8f2892a2913..42cdbe3f31c8 100644
--- a/zh/SUMMARY.md
+++ b/zh/SUMMARY.md
@@ -12,7 +12,8 @@
* [LED灯含义](getting_started/led_meanings.md)
* [声调/声音含义](getting_started/tunes.md)
* [飞行前检查](flying/pre_flight_checks.md)
- * [飞行报告](getting_started/flight_reporting.md)
+ * [Payloads & Cameras](payloads/README.md)
+ * [Flight Reporting](getting_started/flight_reporting.md)
* [基本装配](assembly/README.md)
* [安装飞控](assembly/mount_and_orient_controller.md)
* [震动隔离](assembly/vibration_isolation.md)
diff --git a/zh/flight_modes/mission.md b/zh/flight_modes/mission.md
index b2d01b7535ca..ce2dc37f11c2 100644
--- a/zh/flight_modes/mission.md
+++ b/zh/flight_modes/mission.md
@@ -48,7 +48,7 @@
可以通过激活[HOLD 模式](../flight_modes/hold.md)暂停任务。 当您重新激活 MISSION 飞行模式时,任务将从当前任务命令继续执行。 在任务模式下飞行时,如果决定中止任务,并且切换到了其他飞行模式,如位置模式,通过遥控器讲无人机飞到了其他地方,然后切换回任务模式,无人机将从当前位置继续执行任务,并会飞往下一个未访问的任务航点。
:::warning
-在切换 RC 模式前确保遥控器油门摇杆不为零(否则会炸机)。建议在切换到其他模式前控制摇杆回中。
+Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash). We recommend you centre the control sticks before switching to any other mode.
:::
有关任务规划的更多信息,请参阅:
@@ -80,7 +80,7 @@
## 支持的任务命令
- PX4 在任务模式下“接受”以下 MAVLink 任务命令(注意:下面列出注意事项)。 除非另有说明,否则该实现与 MAVLink 规范中定义的一样。
+ PX4 "accepts" the following MAVLink mission commands in Mission mode (with some *caveats*, given after the list). 除非另有说明,否则该实现与 MAVLink 规范中定义的一样。
* [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT)
* *Param3* (漫游) 被忽略。 如果 *param1* (time_inside)> 0,漫游始终使能。
@@ -89,16 +89,13 @@
* [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
* [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF)
* [MAV_CMD_NAV_LOITER_TO_ALT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TO_ALT)
- * [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
- * [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
- * [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
* [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF)
- * `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (过渡标题) 忽略。 取而代之的是,将下一个航点的标题用于过渡标题。
+ * `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading.
* [MAV_CMD_NAV_VTOL_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_LAND)
- * [EMAV_CMD_NAV_FENCE_RETURN_POINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_FENCE_RETURN_POINT)
+ * [MAV_CMD_NAV_FENCE_RETURN_POINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_FENCE_RETURN_POINT)
* [MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION)
* [MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION)
* [MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION)
@@ -107,6 +104,9 @@
* [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP)
* [MAV_CMD_NAV_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_ROI)
* [MAV_CMD_DO_SET_ROI](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI)
+ * [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
+ * [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
+ * [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
* [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED)
* [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME)
* [MAV_CMD_DO_SET_SERVO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO)
@@ -125,29 +125,36 @@
* [MAV_CMD_DO_VTOL_TRANSITION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_VTOL_TRANSITION)
* [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY)
* [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
- * [MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET)
- * [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
+ * [MAV_CMD_DO_CONTROL_VIDEO](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CONTROL_VIDEO)
+ * [MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW)
+ * [MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE)
+ * [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY)
+ * [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM)
+ * [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS)
注意:
* PX4 解析上述消息,但不是必须要 *做*的。 例如,某些消息是针对飞机类型的。
- * 对于任务命令,PX4 通常不支持本地坐标系(例如,[MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED))。
+ * PX4 does not support local frames for mission commands (e.g. [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED)).
* 并非所有消息/命令都通过 *QGroundControl* 公开。
- * 添加消息时,列表可能已过时。 可以通过查看代码来检查当前设置。 支持 [ /src/modules/mavlink/mavlink_mission.cpp ](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp) 中的 ` MavlinkMissionManager::parse_mavlink_mission_item` (在this git changelist 2>中生成的列表)。
+ * 添加消息时,列表可能已过时。 可以通过查看代码来检查当前设置。 Support is `MavlinkMissionManager::parse_mavlink_mission_item` in [/src/modules/mavlink/mavlink_mission.cpp](https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_mission.cpp).
:::note
-如果发现缺失或错误的消息,请添加 bug 修复或者 PR。 :::
-
- ## 航点间轨迹
-
- PX4 期望从上一个航点到当前目标遵循一条直线(不计划航点之间的任何其他类型路径 - 如果需要,可以通过添加额外航点来模拟)。
-
- 当MC 无人机接近或离开航点时,将基于[jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)的调试来更改*速度*。
-
- 无人机在进入接受半径后立即切换到下一个航点。
-
- * 对于 MC,这个半径由 [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)来定义。
- * 对于 FW,半径由“L1距离”定义。
- * L1 距离是根据两个参数计算的: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) 和 [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD),还有当前地速。
- * 默认情况下,约 70米。
- * 方程式: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
+Please add an issue report or PR if you find a missing/incorrect message.
+:::
+
+ ## 航点间轨迹
+
+ PX4 期望从上一个航点到当前目标遵循一条直线(不计划航点之间的任何其他类型路径 - 如果需要,可以通过添加额外航点来模拟)。
+
+ MC vehicles will change the *speed* when approaching or leaving a waypoint based on the [jerk-limited](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode) tuning. The vehicle will follow a smooth rounded curve towards the next waypoint (if one is defined) defined by the acceptance radius ([NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD)). The diagram below shows the sorts of paths that you might expect.
+
+ ![acc-rad](../../assets/flying/acceptance_radius_mission.png)
+
+ Vehicles switch to the next waypoint as soon as they enter the acceptance radius:
+
+ * For MC this radius is defined by [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD).
+ * For FW the acceptance radius is defined by the "L1 distance".
+ * L1 距离是根据两个参数计算的: [FW_L1_DAMPING](../advanced_config/parameter_reference.md#FW_L1_DAMPING) 和 [FW_L1_PERIOD](../advanced_config/parameter_reference.md#FW_L1_PERIOD),还有当前地速。
+ * 默认情况下,约 70米。
+ * 方程式: $$L_{1_{distance}}=\frac{1}{\pi}L_{1_{damping}}L_{1_{period}}\left \| \vec{v}*{ {xy}*{ground} } \right \|$$
\ No newline at end of file
diff --git a/zh/flying/missions.md b/zh/flying/missions.md
index ff41798952fc..71ef65d412c6 100644
--- a/zh/flying/missions.md
+++ b/zh/flying/missions.md
@@ -26,6 +26,22 @@ If **Heading** has not been explicitly set for the target waypoint (`param4=NaN`
Vehicle types that cannot independently control yaw and direction of travel will ignore yaw settings (e.g. Fixed Wing).
+### Setting Acceptance/Turning Radius
+
+The *acceptance radius* defines the circle around a waypoint within which a vehicle considers it has reached the waypoint, and will immediately switch to (and start turning towards) the next waypoint.
+
+For a multi-rotor drones, the acceptance radius is tuned using the parameter [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD). By default, the radius is small to ensure that multirotors pass above the waypoints, but it can be increased to create a smoother path such that the drone starts to turn before reaching the waypoint.
+
+The image below shows the same mission flown with different acceptance radius parameters:
+
+![acceptance radius comparison](../../assets/flying/acceptance_radius_comparison.jpg)
+
+The speed in the turn is automatically computed based on the acceptance radius (= turning radius) and the maximum allowed acceleration and jerk (see [Jerk-limited Type Trajectory for Multicopters](../config_mc/mc_jerk_limited_type_trajectory.md#auto-mode)).
+
+:::tip
+For more information about the impact of the acceptance radius around the waypoint see: [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory).
+:::
+
## 执行飞行任务
Once the mission is uploaded, switch to the flight view. The mission is displayed in a way that makes it easy to track progress (it cannot be modified in this view).
diff --git a/zh/getting_started/README.md b/zh/getting_started/README.md
index d42d61f84735..f3dad6abbad0 100644
--- a/zh/getting_started/README.md
+++ b/zh/getting_started/README.md
@@ -14,4 +14,6 @@
[飞行模式](../getting_started/flight_modes.md) — 手动、辅助、全自动的控制模式。
-[飞行报告](../getting_started/flight_reporting.md) — 下载详细的飞行日志用于调试分析。
\ No newline at end of file
+[Payloads & Cameras](../payloads/README.md)
+
+[Flight Reporting](../getting_started/flight_reporting.md) — Download detailed flight logs for debugging and analysis.
\ No newline at end of file
diff --git a/zh/payloads/README.md b/zh/payloads/README.md
index d3d83c292aa9..4a6d6364f268 100644
--- a/zh/payloads/README.md
+++ b/zh/payloads/README.md
@@ -4,24 +4,49 @@ PX4 supports a wide range of payloads and cameras.
## Mapping Drones
-* [Camera triggering](../peripherals/camera.md) via GPIO out
-* [Camera triggering](../peripherals/camera.md) via PWM out
-* [Camera triggering](../peripherals/camera.md) via MAVLink out
-* [Camera timing](../peripherals/camera.md#camera_capture) feedback via hotshoe input
+Mapping drones use cameras to capture images at time or distance intervals during surveys.
-## Cargo drones and alike: Servos / Outputs
+MAVLink cameras that support the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4).
-* Servo or GPIO triggering (via RC or via commands)
+Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:
+* [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL) - set time interval between captures.
+* [MAV_CMD_DO_SET_CAM_TRIGG_DIST](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_DIST) - set distance between captures
+* [MAV_CMD_DO_TRIGGER_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_TRIGGER_CONTROL) - start/stop capturing (using distance or time, as defined using above messages).
+
+The following topics show how to *connect* your camera configure PX4:
+* [Camera triggering](../peripherals/camera.md) from flight controller PWM or GPIO outputs, or via MAVLink.
+* [Camera timing feedback](../peripherals/camera.md#camera_capture) via hotshoe input.
+
+
+## Cargo Drones ("Actuator" Payloads)
+
+Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.
### Example Mission (in QGC)
-Use MAV_CMD_DO_SET_ACTUATOR to trigger one of the payload actuators.
+Use the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command to trigger one of the payload actuators.
+
+### RC Triggering
+
+You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters [RC_MAP_AUX1](../advanced_config/parameter_reference.md#RC_MAP_AUX1) to [RC_MAP_AUX3](../advanced_config/parameter_reference.md#RC_MAP_AUX3).
+
+The RC channels are then *usually* mapped to the `AUX1`, `AUX2`, `AUX3` outputs of your flight controller (but they don't have to be). You can check which outputs are used for RC AUX passthrough on your vehicle in the [Airframe Reference](../airframes/airframe_reference.html). For example, [Quadrotor-X](../airframes/airframe_reference.html#quadrotor-x) has the normal mapping: "**AUX1:** feed-through of RC AUX1 channel".
+
+If your vehicle has no mapping then you can add one by using a custom [Mixer File](https://docs.px4.io/master/en/concept/mixing.html) that maps [Control group 3](../concept/mixing.md#control-group-3-manual-passthrough) outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: [pass.aux.mix](https://github.com/PX4/PX4-Autopilot/blob/master/ROMFS/px4fmu_common/mixers/pass.aux.mix).
+
### Example script (MAVSDK)
-This script sends a command to set the actuator and trigger the payload release on a servo:
+The following [MAVSDK](https://mavsdk.mavlink.io/develop/en/) sample code shows how to trigger payload release.
-```
+The code uses the MAVSDK [MavlinkPassthrough](https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_mavlink_passthrough.html) plugin to send the [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR) MAVLink command, specifying the value of up to 3 actuators.
+
+
+
+
+```cpp
#include
#include
#include
@@ -107,3 +132,15 @@ void send_actuator(MavlinkPassthrough& mavlink_passthrough,
std::cout << "Sent message" << std::endl;
}
```
+
+## Surveillance, Search & Rescue
+
+Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night
+
+Use a camera that supports the [MAVLink Camera Protocol](https://mavlink.io/en/services/camera.html) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both [standalone camera operations](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_camera.html) and in [missions](https://mavsdk.mavlink.io/main/en/cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.html#structmavsdk_1_1_mission_1_1_mission_item_1a0299fbbe7c7b03bc43eb116f96b48df4)). See [Camera triggering](../peripherals/camera.md) for information on how to configure your camera to work with MAVLink.
+
+:::note
+Cameras connected directly to the flight control _only_ support camera triggering, and are unlikely to be suitable for most surveillance/search work.
+:::
+
+A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See [Cargo Drones](#cargo-drones-actuator-payloads) above for information about payload delivery.
diff --git a/zh/releases/1.12.md b/zh/releases/1.12.md
index ec30e2e1b873..763022671052 100644
--- a/zh/releases/1.12.md
+++ b/zh/releases/1.12.md
@@ -23,8 +23,12 @@
* **MAVLink Ethernet configuration ([PR#14460](https://github.com/PX4/PX4-Autopilot/pull/14460))**
* MAVLink Ethernet channel settings such as UDP port, remote port and broadcast mode now can be changed dynamically via parameters.
+
+
+
### Commander
@@ -54,6 +58,7 @@ The gains have a new meaning
* Development: [Logic introduction](https://github.com/PX4/PX4-Autopilot/pull/14749), [Parameter replacement](https://github.com/PX4/PX4-Autopilot/pull/14823)
* **Improve Rounded Turns ([PR#16376](https://github.com/PX4/PX4-Autopilot/pull/16376))**
* Creates a more rounded turn at waypoints in multirotor missions (using L1-style guidance logic in corners)
+ * See [Mission Mode > Inter-waypoint Trajectory](../flight_modes/mission.md#inter-waypoint-trajectory) and [Mission > Setting Acceptance/Turning Radius](../flying/missions.md#setting-acceptance-turning-radius)
### VTOL
diff --git a/zh/ros/ros2_offboard_control.md b/zh/ros/ros2_offboard_control.md
index c886f79213a0..b48d09fd995b 100644
--- a/zh/ros/ros2_offboard_control.md
+++ b/zh/ros/ros2_offboard_control.md
@@ -18,7 +18,7 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
1. The user already has their ROS 2 environment properly configured Check the [PX4-ROS 2 bridge](../ros/ros2_comm.md) document for details on how to do it.
1. `px4_msgs` and `px4_ros_com` should be already on your colcon workspace. See the link in the previous point for details.
-1. `offboard_control_mode` and `position_setpoint_triplet` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
+1. `offboard_control_mode` and `trajectory_setpoint` messages are configured in the `uorb_rtps_message_ids.yaml` file both in the PX4-Autopilot and *px4_ros_com* package to be *received* in the Autopilot.
In *PX4-Autopilot/msg/tools/uorb_rtps_message_ids.yaml*:
```yaml
@@ -26,8 +26,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
id: 44
receive: true
...
- - msg: position_setpoint_triplet
- id: 51
+ - msg: trajectory_setpoint
+ id: 186
+ alias: vehicle_local_position_setpoint
receive: true
```
@@ -37,8 +38,9 @@ For this example, PX4 SITL is being used, so it is assumed, first of all, that t
msg: OffboardControlMode
receive: true
...
- - id: 51
- msg: PositionSetpointTriplet
+ - alias: VehicleLocalPositionSetpoint
+ id: 186
+ msg: TrajectorySetpoint
receive: true
```
@@ -60,31 +62,33 @@ timesync_sub_ = this->create_subscription("Timesync_Pub
});
```
-The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `position_setpoint_triplet` messages.
+The above is required in order to obtain a syncronized timestamp to be set and sent with the `offboard_control_mode` and `trajectory_setpoint` messages.
```cpp
- auto timer_callback = [this]() -> void {
- if (offboard_setpoint_counter_ == 100) {
- // Change to Offboard mode after 100 setpoints
+auto timer_callback = [this]() -> void {
+
+ if (offboard_setpoint_counter_ == 10) {
+ // Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
- }
+ }
- // offboard_control_mode needs to be paired with position_setpoint_triplet
- publish_offboard_control_mode();
- publish_position_setpoint_triplet();
+ // offboard_control_mode needs to be paired with trajectory_setpoint
+ publish_offboard_control_mode();
+ publish_trajectory_setpoint();
- // stop the counter after reaching 100
- if (offboard_setpoint_counter_ < 101) {
+ // stop the counter after reaching 11
+ if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(10ms, timer_callback);
+ }
+ };
+ timer_ = this->create_wall_timer(100ms, timer_callback);
+ }
```
-The above is the main loop spining on the ROS 2 node. It first sends 100 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `position_setpoint_triplet` messages are sent to the flight controller.
+The above is the main loop spining on the ROS 2 node. It first sends 10 setpoint messages before sending the command to change to offboard mode At the same time, both `offboard_control_mode` and `trajectory_setpoint` messages are sent to the flight controller.
```cpp
/**
@@ -94,42 +98,34 @@ The above is the main loop spining on the ROS 2 node. It first sends 100 setpoin
void OffboardControl::publish_offboard_control_mode() const {
OffboardControlMode msg{};
msg.timestamp = timestamp_.load();
- msg.ignore_thrust = true;
- msg.ignore_attitude = true;
- msg.ignore_bodyrate_x = true;
- msg.ignore_bodyrate_y = true;
- msg.ignore_bodyrate_z = true;
- msg.ignore_position = false;
- msg.ignore_velocity = true;
- msg.ignore_acceleration_force = true;
- msg.ignore_alt_hold = true;
+ msg.position = true;
+ msg.velocity = false;
+ msg.acceleration = false;
+ msg.attitude = false;
+ msg.body_rate = false;
offboard_control_mode_publisher_->publish(msg);
}
+
/**
- * @brief Publish position setpoint triplets.
- * For this example, it sends position setpoint triplets to make the
- * vehicle hover at 5 meters.
+ * @brief Publish a trajectory setpoint
+ * For this example, it sends a trajectory setpoint to make the
+ * vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
-void OffboardControl::publish_position_setpoint_triplet() const {
- PositionSetpointTriplet msg{};
+void OffboardControl::publish_trajectory_setpoint() const {
+ TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
- msg.current.timestamp = timestamp_.load();
- msg.current.type = PositionSetpoint::SETPOINT_TYPE_POSITION;
- msg.current.x = 0.0;
- msg.current.y = 0.0;
- msg.current.z = -5.0;
- msg.current.cruising_speed = -1.0;
- msg.current.position_valid = true;
- msg.current.alt_valid = true;
- msg.current.valid = true;
-
- position_setpoint_triplet_publisher_->publish(msg);
+ msg.x = 0.0;
+ msg.y = 0.0;
+ msg.z = -5.0;
+ msg.yaw = -3.14; // [-PI:PI]
+
+ trajectory_setpoint_publisher_->publish(msg);
}
```
-The above functions exemplify how the fields on both `offboard_control_mode` and `position_setpoint_triplet` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `ignore_position` field is set to `true`, while all the others get set to `false`, and in the `position_setpoint_triplet`, on the `current` setpoint, `valid`, `alt_valid` and `position_valid` are set to `true`. Also, in this case, `x`, `y` and `z` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
+The above functions exemplify how the fields on both `offboard_control_mode` and `trajectory_setpoint` messages can be set. Notice that the above example is applicable for offboard position control, where on the `offboard_control_mode` message, the `position` field is set to `true`, while all the others get set to `false`. Also, in this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node.
:::tip
The position is already being published in the NED coordinate frame for simplicity, but in the case of the user wanting to subscribe to data coming from other nodes, and since the standard frame of reference in ROS/ROS 2 is ENU, the user can use the available helper functions in the [`frame_transform` library](https://github.com/PX4/px4_ros_com/blob/master/src/lib/frame_transforms.cpp).