diff --git a/de/SUMMARY.md b/de/SUMMARY.md
index 65bb404a3f1a..636d8103af0f 100644
--- a/de/SUMMARY.md
+++ b/de/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/de/msg_docs/index.md b/de/msg_docs/index.md
index 8cf2bb5a322c..02855450117c 100644
--- a/de/msg_docs/index.md
+++ b/de/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/de/ros/mavros_installation.md b/de/ros/mavros_installation.md
index 88dd4db130a6..d71899d331ac 100644
--- a/de/ros/mavros_installation.md
+++ b/de/ros/mavros_installation.md
@@ -20,7 +20,9 @@ These instructions are a simplified version of the [official installation guide]
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ These instructions are a simplified version of the [official installation guide]
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/de/ros/ros2.md b/de/ros/ros2.md
index ef6c624f6cf4..9b483f856475 100644
--- a/de/ros/ros2.md
+++ b/de/ros/ros2.md
@@ -1,34 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) is the newest version of [ROS](http://www.ros.org/) (Robot Operating System), a general purpose robotics library that can be used with the PX4 Autopilot to create powerful drone applications. It captures most of the learnings and features of [ROS 1](../ros/ros1.md), improving a number of flaws of the earlier version.
-
-:::warning
-Tip
-The PX4 development team highly recommend that you use/migrate to this version of ROS!
-:::
-
-This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. The middleware uses uORB message definitions to generate code to serialise and deserialise the messages heading in and out of PX4. Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-To use the [ROS 2](../ros/ros2_comm.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. In the near term future we plan to provide ROS 2 APIs to abstract PX4 conventions, along with examples demonstrating their use.
-
-The main topics in this section are:
-- [ROS 2 User Guide](../ros/ros2_comm.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4.
-- [ROS 2 Offboard Control Example](../ros/ros2_offboard_control.md)
-
-:::note
-ROS 2 is officially supported only on Linux platforms.
-:::note
-ROS 2 is officially supported only on Linux platforms.
-:::
-
-
-:::note ROS
-2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). This option is supported by the MAVROS project.
-:::
-
-
-## Further Reading/Information
-
-- [ROS 2 User Guide](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2.
-
+
diff --git a/de/ros/ros2_comm.md b/de/ros/ros2_comm.md
index 55f922e07d61..47f18ae25603 100644
--- a/de/ros/ros2_comm.md
+++ b/de/ros/ros2_comm.md
@@ -1,783 +1 @@
-# ROS 2 User Guide
-
-The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
-
-This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
-
-:::note
-From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## Overview
-
-The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware.
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
-
-The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default.
-
-You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware.
-
-Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
-
-You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
-
-:::note
-The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics.
-:::
-
-
-## Installation & Setup
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-:::note PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [Install PX4](#install-px4) (to use the PX4 simulator)
-- [Install ROS 2](#install-ros-2)
-- [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client)
-- [Build & Run ROS 2 Workspace](#build-ros-2-workspace)
-
-Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered.
-
-
-### Install PX4
-
-You need to install the PX4 development toolchain in order to use the simulator.
-
-:::note
-The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-Set up a PX4 development environment on Ubuntu in the normal way:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### Install ROS 2
-
-To install ROS 2 and its dependencies:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
- ::::
-
-1. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Setup Micro XRCE-DDS Agent & Client
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### Setup the Agent
-
-The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
-
-To setup and start the agent:
-
-1. Open a terminal.
-1. Enter the following commands to fetch and build the agent from source:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-The agent is now running, but you won't see much until we start PX4 (in the next step).
-
-:::note
-You can leave the agent running in this terminal!
-:::note
-You can leave the agent running in this terminal!
-:::
-
-#### Start the Client
-
-The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
-
-To start the simulator (and client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-The agent and client are now running they should connect.
-
-The PX4 terminal displays the [NuttShell/PX4 System Console](../debug/system_console.md) output as PX4 boots and runs. As soon as the agent connects the output should include `INFO` messages showing creation of data writers:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Build ROS 2 Workspace
-
-This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere).
-
-The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`.
-
-For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml). ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- :::note
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- cd ..
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- cd ..
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-:::note
-The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case). This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not!
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. This clock is always slightly off-sync w.r.t. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 Example Applications
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-:::note
-[Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-:::note
-The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-The instantiation of the `SensorCombinedListener` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be: Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders.
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
-:::note
-Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-:::note
-Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-...
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example. The `ros2 launch` command is used to start a ROS 2 launch file.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Additional information
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/de/ros/ros2_multi_vehicle.md b/de/ros/ros2_multi_vehicle.md
index 510fff744168..6449c4011507 100644
--- a/de/ros/ros2_multi_vehicle.md
+++ b/de/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-:::note
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-:::note
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/de/ros/ros2_offboard_control.md b/de/ros/ros2_offboard_control.md
index 64e85ef18168..ad1f47e679c4 100644
--- a/de/ros/ros2_offboard_control.md
+++ b/de/ros/ros2_offboard_control.md
@@ -1,200 +1 @@
-# ROS 2 Offboard Control Example
-
-The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
-
-The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits. While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
-
-It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 `main` after PX4 v1.13.
-
-:::warning
-*Offboard* control is dangerous. If you are operating on a real vehicle be sure to have a way of gaining back manual control in case something goes wrong.
-:::
-
-:::note ROS
-and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). There is no implicit conversion between frame types when topics are published or subscribed!
-
-This example publishes positions in the NED frame, as expected by PX4. To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library.
-:::
-
-## Trying it out
-
-Follow the instructions in [ROS 2 User Guide](../ros/ros2_comm.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
-
-After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros/ros2_comm.md#build-ros-2-workspace) to run the example.
-
-To build and run the example:
-
-1. Open a new terminal.
-1. Create and navigate into a new colcon workspace directory using:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- cd ..
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- cd ..
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Launch the example.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-The vehicle should arm, ascend 5 metres, and then wait (perpetually).
-
-## Implementation
-
-The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-:::note PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. The required behaviour is implemented by the main loop spinning in the ROS 2 node, as shown below:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-The loop runs on a 100ms timer. The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode). For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4.
-
-After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. After the vehicle arms and changes mode it starts tracking the position setpoints. The setpoints are still sent in every cycle so that the vehicle does not fall out of offboard mode.
-
-The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively).
-
-The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` provides the position setpoint. 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.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. While we don't call `disarm()` in this example, it is also used in the implementation of that function.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-:::note
-[VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. :::note [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful.
-:::
-
-
-
+
diff --git a/ja/SUMMARY.md b/ja/SUMMARY.md
index 55c45c0b8043..e4bd37d85eab 100644
--- a/ja/SUMMARY.md
+++ b/ja/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/ja/msg_docs/index.md b/ja/msg_docs/index.md
index 61cd506b8777..0a1847929917 100644
--- a/ja/msg_docs/index.md
+++ b/ja/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/ja/ros/mavros_installation.md b/ja/ros/mavros_installation.md
index ad6411702789..79cfe1554c58 100644
--- a/ja/ros/mavros_installation.md
+++ b/ja/ros/mavros_installation.md
@@ -20,7 +20,9 @@ These instructions are a simplified version of the [official installation guide]
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ These instructions are a simplified version of the [official installation guide]
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/ja/ros/ros2.md b/ja/ros/ros2.md
index 9552c43297b4..9b483f856475 100644
--- a/ja/ros/ros2.md
+++ b/ja/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) is the newest version of [ROS](http://www.ros.org/) (Robot Operating System), a general purpose robotics library that can be used with the PX4 Autopilot to create powerful drone applications. It captures most of the learnings and features of [ROS 1](../ros/ros1.md), improving a number of flaws of the earlier version.
-
-:::warning
-Tip
-The PX4 development team highly recommend that you use/migrate to this version of ROS!
-:::
-
-Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. The middleware uses uORB message definitions to generate code to serialise and deserialise the messages heading in and out of PX4. These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-To use the [ROS 2](../ros/ros2_comm.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. In the near term future we plan to provide ROS 2 APIs to abstract PX4 conventions, along with examples demonstrating their use.
-
-The main topics in this section are:
-- [ROS 2 User Guide](../ros/ros2_comm.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4.
-- [ROS 2 Offboard Control Example](../ros/ros2_offboard_control.md)
-
-::: info
-ROS 2 is officially supported only on Linux platforms.
-Ubuntu 20.04 LTS is the official supported distribution.
-:::
-
-
-::: info ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). This option is supported by the MAVROS project.
-:::
-
-
-## Further Reading/Information
-
-- [ROS 2 User Guide](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2.
-
+
diff --git a/ja/ros/ros2_comm.md b/ja/ros/ros2_comm.md
index 72e0174d9f19..47f18ae25603 100644
--- a/ja/ros/ros2_comm.md
+++ b/ja/ros/ros2_comm.md
@@ -1,754 +1 @@
-# ROS 2 User Guide
-
-The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
-
-This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
-
-::: info From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## Overview
-
-The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware.
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
-
-The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
-
-ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
-
-Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
-
-You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
-
-::: info In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). This repo is no longer needed, but does contain useful examples.
-:::
-
-
-## Installation & Setup
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-::: info PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [Install PX4](#install-px4) (to use the PX4 simulator)
-- [Install ROS 2](#install-ros-2)
-- [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client)
-- [Build & Run ROS 2 Workspace](#build-ros-2-workspace)
-
-Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered.
-
-
-### Install PX4
-
-You need to install the PX4 development toolchain in order to use the simulator.
-
-::: info The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics.
-:::
-
-Set up a PX4 development environment on Ubuntu in the normal way:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### Install ROS 2
-
-To install ROS 2 and its dependencies:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
- ::::
-
-1. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Setup Micro XRCE-DDS Agent & Client
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### Setup the Agent
-
-The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
-
-To setup and start the agent:
-
-1. Open a terminal.
-1. Enter the following commands to fetch and build the agent from source:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-The agent is now running, but you won't see much until we start PX4 (in the next step).
-
-::: info
-You can leave the agent running in this terminal!
-Note that only one agent is allowed per connection channel.
-:::
-
-#### Start the Client
-
-The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
-
-To start the simulator (and client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-The agent and client are now running they should connect.
-
-The PX4 terminal displays the [NuttShell/PX4 System Console](../debug/system_console.md) output as PX4 boots and runs. As soon as the agent connects the output should include `INFO` messages showing creation of data writers:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Build ROS 2 Workspace
-
-This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere).
-
-The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`.
-
-::: info The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- ::: info
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-::: info The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 Example Applications
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-::: info [Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-::: info The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-The instantiation of the `SensorCombinedListener` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-::: info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-The `ros2 launch` command is used to start a ROS 2 launch file. For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Additional information
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/ja/ros/ros2_multi_vehicle.md b/ja/ros/ros2_multi_vehicle.md
index b48ee1b0b988..6449c4011507 100644
--- a/ja/ros/ros2_multi_vehicle.md
+++ b/ja/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-::: info
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-::: info
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/ja/ros/ros2_offboard_control.md b/ja/ros/ros2_offboard_control.md
index 47ba05d2a69b..ad1f47e679c4 100644
--- a/ja/ros/ros2_offboard_control.md
+++ b/ja/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 Offboard Control Example
-
-The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
-
-The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits. While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
-
-It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 `main` after PX4 v1.13.
-
-:::warning
-*Offboard* control is dangerous. If you are operating on a real vehicle be sure to have a way of gaining back manual control in case something goes wrong.
-:::
-
-::: info ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). There is no implicit conversion between frame types when topics are published or subscribed!
-
-This example publishes positions in the NED frame, as expected by PX4. To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library.
-:::
-
-## Trying it out
-
-Follow the instructions in [ROS 2 User Guide](../ros/ros2_comm.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
-
-After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros/ros2_comm.md#build-ros-2-workspace) to run the example.
-
-To build and run the example:
-
-1. Open a new terminal.
-1. Create and navigate into a new colcon workspace directory using:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Launch the example.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-The vehicle should arm, ascend 5 metres, and then wait (perpetually).
-
-## Implementation
-
-The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-::: info PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. The required behaviour is implemented by the main loop spinning in the ROS 2 node, as shown below:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-The loop runs on a 100ms timer. For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4. The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode).
-
-After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. After the vehicle arms and changes mode it starts tracking the position setpoints. The setpoints are still sent in every cycle so that the vehicle does not fall out of offboard mode.
-
-The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively).
-
-The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` provides the position setpoint. 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.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. While we don't call `disarm()` in this example, it is also used in the implementation of that function.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-::: info [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. The param and command fields map to [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands) and their parameter values.
-:::
-
-
-
+
diff --git a/ko/SUMMARY.md b/ko/SUMMARY.md
index eebf4cc76eea..c882debe4b0f 100644
--- a/ko/SUMMARY.md
+++ b/ko/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/ko/msg_docs/index.md b/ko/msg_docs/index.md
index 61cd506b8777..0a1847929917 100644
--- a/ko/msg_docs/index.md
+++ b/ko/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/ko/ros/mavros_installation.md b/ko/ros/mavros_installation.md
index 9cb7458fc53e..9594cc20be02 100644
--- a/ko/ros/mavros_installation.md
+++ b/ko/ros/mavros_installation.md
@@ -20,7 +20,9 @@ This section explains how to install [ROS 1](../ros/index.md) with PX4. ROS 1 fu
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ This section explains how to install [ROS 1](../ros/index.md) with PX4. ROS 1 fu
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/ko/ros/ros2.md b/ko/ros/ros2.md
index d8ecce7240bc..9b483f856475 100644
--- a/ko/ros/ros2.md
+++ b/ko/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/)는 PX4 자동조종장치와 사용하여 강력한 드론 애플리케이션을 만들 수 있는 범용 로봇 라이브러리인 [ROS](http://www.ros.org/)(Robot Operating System)의 최신 버전입니다. It captures most of the learnings and features of [ROS 1](../ros/ros1.md), improving a number of flaws of the earlier version.
-
-:::warning
-Tip
-PX4 개발 팀은 이 버전의 ROS를 마이그레이션할 것을 적극 권장합니다!
-:::
-
-Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. The middleware uses uORB message definitions to generate code to serialise and deserialise the messages heading in and out of PX4. These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-To use the [ROS 2](../ros/ros2_comm.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. In the near term future we plan to provide ROS 2 APIs to abstract PX4 conventions, along with examples demonstrating their use.
-
-이 섹션의 주요 주제는 다음과 같습니다.
-- [ROS 2 User Guide](../ros/ros2_comm.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4.
-- [ROS 2 Offboard Control Example](../ros/ros2_offboard_control.md)
-
-::: info
-ROS 2 is officially supported only on Linux platforms.
-Ubuntu 20.04 LTS는 공식적으로 지원되는 배포판입니다.
-:::
-
-
-::: info ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). This option is supported by the MAVROS project.
-:::
-
-
-## 추가 읽기/정보
-
-- [ROS 2 User Guide](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2.
-
+
diff --git a/ko/ros/ros2_comm.md b/ko/ros/ros2_comm.md
index 22d27ca2dfb1..47f18ae25603 100644
--- a/ko/ros/ros2_comm.md
+++ b/ko/ros/ros2_comm.md
@@ -1,753 +1 @@
-# ROS 2 User Guide
-
-The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
-
-This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
-
-::: info From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## 개요
-
-The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware.
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
-
-The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
-
-ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
-
-Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
-
-You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
-
-::: info In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). This repo is no longer needed, but does contain useful examples.
-:::
-
-
-## 설치 및 설정
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-::: info PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [Install PX4](#install-px4) (to use the PX4 simulator)
-- [ROS2 설치](#install-ros-2)
-- [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client)
-- [Build & Run ROS 2 Workspace](#build-ros-2-workspace)
-
-Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered.
-
-
-### Install PX4
-
-You need to install the PX4 development toolchain in order to use the simulator.
-
-::: info The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics.
-:::
-
-Set up a PX4 development environment on Ubuntu in the normal way:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### ROS2 설치
-
-To install ROS 2 and its dependencies:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`). 특히 `--verbose` 인수는 전체 *colcon* 빌드 출력을 보여줍니다.
-
- ::::
-
-1. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Setup Micro XRCE-DDS Agent & Client
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### Setup the Agent
-
-The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
-
-To setup and start the agent:
-
-1. Open a terminal.
-1. Enter the following commands to fetch and build the agent from source:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-The agent is now running, but you won't see much until we start PX4 (in the next step).
-
-::: info
-You can leave the agent running in this terminal!
-Note that only one agent is allowed per connection channel.
-:::
-
-#### Start the Client
-
-The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
-
-To start the simulator (and client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-The agent and client are now running they should connect.
-
-The PX4 terminal displays the [NuttShell/PX4 System Console](../debug/system_console.md) output as PX4 boots and runs. As soon as the agent connects the output should include `INFO` messages showing creation of data writers:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### ROS 2 작업 공간 빌드
-
-This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere).
-
-The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`.
-
-::: info The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- ::: info
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-::: info The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 예제 애플리케이션
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-::: info [Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-아래 줄은 하나 이상의 호환 가능한 ROS 게시자와 일치시킬 수 있는 `sensor_combined_topic`에 대한 구독을 만듭니다.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-::: info The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-`px4_ros_com/src/advertisers` 아래의 `debug_vect_advertiser.cpp`를 예로 들면 먼저 `debug_vect` msg 헤더를 포함한 필수 헤더를 가져옵니다.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-그런 다음 코드는 일반 `rclcpp::Node` 기본 클래스의 하위 클래스인 `DebugVectAdvertiser` 클래스를 생성합니다.
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-```
-
-`DebugVectAdvertiser` 클래스를 ROS 노드로 인스턴스화하는 작업은 `main` 함수에서 수행됩니다.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("DebugVect_PubSubTopic", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### 오프보드 제어
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-::: info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-The `ros2 launch` command is used to start a ROS 2 launch file. For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- $ git clone https://github.com/PX4/px4_ros_com.git ~/px4_ros_com_ros2/src/px4_ros_com
- $ git clone https://github.com/PX4/px4_msgs.git ~/px4_ros_com_ros2/src/px4_msgs
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- $ cd ~/px4_ros_com_ros2/src/px4_ros_com/scripts
- $ source build_ros2_workspace.bash
- ```
-
-:::
-
- ::::
-
-
-## 추가 정보
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS와 ROS 미들웨어 구현](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/ko/ros/ros2_multi_vehicle.md b/ko/ros/ros2_multi_vehicle.md
index b48ee1b0b988..6449c4011507 100644
--- a/ko/ros/ros2_multi_vehicle.md
+++ b/ko/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-::: info
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-::: info
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/ko/ros/ros2_offboard_control.md b/ko/ros/ros2_offboard_control.md
index b793908dcd95..ad1f47e679c4 100644
--- a/ko/ros/ros2_offboard_control.md
+++ b/ko/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 오프보드 제어 예
-
-The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
-
-The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits. While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
-
-It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 `main` after PX4 v1.13.
-
-:::warning
-*오프보드* 제어는 위험합니다. 실제 차량에서 작동하는 경우 문제가 발생하면, 다시 수동 제어를 할 수 있어야 합니다.
-:::
-
-::: info ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). There is no implicit conversion between frame types when topics are published or subscribed!
-
-This example publishes positions in the NED frame, as expected by PX4. To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library.
-:::
-
-## Trying it out
-
-Follow the instructions in [ROS 2 User Guide](../ros/ros2_comm.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
-
-After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros/ros2_comm.md#build-ros-2-workspace) to run the example.
-
-To build and run the example:
-
-1. Open a new terminal.
-1. Create and navigate into a new colcon workspace directory using:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Launch the example.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-The vehicle should arm, ascend 5 metres, and then wait (perpetually).
-
-## 구현
-
-The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-::: info PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. The required behaviour is implemented by the main loop spinning in the ROS 2 node, as shown below:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-The loop runs on a 100ms timer. For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4. The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode).
-
-After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. After the vehicle arms and changes mode it starts tracking the position setpoints. The setpoints are still sent in every cycle so that the vehicle does not fall out of offboard mode.
-
-The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively).
-
-The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` provides the position setpoint. 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.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. While we don't call `disarm()` in this example, it is also used in the implementation of that function.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-::: info [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. The param and command fields map to [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands) and their parameter values.
-:::
-
-
-
+
diff --git a/ru/SUMMARY.md b/ru/SUMMARY.md
index 65bb404a3f1a..636d8103af0f 100644
--- a/ru/SUMMARY.md
+++ b/ru/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/ru/msg_docs/index.md b/ru/msg_docs/index.md
index 61cd506b8777..0a1847929917 100644
--- a/ru/msg_docs/index.md
+++ b/ru/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/ru/ros/mavros_installation.md b/ru/ros/mavros_installation.md
index ad6411702789..79cfe1554c58 100644
--- a/ru/ros/mavros_installation.md
+++ b/ru/ros/mavros_installation.md
@@ -20,7 +20,9 @@ These instructions are a simplified version of the [official installation guide]
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ These instructions are a simplified version of the [official installation guide]
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/ru/ros/ros2.md b/ru/ros/ros2.md
index 9552c43297b4..9b483f856475 100644
--- a/ru/ros/ros2.md
+++ b/ru/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) is the newest version of [ROS](http://www.ros.org/) (Robot Operating System), a general purpose robotics library that can be used with the PX4 Autopilot to create powerful drone applications. It captures most of the learnings and features of [ROS 1](../ros/ros1.md), improving a number of flaws of the earlier version.
-
-:::warning
-Tip
-The PX4 development team highly recommend that you use/migrate to this version of ROS!
-:::
-
-Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. The middleware uses uORB message definitions to generate code to serialise and deserialise the messages heading in and out of PX4. These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-To use the [ROS 2](../ros/ros2_comm.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. In the near term future we plan to provide ROS 2 APIs to abstract PX4 conventions, along with examples demonstrating their use.
-
-The main topics in this section are:
-- [ROS 2 User Guide](../ros/ros2_comm.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4.
-- [ROS 2 Offboard Control Example](../ros/ros2_offboard_control.md)
-
-::: info
-ROS 2 is officially supported only on Linux platforms.
-Ubuntu 20.04 LTS is the official supported distribution.
-:::
-
-
-::: info ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). This option is supported by the MAVROS project.
-:::
-
-
-## Further Reading/Information
-
-- [ROS 2 User Guide](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2.
-
+
diff --git a/ru/ros/ros2_comm.md b/ru/ros/ros2_comm.md
index 72e0174d9f19..47f18ae25603 100644
--- a/ru/ros/ros2_comm.md
+++ b/ru/ros/ros2_comm.md
@@ -1,754 +1 @@
-# ROS 2 User Guide
-
-The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
-
-This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
-
-::: info From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## Overview
-
-The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware.
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
-
-The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
-
-ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
-
-Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
-
-You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
-
-::: info In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). This repo is no longer needed, but does contain useful examples.
-:::
-
-
-## Installation & Setup
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-::: info PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [Install PX4](#install-px4) (to use the PX4 simulator)
-- [Install ROS 2](#install-ros-2)
-- [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client)
-- [Build & Run ROS 2 Workspace](#build-ros-2-workspace)
-
-Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered.
-
-
-### Install PX4
-
-You need to install the PX4 development toolchain in order to use the simulator.
-
-::: info The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics.
-:::
-
-Set up a PX4 development environment on Ubuntu in the normal way:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### Install ROS 2
-
-To install ROS 2 and its dependencies:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
- ::::
-
-1. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Setup Micro XRCE-DDS Agent & Client
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### Setup the Agent
-
-The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
-
-To setup and start the agent:
-
-1. Open a terminal.
-1. Enter the following commands to fetch and build the agent from source:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-The agent is now running, but you won't see much until we start PX4 (in the next step).
-
-::: info
-You can leave the agent running in this terminal!
-Note that only one agent is allowed per connection channel.
-:::
-
-#### Start the Client
-
-The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
-
-To start the simulator (and client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-The agent and client are now running they should connect.
-
-The PX4 terminal displays the [NuttShell/PX4 System Console](../debug/system_console.md) output as PX4 boots and runs. As soon as the agent connects the output should include `INFO` messages showing creation of data writers:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Build ROS 2 Workspace
-
-This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere).
-
-The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`.
-
-::: info The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- ::: info
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-::: info The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 Example Applications
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-::: info [Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-::: info The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-The instantiation of the `SensorCombinedListener` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-::: info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-The `ros2 launch` command is used to start a ROS 2 launch file. For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Additional information
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/ru/ros/ros2_multi_vehicle.md b/ru/ros/ros2_multi_vehicle.md
index b48ee1b0b988..6449c4011507 100644
--- a/ru/ros/ros2_multi_vehicle.md
+++ b/ru/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-::: info
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-::: info
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/ru/ros/ros2_offboard_control.md b/ru/ros/ros2_offboard_control.md
index 47ba05d2a69b..ad1f47e679c4 100644
--- a/ru/ros/ros2_offboard_control.md
+++ b/ru/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 Offboard Control Example
-
-The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
-
-The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits. While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
-
-It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 `main` after PX4 v1.13.
-
-:::warning
-*Offboard* control is dangerous. If you are operating on a real vehicle be sure to have a way of gaining back manual control in case something goes wrong.
-:::
-
-::: info ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). There is no implicit conversion between frame types when topics are published or subscribed!
-
-This example publishes positions in the NED frame, as expected by PX4. To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library.
-:::
-
-## Trying it out
-
-Follow the instructions in [ROS 2 User Guide](../ros/ros2_comm.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
-
-After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros/ros2_comm.md#build-ros-2-workspace) to run the example.
-
-To build and run the example:
-
-1. Open a new terminal.
-1. Create and navigate into a new colcon workspace directory using:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Launch the example.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-The vehicle should arm, ascend 5 metres, and then wait (perpetually).
-
-## Implementation
-
-The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-::: info PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. The required behaviour is implemented by the main loop spinning in the ROS 2 node, as shown below:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-The loop runs on a 100ms timer. For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4. The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode).
-
-After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. After the vehicle arms and changes mode it starts tracking the position setpoints. The setpoints are still sent in every cycle so that the vehicle does not fall out of offboard mode.
-
-The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively).
-
-The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` provides the position setpoint. 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.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. While we don't call `disarm()` in this example, it is also used in the implementation of that function.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-::: info [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. The param and command fields map to [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands) and their parameter values.
-:::
-
-
-
+
diff --git a/tr/SUMMARY.md b/tr/SUMMARY.md
index 65bb404a3f1a..636d8103af0f 100644
--- a/tr/SUMMARY.md
+++ b/tr/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/tr/msg_docs/index.md b/tr/msg_docs/index.md
index 61cd506b8777..0a1847929917 100644
--- a/tr/msg_docs/index.md
+++ b/tr/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Graphs showing how these are used [can be found here](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/tr/ros/mavros_installation.md b/tr/ros/mavros_installation.md
index ad6411702789..79cfe1554c58 100644
--- a/tr/ros/mavros_installation.md
+++ b/tr/ros/mavros_installation.md
@@ -20,7 +20,9 @@ These instructions are a simplified version of the [official installation guide]
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ These instructions are a simplified version of the [official installation guide]
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/tr/ros/ros2.md b/tr/ros/ros2.md
index 9552c43297b4..9b483f856475 100644
--- a/tr/ros/ros2.md
+++ b/tr/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) is the newest version of [ROS](http://www.ros.org/) (Robot Operating System), a general purpose robotics library that can be used with the PX4 Autopilot to create powerful drone applications. It captures most of the learnings and features of [ROS 1](../ros/ros1.md), improving a number of flaws of the earlier version.
-
-:::warning
-Tip
-The PX4 development team highly recommend that you use/migrate to this version of ROS!
-:::
-
-Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. The middleware uses uORB message definitions to generate code to serialise and deserialise the messages heading in and out of PX4. These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-To use the [ROS 2](../ros/ros2_comm.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. In the near term future we plan to provide ROS 2 APIs to abstract PX4 conventions, along with examples demonstrating their use.
-
-The main topics in this section are:
-- [ROS 2 User Guide](../ros/ros2_comm.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4.
-- [ROS 2 Offboard Control Example](../ros/ros2_offboard_control.md)
-
-::: info
-ROS 2 is officially supported only on Linux platforms.
-Ubuntu 20.04 LTS is the official supported distribution.
-:::
-
-
-::: info ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). This option is supported by the MAVROS project.
-:::
-
-
-## Further Reading/Information
-
-- [ROS 2 User Guide](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2.
-
+
diff --git a/tr/ros/ros2_comm.md b/tr/ros/ros2_comm.md
index 72e0174d9f19..47f18ae25603 100644
--- a/tr/ros/ros2_comm.md
+++ b/tr/ros/ros2_comm.md
@@ -1,754 +1 @@
-# ROS 2 User Guide
-
-The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
-
-This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
-
-::: info From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## Overview
-
-The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware.
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
-
-The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
-
-ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
-
-Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
-
-You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
-
-::: info In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). This repo is no longer needed, but does contain useful examples.
-:::
-
-
-## Installation & Setup
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-::: info PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [Install PX4](#install-px4) (to use the PX4 simulator)
-- [Install ROS 2](#install-ros-2)
-- [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client)
-- [Build & Run ROS 2 Workspace](#build-ros-2-workspace)
-
-Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered.
-
-
-### Install PX4
-
-You need to install the PX4 development toolchain in order to use the simulator.
-
-::: info The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics.
-:::
-
-Set up a PX4 development environment on Ubuntu in the normal way:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### Install ROS 2
-
-To install ROS 2 and its dependencies:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
- ::::
-
-1. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Setup Micro XRCE-DDS Agent & Client
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### Setup the Agent
-
-The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
-
-To setup and start the agent:
-
-1. Open a terminal.
-1. Enter the following commands to fetch and build the agent from source:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-The agent is now running, but you won't see much until we start PX4 (in the next step).
-
-::: info
-You can leave the agent running in this terminal!
-Note that only one agent is allowed per connection channel.
-:::
-
-#### Start the Client
-
-The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
-
-To start the simulator (and client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-The agent and client are now running they should connect.
-
-The PX4 terminal displays the [NuttShell/PX4 System Console](../debug/system_console.md) output as PX4 boots and runs. As soon as the agent connects the output should include `INFO` messages showing creation of data writers:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Build ROS 2 Workspace
-
-This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere).
-
-The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`.
-
-::: info The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- ::: info
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-::: info The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 Example Applications
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-::: info [Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-::: info The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-The instantiation of the `SensorCombinedListener` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-::: info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-The `ros2 launch` command is used to start a ROS 2 launch file. For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Additional information
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/tr/ros/ros2_multi_vehicle.md b/tr/ros/ros2_multi_vehicle.md
index b48ee1b0b988..6449c4011507 100644
--- a/tr/ros/ros2_multi_vehicle.md
+++ b/tr/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-::: info
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-::: info
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/tr/ros/ros2_offboard_control.md b/tr/ros/ros2_offboard_control.md
index 47ba05d2a69b..ad1f47e679c4 100644
--- a/tr/ros/ros2_offboard_control.md
+++ b/tr/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 Offboard Control Example
-
-The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
-
-The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits. While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
-
-It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 `main` after PX4 v1.13.
-
-:::warning
-*Offboard* control is dangerous. If you are operating on a real vehicle be sure to have a way of gaining back manual control in case something goes wrong.
-:::
-
-::: info ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). There is no implicit conversion between frame types when topics are published or subscribed!
-
-This example publishes positions in the NED frame, as expected by PX4. To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library.
-:::
-
-## Trying it out
-
-Follow the instructions in [ROS 2 User Guide](../ros/ros2_comm.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
-
-After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros/ros2_comm.md#build-ros-2-workspace) to run the example.
-
-To build and run the example:
-
-1. Open a new terminal.
-1. Create and navigate into a new colcon workspace directory using:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Launch the example.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-The vehicle should arm, ascend 5 metres, and then wait (perpetually).
-
-## Implementation
-
-The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-::: info PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. The required behaviour is implemented by the main loop spinning in the ROS 2 node, as shown below:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-The loop runs on a 100ms timer. For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4. The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode).
-
-After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. After the vehicle arms and changes mode it starts tracking the position setpoints. The setpoints are still sent in every cycle so that the vehicle does not fall out of offboard mode.
-
-The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively).
-
-The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` provides the position setpoint. 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.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. While we don't call `disarm()` in this example, it is also used in the implementation of that function.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-::: info [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. The param and command fields map to [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands) and their parameter values.
-:::
-
-
-
+
diff --git a/uk/SUMMARY.md b/uk/SUMMARY.md
index c18b96d685de..b6df2ad71800 100644
--- a/uk/SUMMARY.md
+++ b/uk/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/uk/msg_docs/index.md b/uk/msg_docs/index.md
index 03b0f70e1b26..d1e56c1c2b3b 100644
--- a/uk/msg_docs/index.md
+++ b/uk/msg_docs/index.md
@@ -3,7 +3,7 @@
:::info Цей список [автоматично згенеровано](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) з вихідного коду.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). Графи, що показують, як вони використовуються [можна знайти тут](../middleware/uorb_graph.md).
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). Графи, що показують, як вони використовуються [можна знайти тут](../middleware/uorb_graph.md).
- [ActionRequest](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/uk/ros/mavros_installation.md b/uk/ros/mavros_installation.md
index f374f8742ce1..e3807e16ba91 100644
--- a/uk/ros/mavros_installation.md
+++ b/uk/ros/mavros_installation.md
@@ -20,7 +20,9 @@ This section explains how to install [ROS 1](../ros/index.md) with PX4. ROS 1 fu
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -50,7 +52,9 @@ This section explains how to install [ROS 1](../ros/index.md) with PX4. ROS 1 fu
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/uk/ros/ros2.md b/uk/ros/ros2.md
index b9af26b7e058..9b483f856475 100644
--- a/uk/ros/ros2.md
+++ b/uk/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) є найновішою версією [ROS](http://www.ros.org/) (Robot Operating System), загальна мета бібліотеки робототехніки для якої може бути використана - це для створення потужних застосунків для дронів разом з PX4 Autopilot. Він охоплює більшість навчальних функцій і опцій [ROS 1](../ros/ros1.md) та покращує ряд недоліків попередньої версії.
-
-:::warning
-Tip
-Команда розробників PX4 наполегливо рекомендуємо вам використовувати/перейти на цю версію ROS!
-:::
-
-Спілкування між ROS 2 і PX4 використовує проміжне програмне забезпечення, яке реалізує протокол [XRCE-DDS](../middleware/uxrce_dds.md). Цей посередник використовує PX4 повідомлення[uORB messages](../msg_docs/README.md) у вигляді повідомлень та типів ROS 2, що ефективно дозволяє прямий доступ до PX4 з робочих процесів та вузлів ROS 2. Проміжна програма використовує визначення повідомлень uORB для генерації коду для серіалізації та десеріалізації заголовків повідомлень PX4. Ці ж визначення повідомлень використовуються в програмах ROS 2, щоб дозволити інтерпретувати повідомлення.
-
-Для ефективного використання [ROS 2](../ros/ros2_comm.md) через XRCE-DDS вам потрібно (на момент написання) мати достатнє розуміння внутрішньої архітектури та конвенцій PX4, які відрізняються від тих, що використовуються в ROS. У найближчому майбутньому ми плануємо надати ROS 2 API до абстрактних конвенцій PX4, разом із прикладами, що демонструють їх використання.
-
-Основні теми в цьому розділі є:
-- [ROS 2 Посібник користувача](../ros/ros2_comm.md): PX4-центричний огляд ROS 2, включаючи встановлення, налаштування і спосіб створення додатків ROS 2 які спілкуються з PX4.
-- [ROS 2 приклад зовнішнього контролю](../ros/ros2_offboard_control.md)
-
-:::info
-ROS 2 офіційно підтримується тільки на платформах Linux.
-Ubuntu 20.04 LTS є офіційним, підтримуваним дистрибутивом.
-:::
-
-
-:::info ROS 2 також може з’єднуватися з PX4 за допомогою [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (замість XRCE-DDS). Ця опція підтримується проектом MAVROS.
-:::
-
-
-## Додаткова інформація
-
-- [ROS 2 Посібник користувача](../ros/ros2_comm.md)
-- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 проміжне програмне забезпечення для підключення до ROS 2.
-
+
diff --git a/uk/ros/ros2_comm.md b/uk/ros/ros2_comm.md
index 505bbaf366a2..47f18ae25603 100644
--- a/uk/ros/ros2_comm.md
+++ b/uk/ros/ros2_comm.md
@@ -1,754 +1 @@
-# ROS 2 Посібник користувача
-
-Архітектура ROS 2-PX4 забезпечує глибоку інтеграцію між ROS 2 і PX4, дозволяючи підписникам ROS 2 або вузлам видавців безпосередньо взаємодіяти з темами uORB PX4.
-
-Ця тема містить огляд архітектури та пайплайну додатків, а також пояснює, як налаштувати та використовувати ROS 2 з PX4.
-
-:::info Починаючи з PX4 v1.14, ROS 2 використовує проміжне програмне забезпечення [uXRCE-DDS](../middleware/uxrce_dds.md), яке замінило проміжне програмне забезпечення _FastRTPS_, що використовувалося у версії 1.13 (версія 1.13 не підтримує uXRCE-DDS).
-
-У [посібнику з міграції](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) пояснюється, що потрібно зробити, щоб перенести програми ROS 2 з PX4 v1.13 на PX4 v1.14.
-
-Якщо ви досі працюєте на PX4 v1.13, дотримуйтесь інструкцій в [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## Загальний огляд
-
-Пайплайн додатків для ROS 2 дуже простий завдяки використанню комунікаційного проміжного програмного забезпечення [uXRCE-DDS](../middleware/uxrce_dds.md).
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-Проміжне програмне забезпечення uXRCE-DDS складається з клієнта, що працює на PX4, і агента, що працює на комп'ютері-компаньйоні, з двостороннім обміном даними між ними по послідовному, UDP, TCP або користувацькому каналу зв'язку. Агент діє як проксі для клієнта з метою публікації та підписки на теми в глобальному просторі даних DDS.
-
-PX4 [клієнт uxrce_dds](../modules/modules_system.md#uxrce-dds-client) генерується під час збірки та за замовчуванням включений у прошивку PX4. Він включає як код клієнта "загального" мікро XRCE-DDS, так і код перекладу, специфічний для PX4, який він використовує для публікації/передачі даних з/у теми uORB. Підмножина повідомлень uORB, які генеруються в клієнті, перелічені в [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Генератор використовує визначення повідомлень uORB у дереві джерела: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg), щоб створити код для відправлення повідомлень ROS 2.
-
-Програми ROS 2 потрібно створювати в робочій області, яка має _ті самі_ визначення повідомлень, які використовувалися для створення клієнтського модуля uXRCE-DDS у мікропрограмі PX4. Ви можете включити їх, клонуючи інтерфейсний пакет [PX4/px4_msgs](https://github.com/PX4/px4_msgs) у своє робоче середовище ROS 2 (гілки у репозиторії відповідають повідомленням для різних випусків PX4).
-
-Зверніть увагу, що сам по собі _агент_ micro XRCE-DDS <0>не має залежності0> від клієнтського коду. Це може бути побудовано з [вихідний код](https://github.com/eProsima/Micro-XRCE-DDS-Agent) або як самостійний елемент, або як частина збірки ROS, або встановлено як snap.
-
-Зазвичай вам потрібно запустити як клієнт, так і агента при використанні ROS 2. Зверніть увагу, що клієнт uXRCE-DDS вбудований в прошивку за замовчуванням, але не запускається автоматично, за винятком збірок симулятора.
-
-:::info У PX4v1.13 та раніше, ROS 2 був залежний від визначень у [px4_ros_com](https://github.com/PX4/px4_ros_com). Цей репозиторій більше не потрібен, але містить корисні приклади.
-:::
-
-
-## Встановлення та налаштування
-
-Підтримувані платформи ROS 2 для розробки PX4 - ROS 2 "Humble" на Ubuntu 22.04 та ROS 2 "Foxy" на Ubuntu 20.04.
-
-ROS 2 "Humble" рекомендується, оскільки це поточний розподіл ROS 2 LTS. ROS 2 "Foxy" досягла кінця свого життя в травні 2023 року, але все ще стабільна і працює з PX4.
-
-::: info PX4 не так добре протестований на Ubuntu 22.04, як на Ubuntu 20.04 (на момент написання), і Ubuntu 20.04 потрібний, якщо ви хочете використовувати [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-Для налаштування ROS 2 для використання з PX4:
-
-- [Встановити PX4](#install-px4) (для використання симулятора PX4)
-- [Встановіть ROS 2](#install-ros-2)
-- [Налаштування агента та клієнта Micro XRCE-DDS](#setup-micro-xrce-dds-agent-client)
-- [Створіть та запустіть робоче середовище ROS 2](#build-ros-2-workspace)
-
-Інші залежності архітектури, які встановлюються автоматично, такі як _Fast DDS_, не враховуються.
-
-
-### Встановлення PX4
-
-Вам потрібно встановити інструментальний набір розробки PX4, щоб використовувати симулятор.
-
-:::info Єдиним залежністю ROS 2 від PX4 є набір визначень повідомлень, який він отримує з [px4_msgs](https://github.com/PX4/px4_msgs). Вам потрібно встановити PX4 лише в разі, якщо вам потрібен симулятор (як у цьому посібнику), або якщо ви створюєте збірку, яка публікує власні теми uORB.
-:::
-
-Налаштуйте середовище розробки PX4 на Ubuntu звичайним шляхом:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Зверніть увагу, що вищезазначені команди встановлять рекомендований симулятор для вашої версії Ubuntu. Якщо ви хочете встановити PX4, але зберегти вашу існуючу установку симулятора, запустіть `ubuntu.sh` вище з прапорцем `--no-sim-tools`.
-
-Для отримання додаткової інформації та усунення неполадок див. [Середовище розробки Ubuntu](../dev_setup/dev_env_linux_ubuntu.md) та [Завантажити вихідний код PX4](../dev_setup/building_px4.md).
-
-### Встановлення ROS 2
-
-Щоб встановити ROS 2 і його залежності:
-
-1. Встановлення ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- Інструкції вище відтворено з офіційного посібника з установки: [Встановлення ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). Ви можете встановити _або_ робочий стіл (`ros-humble-desktop`) _або_ мінімалістичні версії (`ros-humble-ros-base`), *і* засоби розробки (`ros-dev-tools`).
-:::
-
-
- :::tab foxy Щоб встановити ROS 2 "Foxy" на Ubuntu 20.04:
-
- - Дотримуйтесь офіційного посібника з встановлення: [Встановіть ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- Ви можете встановити _або_ робочий стіл (`ros-foxy-desktop`) _або_ мінімалістичні версії (`ros-foxy-ros-base`), *і* засоби розробки (`ros-dev-tools`).
-:::
-
- ::::
-
-1. Деякі Python залежності також мають бути встановленні (використовуючи **`pip`** або **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### Налаштування агента та клієнта Micro XRCE-DDS
-
-Для того щоб ROS 2 міг спілкуватися з PX4, [клієнт uXRCE-DDS](../modules/modules_system.md#uxrce-dds-client) повинен працювати на PX4, підключений до агента micro XRCE-DDS, який працює на компаньйоновому комп'ютері.
-
-#### Налаштувати агента
-
-Агент може бути встановлений на компаньйоновий комп'ютер [різними способами](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). Нижче ми покажемо, як побудувати агента "standalone" з вихідних кодів та підключитися до клієнта, який працює на симуляторі PX4.
-
-Для налаштування та запуску агента:
-
-1. Відкрийте термінал.
-1. Введіть наступні команди для витягування та побудови агента з вихідного коду:
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. Запустіть агента з налаштуваннями для підключення до клієнта uXRCE-DDS, який працює на симуляторі:
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-Агент зараз працює, але ви не побачите багато, поки ми не почнемо PX4 (у наступному кроці).
-
-::: інформація
-Ви можете залишити агента, що працює в цьому терміналі!
-Зверніть увагу, що дозволено лише одного агента на підключений канал зв'язку.
-:::
-
-#### Запустіть клієнта
-
-Симулятор PX4 автоматично запускає клієнт uXRCE-DDS, підключаючись до порту UDP 8888 на локальному хості.
-
-Для запуску симулятора (і клієнта):
-
-1. Відкрийте новий термінал в корені репозиторію **PX4 Autopilot**, який був встановлений вище.
-
- :::: tabs
-
- ::: tab humble
- - Розпочніть симуляцію PX4 у [Gazebo](../sim_gazebo_gz/index.md) за допомогою:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Почніть симуляцію PX4 [Симуляція Gazebo Classic](../sim_gazebo_classic/index.md) за допомогою:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-Агент та клієнт зараз працюють, вони повинні підключитися.
-
-Термінал PX4 відображає вивід [NuttShell/PX4 Системна Консоль](../debug/system_console.md) під час завантаження та роботи PX4. Як тільки агент підключає вихід, вивід повинен містити повідомлення `INFO`, що показують створення записувачів даних:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-Термінал агента micro XRCE-DDS також повинен почати показувати вивід, оскільки в мережі DDS створюються еквівалентні теми:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Створення робочого простору ROS 2
-
-Цей розділ показує, як створити робоче середовище ROS 2, розміщене в вашій домашній директорії (змініть команди за необхідності, щоб розмістити вихідний код в іншому місці).
-
-Пакети [px4_ros_com](https://github.com/PX4/px4_ros_com) та [px4_msgs](https://github.com/PX4/px4_msgs) клонуються до папки робочого простору, а потім використовується інструмент `colcon` для збірки робочого простору. Приклад виконується за допомогою `ros2 launch`.
-
-:::info Приклад будує [Приклад застосунку ROS 2 Listener](#ros-2-listener), розташований в [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) також потрібний, щоб приклад міг інтерпретувати теми PX4 ROS 2.
-:::
-
-
-#### Створення робочого простору
-
-Створити та побудувати робочий простір:
-
-1. Відкрийте новий термінал.
-1. Створіть новий каталог робочого простору та перейдіть до нього за допомогою:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- :::info
-Узгодження імен для папок робочого простору може полегшити керування робочим простором.
-:::
-
-1. Скопіюйте репозиторій прикладів і [px4_msgs](https://github.com/PX4/px4_msgs) до каталогу `/src` (за замовчуванням клоновано гілку `main`, яка відповідає версії PX4, яку ми запускаємо):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Створіть середовище розробки ROS 2 у поточному терміналі і скомпілюйте робочу область за допомогою `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- У результаті буде зібрано усі каталоги у `/src` за допомогою вихідного набору інструментів.
-
-
-#### Запуск прикладу
-
-Щоб запустити виконувані файли, які ви щойно побудували, вам потрібно джерело `local_setup.bash`. Це надає доступ до "гаків середовища" для поточного робочого простору. Іншими словами, воно робить виконувані файли, що були тільки що побудовані, доступними в поточному терміналі.
-
-:::info У [початкових навчальних посібниках ROS2](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) рекомендується _відкрити новий термінал_ для запуску ваших виконавчих файлів.
-:::
-
-В новому терміналі:
-
-1. Перейдіть на верхній рівень каталогу вашого робочого простору та джерело середовища ROS 2 (у цьому випадку "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Джерело `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Тепер запустіть приклад. Зверніть увагу, що тут ми використовуємо `ros2 launch`, який описано нижче.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-Якщо це працює, ви повинні бачити дані, які друкуються на терміналі / консолі, де ви запустили слухача ROS:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Керування Транспортним Засобом
-
-Для контролю за додатками, додатки ROS 2:
-
-- підписатися на (слухати) тематичні теми, опубліковані PX4
-- опублікувати у темах, які спонукають PX4 виконати певну дію.
-
-Теми, які ви можете використовувати, визначені в [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), і ви можете отримати більше інформації про їх дані в [Посилання на повідомлення uORB](../msg_docs/index.md). Наприклад, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) може бути використано для отримання глобального положення транспортного засобу, тоді як [VehicleCommand](../msg_docs/VehicleCommand.md) може бути використано для виконання дій, таких як зльот та посадка.
-
-[Приклади застосувань ROS 2](#ros-2-example-applications), наведені нижче, надають конкретні приклади того, як використовувати ці теми.
-
-## Проблеми сумісності
-
-Цей розділ містить інформацію, яка може вплинути на те, як ви пишете свій код ROS.
-
-### Налаштування QoS підписника ROS 2
-
-Код ROS 2, який підписується на теми, опубліковані PX4, _повинен_ вказати відповідну (сумісну) настройку QoS, щоб слухати теми. Зокрема, вузли повинні підписатися, використовуючи попередньо визначену якість обслуговування даних сенсорів ROS 2 (з [прикладу вихідного коду слухача](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-Це потрібно, оскільки типові налаштування [Якості обслуговування (QoS)](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) ROS 2 відрізняються від налаштувань, що використовуються PX4. Не всі комбінації налаштувань якості обслуговування відправник-підписник [Qos можливі](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), і виявляється, що типові налаштування ROS 2 для підписки не є такими! Зверніть увагу, що код ROS не повинен встановлювати налаштування QoS при публікації (налаштування PX4 сумісні з типовими налаштуваннями ROS у цьому випадку).
-
-
-
-
-### Узгодження систем координат ROS 2 & PX4
-
-Локальна/світова та тілові системи координат, що використовуються в ROS та PX4, відрізняються.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-Дивіться [REP105: Системи координат для мобільних платформ](http://www.ros.org/reps/rep-0105.html) для отримання додаткової інформації про системи координат ROS.
-:::
-
-Обидві системи координат показані на зображенні нижче (FRD зліва / FLU справа).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-Конвенції FRD (NED) приймаються на **всі** теми PX4, якщо явно не вказано в відповідному визначенні повідомлення. Отже, вузли ROS 2, які хочуть співпрацювати з PX4, повинні дбати про конвенції кадрів.
-
-- Для повороту вектора з ENU на NED потрібно виконати дві основні обертання:
-
- - спочатку обертання на кут pi/2 навколо вісі `Z` (вгору),
- - потім обертання на кут пі навколо вісі `X` (старий схід/новий північ).
-- Для повороту вектора з NED на ENU потрібно виконати дві основні обертання:
--
- - спочатку обертання на кут pi/2 навколо вісі `Z` (вниз),
- - потім обертання на кут пі навколо вісі `X` (старий північ/новий схід). Зверніть увагу, що дві отримані операції математично еквівалентні.
-- Для обертання вектора з FLU на FRD достатньо обертання навколо вісі `X` (передньої) на пі.
-- Для обертання вектора з FRD на FLU достатньо обертання на пі радіан навколо вісі `X` (передній).
-
-Приклади векторів, які потребують обертання:
-
-- усі поля в повідомленні [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md); конвертація ENU в NED необхідна перед їхнім відправленням.
-- всі поля в повідомленні [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md); потрібно виконати конвертацію з FLU в FRD перед їх відправленням.
-
-Подібно до векторів, також кватерніони, що представляють відношення транспортного засобу (тіло) відносно. світова рамка потребує конвертації.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) надає спільну бібліотеку [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) для легкого виконання таких перетворень.
-
-### Синхронізація часу ROS, Gazebo та PX4
-
-За замовчуванням синхронізація часу між ROS 2 та PX4 автоматично керується проміжним ПЗ [uXRCE-DDS](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html), а статистика синхронізації часу доступна при прослуховуванні мостової теми `/fmu/out/timesync_status`. Коли клієнт uXRCE-DDS працює на контролері польоту, а агент працює на супутниковому комп'ютері, це є бажана поведінка, оскільки зміщення часу, дрейф часу та затримка у комунікації обчислюються та автоматично компенсуються.
-
-Для симуляцій Gazebo PX4 використовує тему Gazebo `/clock` як [джерело часу](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) замість. Цей годинник завжди трохи не синхронізований відносно. годинник операційної системи (фактор реального часу ніколи не є точно один) і він може навіть працювати набагато швидше або повільніше залежно від [переваг користувача](http://sdformat. org/spec? elem=physics&ver=1.9). Зверніть увагу, що це відрізняється від процедури [симуляційного блокування](../simulation/index.md#lockstep-simulation), яка була прийнята з Gazebo Classic.
-
-Користувачі ROS2 мають дві можливості щодо [джерела часу](https://design.ros2.org/articles/clock_and_time.html) їх вузлів.
-
-#### Вузли ROS2 використовують годинник ОС як джерело часу
-
-Цей сценарій, який розглядається на цій сторінці та в керівництві [offboard_control](./offboard_control.md), також є стандартною поведінкою вузлів ROS2. Годинник ОС діє як джерело часу, тому його можна використовувати лише тоді, коли фактор реального часу симуляції дуже близький до одиниці. Часовий синхронізатор клієнта uXRCE-DDS потім з'єднує годинник ОС на стороні ROS2 з годинником Gazebo на стороні PX4. Користувачеві не потрібно вживати жодних подальших заходів.
-
-#### Вузли ROS2 використовують годинник Gazebo як джерело часу
-
-У цьому сценарії ROS2 також використовує тему Gazebo `/clock` як джерело часу. Цей підхід має сенс, якщо симуляція Gazebo працює з коефіцієнтом реального часу, відмінним від одиниці, або якщо ROS2 потрібно безпосередньо взаємодіяти з Gazebo. На стороні ROS2 пряме взаємодія з Gazebo досягається за допомогою пакету [ros_gz_bridge](https://github.com/gazebosim/ros_gz) з репозиторію [ros_gz](https://github.com/gazebosim/ros_gz). Прочитайте [repo](https://github.com/gazebosim/ros_gz#readme) та [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs, щоб дізнатися правильну версію, яка повинна бути встановлена в залежності від вашої версії ROS2 та Gazebo.
-
-Якщо пакет встановлено та джерело підключено, вузол `parameter_bridge` надає можливості мостування і може бути використаний для створення одностороннього моста `/clock`:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-На цьому етапі кожному вузлу ROS2 необхідно бути інструкцією використовувати новостворену тему `/clock` як джерело часу замість ОС, це робиться шляхом встановлення параметра `use_sim_time` (кожного вузла) на `true` (див. [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-Це завершує внесені зміни, необхідні на стороні ROS2. На стороні PX4 вам потрібно лише зупинити синхронізацію часу uXRCE-DDS, встановивши параметр [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) на `false`. Таким чином, Gazebo буде діяти як основний і єдиний джерело часу як для ROS2, так і для PX4.
-
-## Приклади програм ROS 2
-
-### Слухач ROS 2
-
-Приклади слухачів ROS 2 [у репозиторії px4_ros_com](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) демонструють, як писати вузли ROS для прослуховування тем, що публікуються PX4.
-
-Тут ми розглядаємо вузол [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) у папці `px4_ros_com/src/examples/listeners`, який підписується на повідомлення [SensorCombined](../msg_docs/SensorCombined.md).
-
-:::info [Побудуйте робоче середовище ROS 2](#build-ros-2-workspace) показує, як побудувати та запустити цей приклад.
-:::
-
-Спочатку код імпортує бібліотеки C++, необхідні для взаємодії з проміжним програмним забезпеченням ROS 2 та файл заголовка для повідомлення `SensorCombined`, на яке підписується вузол:
-
-```cpp
-#include
-#include
-```
-
-Потім він створює клас `SensorCombinedListener`, який успадковує загальний базовий клас `rclcpp::Node`.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-Це створює функцію зворотного виклику для отримання повідомлень uORB `SensorCombined` (тепер як повідомлення micro XRCE-DDS) та виводить вміст полів повідомлення кожного разу, коли повідомлення отримано.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-:::info Підписка встановлює профіль QoS на основі `rmw_qos_profile_sensor_data`. Це потрібно, оскільки типовий профіль якості обслуговування ROS 2 для підписників несумісний з профілем PX4 для видавців. Для отримання додаткової інформації див. : [ROS 2 Налаштування QoS для підписника](#ros-2-subscriber-qos-settings),
-:::
-
-Рядки нижче створюють виробника для теми uORB `SensorCombined`, яка може бути зіставлена з одним або кількома сумісними підписниками ROS 2 для теми ROS 2 `fmu/sensor_combined/out`.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-Інстанціювання класу `SensorCombinedListener` як вузла ROS виконується у функції `main`.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-Цей конкретний приклад має пов'язаний файл запуску за посиланням [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). Це дозволяє запускати його за допомогою команди [`ros2 launch`](#ros2-launch).
-
-### ROS 2 Advertiser
-
-Вузол відправника ROS 2 публікує дані в мережу DDS/RTPS (і, отже, в автопілот PX4).
-
-Беручи як приклад `debug_vect_advertiser.cpp` під `px4_ros_com/src/advertisers`, спочатку ми імпортуємо необхідні заголовки, включаючи заголовок повідомлення `debug_vect`.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Потім код створює клас `DebugVectAdvertiser`, який успадковує загальний базовий клас `rclcpp::Node`.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-Код нижче створює функцію для відправлення повідомлень. Повідомлення надсилаються на основі виклику за часом, який надсилає два повідомлення на секунду за таймером.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-Інстанціювання класу `DebugVectAdvertiser` як вузла ROS виконується у функції `main`.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-Для повного прикладу посилання на те, як використовувати керування Offboard з PX4, див. : [Приклад керування Offboard ROS 2](../ros/ros2_offboard_control.md).
-
-## Використання апаратної плати керування польотом
-
-ROS 2 з PX4, що працює на пульті керування польотом, майже те саме, що й працювати з PX4 на симуляторі. Єдине відмінність полягає в тому, що потрібно запустити як агента, так і клієнта, з параметрами, відповідними для каналу зв'язку.
-
-Для отримання додаткової інформації дивіться [Початок uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Користувацькі теми uORB
-
-ROS 2 потребує мати ті _самі_ визначення повідомлень, які використовувалися для створення модуля клієнта uXRCE-DDS в прошивці PX4, щоб інтерпретувати повідомлення. Визначення зберігаються в пакеті інтерфейсу ROS 2 [PX4/px4_msgs](https://github.com/PX4/px4_msgs) і автоматично синхронізуються CI на гілках `main` та release. Зверніть увагу, що всі повідомлення з вихідного коду PX4 присутні в репозиторії, але лише ті, які перелічені в `dds_topics.yaml`, будуть доступні як теми ROS 2. Тому
-
-- Якщо ви використовуєте основну або випускову версію PX4, ви можете отримати визначення повідомлень, клонуючи пакунок інтерфейсу [PX4/px4_msgs](https://github.com/PX4/px4_msgs) у вашу робочу область.
-- Якщо ви створюєте або змінюєте повідомлення uORB, вам потрібно вручну оновити повідомлення у вашому робочому просторі з дерева джерела PX4. Загалом це означає, що ви мали б оновити [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), клонувати пакет інтерфейсу, а потім вручну синхронізувати його, копіюючи нові/змінені визначення повідомлень з [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) до його папок `msg`. Припускаючи, що PX4-Autopilot знаходиться у вашій домашній директорії `~`, тоді як `px4_msgs` знаходиться у `~/px4_ros_com/src/`, то команда може бути:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- :::info Технічно, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) повністю визначає відношення між темами PX4 uORB та повідомленнями ROS 2. Для отримання додаткової інформації див. [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Налаштування простору назв теми
-
-Спеціальні простори імен тем можуть бути застосовані на етапі збірки (зміна [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) або під час виконання (корисно для операцій з кількома транспортними засобами):
-
-- Одним із варіантів є використання опції `-n` при запуску [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) з командного рядка. Ця техніка може бути використана як у симуляційних, так і в реальних транспортних засобах.
-- Спеціальний простір імен може бути наданий для симуляцій (тільки) за допомогою встановлення змінної середовища `PX4_UXRCE_DDS_NS` перед запуском симуляції.
-
-
-:::info Зміна простору імен під час виконання додасть потрібний простір імен як префікс до всіх полів `topic` в [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Отже, команди, подібні до:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-або
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-згенерує теми під просторами імен:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-[ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) - це корисний інструмент для роботи з ROS. Ви можете використовувати його, наприклад, щоб швидко перевірити, чи публікуються теми, а також докладно їх перевірити, якщо у вас є `px4_msg` у робочому просторі. Команда також дозволяє вам запускати більш складні системи ROS за допомогою файлу запуску. Декілька можливостей демонструються нижче.
-
-### ros2 topic list
-
-Використовуйте `ros2 topic list`, щоб переглянути список тем, доступних для ROS 2:
-
-```sh
-ros2 topic list
-```
-
-Якщо PX4 підключений до агента, результатом буде список типів теми:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Зверніть увагу, що робочому простору не потрібно будувати з `px4_msgs` для успішного виконання; інформація про тип теми є частиною навантаження повідомлення.
-
-### ros2 topic echo
-
-Використовуйте `ros2 topic echo`, щоб показати деталі певної теми.
-
-На відміну від `ros2 topic list`, для цієї роботи вам потрібно знаходитися в робочому просторі, який побудував `px4_msgs` та джерело `local_setup.bash`, щоб ROS міг інтерпретувати повідомлення.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-Команда виведе деталі теми під час оновлення.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-Ви можете отримати статистику про швидкість повідомлень, використовуючи `ros2 topic hz`. Наприклад, щоб отримати ставки для `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-Вихід буде виглядати приблизно так:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-Команда `ros2 launch` використовується для запуску файлу запуску ROS 2. Наприклад, вище ми використовували `ros2 launch px4_ros_com sensor_combined_listener.launch.py` для запуску прикладу слухача.
-
-Вам не потрібно мати файл запуску, але вони дуже корисні, якщо у вас складна система ROS 2, яка потребує запуску кількох компонентів.
-
-Для отримання інформації про файли запуску див. [Посібники ROS 2 > Створення файлів запуску](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Відстеження проблем
-
-### Відсутні залежності
-
-Стандартна установка повинна включати всі необхідні інструменти для ROS 2.
-
-Якщо щось відсутнє, його можна додати окремо:
-- Інструменти збірки **`colcon`** повинні бути в інструментах розробки. Можна встановити за допомогою:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- Бібліотеку Eigen3, яку використовує бібліотека трансформацій, повинно бути в обох пакунків: desktop та base. Воно повинно бути встановлено, як показано:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Додаткова інформація
-
-- [ROS 2 у PX4: Технічні деталі безперервного переходу до XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Пабло Гаррідо та Нуно Маркес (youtube)
-- [Реалізації проміжного ПЗ DDS та ROS](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/uk/ros/ros2_multi_vehicle.md b/uk/ros/ros2_multi_vehicle.md
index 7586afac9c72..6449c4011507 100644
--- a/uk/ros/ros2_multi_vehicle.md
+++ b/uk/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Симуляція з ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) дозволяє підключати декілька клієнтів до одного агента через UDP. Це особливо корисно в симуляції, якщо потрібно запустити лише один агент.
-
-## Налаштування та вимоги
-
-Єдині вимоги
-
-- Щоб мати змогу запустити [симуляцію кількох транспортних засобів](../simulation/multi-vehicle-simulation.md) без ROS 2 з вибраним симулятором ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) та [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- Можливість використання [ROS 2](./ros2_comm.md) в симуляції одного транспортного засобу.
-
-## Принцип операції
-
-У симуляції кожен екземпляр PX4 отримує унікальний номер `px4_instance`, починаючи з `0`. Це значення використовується для присвоєння унікального значення ключу [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-:::info
-Таким чином, `UXRCE_DDS_KEY` завжди збігатиметься з [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Крім того, коли `px4_instance` більше нуля, додається унікальний [префікс простору імен](../middleware/uxrce_dds.md#customizing-the-topic-namespace) ROS 2 у вигляді `px4_$px4_instance`:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-:::info
-Змінна оточення `PX4_UXRCE_DDS_NS`, якщо її встановлено, перевизначає поведінку простору імен, описану вище.
-:::
-
-Перший екземпляр (`px4_instance=0`) не має додаткового простору імен, щоб відповідати стандартній поведінці клієнта `xrce-dds` на реальному транспортному засобі. Цю невідповідність можна виправити вручну за допомогою `PX4_UXRCE_DDS_NS` у першому випадку або почавши додавання транспортних засобів з індексу `1` замість `0` (це поведінка за замовчуванням, прийнята у [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) для Gazebo Classic).
-
-Типове налаштування клієнта у симуляції:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Налаштування значення `target_system`
-
-PX4 приймає повідомлення [VehicleCommand](../msg_docs/VehicleCommand.md) тільки якщо їхнє поле `target_system` дорівнює нулю (широкомовний зв'язок) або збігається з `MAV_SYS_ID`. У всіх інших ситуаціях повідомлення ігноруються. Тому, коли вузли ROS 2 хочуть надіслати `VehicleCommand` до PX4, вони повинні переконатися, що повідомлення заповнені відповідним значенням `target_system`.
-
-Наприклад, якщо ви хочете надіслати команду третьому автомобілю, який має `px4_instance=2`, вам потрібно встановити `target_system=3` у всіх ваших повідомленнях `VehicleCommand`.
+
diff --git a/uk/ros/ros2_offboard_control.md b/uk/ros/ros2_offboard_control.md
index adcf98511dd1..ad1f47e679c4 100644
--- a/uk/ros/ros2_offboard_control.md
+++ b/uk/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 Offboard Control Приклад
-
-Наступний приклад на C++ показує, як виконати керування положенням у режимі [offboard mode](../flight_modes/offboard.md) з вузла ROS 2.
-
-Приклад починає відправляти установочні точки, входить у режим offboard, озброюється, піднімається на 5 метрів і чекає. Незважаючи на простоту, він демонструє основні принципи використання offboard control і способи надсилання команд транспортному засобу.
-
-Він був протестований на Ubuntu 20.04 з ROS 2 Foxy та PX4 `main` після PX4 v1.13.
-
-:::warning
-*Offboard* керування небезпечне. Якщо ви керуєте реальним транспортним засобом, то обов'язково майте можливість отримати назад ручне керування на випадок, якщо щось піде не так.
-:::
-
-:::info ROS та PX4 роблять кілька різних припущень, зокрема щодо [конвенцій кадрів](../ros/external_position_estimation.md#reference-frames-and-ros). Не існує неявного перетворення між типами кадрів при публікації або підписці на теми!
-
-У цьому прикладі публікуються позиції у фреймі NED, як і очікує PX4. Щоб підписатися на дані, що надходять з вузлів, які публікують у іншій системі координат (наприклад, ENU, яка є стандартною системою координат у ROS/ROS 2), скористайтеся допоміжними функціями у бібліотеці [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp).
-:::
-
-## Випробування
-
-Дотримуйтесь інструкцій у [Посібнику користувача ROS 2](../ros/ros2_comm.md), щоб встановити PX і запустити симулятор, встановити ROS 2 і запустити агента XRCE-DDS.
-
-Після цього ми можемо виконати набір кроків, подібних до тих, що наведені у [ROS 2 Посібник користувача > ROS 2 Побудова робочого простору](../ros/ros2_comm.md#build-ros-2-workspace), щоб запустити приклад.
-
-Створити та запустити приклад:
-
-1. Відкрийте новий термінал.
-1. Створіть новий каталог робочого простору colcon і перейдіть до нього за допомогою:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. Клонуйте репозиторій [px4_msgs](https://github.com/PX4/px4_msgs) до каталогу `/src` (цей репозиторій потрібен у кожному робочому просторі ROS 2 PX4!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. Клонуйте репозиторій з прикладом [px4_ros_com](https://github.com/PX4/px4_ros_com) до каталогу `/src`:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Створіть середовище розробки ROS 2 у поточному терміналі і скомпілюйте робочу область за допомогою `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. Джерело `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. Запустіть приклад.
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-Транспортний засіб повинен озброїтися, піднятися на 5 метрів і потім зачекати (вічно).
-
-## Імплементація
-
-Вихідний код прикладу керування позашляховою платформою можна знайти за посиланням [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) у каталозі [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp).
-
-:::info PX4 публікує всі повідомлення, використані в цьому прикладі, як ROS теми за замовчуванням (див. [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 вимагає, щоб транспортний засіб вже отримував повідомлення `OffboardControlMode` перед тим, як він збере в режимі автономного керування, або перед тим, як він перейде в режим автономного керування під час польоту. Крім того, PX4 вийде з offboard mode, якщо частота потоку повідомлень `OffboardControlMode` впаде нижче приблизно 2 Гц. Необхідна поведінка реалізується за допомогою головного циклу, що виконується у вузлі ROS 2, як показано нижче:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-Цикл працює на таймері тривалістю 100 мс. Протягом перших 10 циклів він викликає `publish_offboard_control_mode()` і `publish_trajectory_setpoint()`, щоб відправити [OffboardControlMode](../msg_docs/OffboardControlMode.md) та [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) повідомлення до PX4. Повідомлення `OffboardControlMode` транслюються таким чином, що PX4 дозволить озброєння, як тільки перейде в режим offboard, тоді як повідомлення `TrajectorySetpoint` ігноруються (доки транспортний засіб перебуває в режимі offboard).
-
-Після 10 циклів викликається `publish_vehicle_command()` для зміни на режим безпілотного керування, а також викликається `arm()` для озброєння транспортного засобу. Після того, як транспортний засіб озброюється та змінює режим, він починає відстежувати встановлені точки. Задані точки все ще відправляються в кожному циклі, щоб транспортний засіб не виходив з режиму поза платформою.
-
-Реалізації методів `publish_offboard_control_mode()` та `publish_trajectory_setpoint()` показані нижче. Ці публікують повідомлення [OffboardControlMode](../msg_docs/OffboardControlMode.md) та [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) до PX4 (відповідно).
-
-Параметр `OffboardControlMode` потрібен для того, щоб повідомити PX4 про _тип_ використовуваного режиму керування offboard. Тут ми використовуємо лише _position control_, тому поле `position` має значення `true`, а всі інші поля мають значення `false`.
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` надає задане значення положення. У цьому випадку поля `x`, `y`, `z` і `yaw` жорстко закодовані на певні значення, але вони можуть оновлюватися динамічно за алгоритмом або навіть за допомогою зворотного виклику підписки на повідомлення, що надходять з іншого вузла.
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-Функція `publish_vehicle_command()` надсилає повідомлення [VehicleCommand](../msg_docs/VehicleCommand.md) з командами до польотного контролера. Ми використовуємо його вище, щоб змінити режим на режим offboard, а також у `arm()` для озброєння транспортного засобу. Хоча у цьому прикладі ми не викликаємо `disarm()`, він також використовується у реалізації цієї функції.
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-:::info [VehicleCommand](../msg_docs/VehicleCommand.md) - один з найпростіших і найпотужніших способів керування PX4, а підписавшись на [VehicleCommandAck](../msg_docs/VehicleCommandAck.md), ви також можете підтвердити, що задавання певної команди було успішним. Поля param і command відображають команди [MAVLink](https://mavlink.io/en/messages/common.html#mav_commands) та їхні значення параметрів.
-:::
-
-
-
+
diff --git a/zh/SUMMARY.md b/zh/SUMMARY.md
index f440fc023e84..889eb69322d8 100644
--- a/zh/SUMMARY.md
+++ b/zh/SUMMARY.md
@@ -578,6 +578,7 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](msg_docs/RegisterExtComponentRequest.md)
+ - [RoverAckermannGuidanceStatus](msg_docs/RoverAckermannGuidanceStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
diff --git a/zh/msg_docs/index.md b/zh/msg_docs/index.md
index fd5e86410f86..3c5643872cd1 100644
--- a/zh/msg_docs/index.md
+++ b/zh/msg_docs/index.md
@@ -3,7 +3,7 @@
::: info This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
-This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros2/user_guide.md)). 如何使用这些图表[可以在这里找到](../middleware/uorb_graph.md)。
+This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)). 如何使用这些图表[可以在这里找到](../middleware/uorb_graph.md)。
- [操作请求](ActionRequest.md)
- [ActuatorArmed](ActuatorArmed.md)
diff --git a/zh/ros/mavros_installation.md b/zh/ros/mavros_installation.md
index 487aef7556d6..46ce5f0be2a8 100644
--- a/zh/ros/mavros_installation.md
+++ b/zh/ros/mavros_installation.md
@@ -18,7 +18,9 @@ These instructions are a simplified version of the [official installation guide]
:::: tabs
-::: tab ROS Noetic (Ubuntu 22.04) If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
+::: tab ROS Noetic (Ubuntu 22.04)
+
+If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04:
1. Install PX4 without the simulator toolchain:
@@ -48,7 +50,9 @@ These instructions are a simplified version of the [official installation guide]
:::
-::: tab ROS Melodic (Ubuntu 18.04) If you're working with ROS "Melodic on Ubuntu 18.04:
+::: tab ROS Melodic (Ubuntu 18.04)
+
+If you're working with ROS "Melodic on Ubuntu 18.04:
1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell:
diff --git a/zh/ros/ros2.md b/zh/ros/ros2.md
index a0cd6e618d3c..9b483f856475 100644
--- a/zh/ros/ros2.md
+++ b/zh/ros/ros2.md
@@ -1,32 +1 @@
-# ROS 2
-
-[ROS 2](https://index.ros.org/doc/ros2/) 是[ROS](http://www.ros.org/) (机器人操作系统)最新版本 , 一个通用的机器人库,可以与 PX4 自驾仪一起创建强大的无人机应用。 它继承了 [ROS 1](../ros/ros1.md)的大部分经验和特征,改进了早期版本的一些缺陷。
-
-:::warning
-提示
-PX4开发团队强烈建议您使用/迁移到这个版本的ROS!
-:::
-
-ROS 2 和 PX4 之间的通信使用中间件实现 [XRCE-DDS 协议](../middleware/uxrce_dds.md)。 这个中间件将PX4的 [uORB 消息](../msg_docs/README.md) 作为ROS 2 消息和类型直接使用,非常高效地实现 ROS 2 工作空间和节点直接访问 PX4。 中间件使用 uORB 消息定义生成代码来序列化和反序列化来处理PX4 的收发消息。 These same message definitions are used in ROS 2 applications to allow the messages to be interpreted.
-
-为了在 XRCE-DDS 上高效使用 [ROS 2](../ros/ros2_comm.md) , (撰写本文时)你必须对PX4内部结构和约定有一定的理解,以明确与使用 ROS 有哪些不同。 我们计划近期提供ROS 2 API 以对 PX4 的特性进行封装,并举例说明它们的用途。
-
-本节的主要主题是:
-- [ROS 2 用户指南](../ros/ros2_comm.md): PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。
-- [ROS 2 Offboard 控制示例](../ros/ros2_offboard_control.md)
-
-::: info
-ROS 2 is officially supported only on Linux platforms.
-Ubuntu 20.04 LTS 是官方支持的版本。
-:::
-
-
-::: info ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) (instead of XRCE-DDS). MAVROS项目支持此选项。
-:::
-
-
-## 更多信息
-
-- [ROS 2 用户指南](../ros/ros2_comm.md)
-- [XRCE-DDS(PX4-ROS 2/DDS桥)](../middleware/uxrce_dds.md): PX4 中间件用于连接到ROS2
-
+
diff --git a/zh/ros/ros2_comm.md b/zh/ros/ros2_comm.md
index 73aaeaa766e6..47f18ae25603 100644
--- a/zh/ros/ros2_comm.md
+++ b/zh/ros/ros2_comm.md
@@ -1,754 +1 @@
-# ROS 2 用户指南
-
-ROS 2-PX4 架构在ROS 2和PX4之间进行了深度整合。 允许 ROS 2 订阅或发布节点直接使用 PX4 uORB 话题。
-
-本指南介绍了系统架构和应用程序流程,并解释了如何与PX4一起安装和使用ROS2。
-
-::: info From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
-
-The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
-
-If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html).
-
-:::
-
-## 概述
-
-由于使用 [uXRCE-DDS](../middleware/uxrce_dds.md) 通信中间件,因此ROS 2的应用程序流程非常简单。
-
-![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg)
-
-
-
-uXRCE-DDS的中间件由运行在PX4上的客户端(Client)和运行在机载计算机上的代理端(Agent)组成, 通过串口、UDP、TCP或其他链路实现双向数据互联。 代理端(Agent)充当客户端(Client)的代理在DDS全局数据空间中发布和订阅话题。
-
-The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. 它包含“通用”XRCE-DDS客户端(Client)代码和PX4 特定翻译代码以支持用来发布或获取来自uORB的话题 。 为客户端(Client)生成的 uORB 消息的子集在 [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) 中定义。 生成器使用代码树: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) 中的 uORB 消息定义来创建 ROS 2 消息代码。
-
-ROS 2 应用程序应该在具有 _相同的_ 消息定义的工作区中构建,即在 PX4 Firmware 中创建 uXRCE-DDS客户端(Client)模块时使用的消息。 你可以通过克隆接口包 [PX4/px4_msgs](https://github.com/PX4/px4_msgs) 到你的 ROS 2 工作空间中(仓库中的分支对应于不同版本 PX4 消息)。
-
-请注意,micro XRCE-DDS _代理(Agent)_ 本身并不依赖客户端代码。 可以通过 [源码](https://github.com/eProsima/Micro-XRCE-DDS-Agent)单独或作为ROS的一部分通过编译生成,也可以通过snap安装。
-
-您通常需要在使用 ROS 2 时同时启动客户端(Client)和代理人(Agent)。 请注意,uXRCE-DDS客户端默认是编译进固件中的,但除模拟器构建外,不会自动启动。
-
-::: info In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). 该仓库不再需要了,但的确包含了有用的例子。
-:::
-
-
-## 安装设置
-
-The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
-
-ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
-
-::: info PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use [Gazebo Classic](../sim_gazebo_classic/index.md).
-:::
-
-To setup ROS 2 for use with PX4:
-
-- [安装 PX4](#install-px4) (使用 PX4 模拟器)
-- [安装 ROS 2](#install-ros-2)
-- [安装Micro XRCE-DDS 代理(Agent)& 客户端(Client)](#setup-micro-xrce-dds-agent-client)
-- [构建 & 运行 ROS 2 工作空间](#build-ros-2-workspace)
-
-框架的其他依赖关系将自动安装,如 _Fast DDS_。
-
-
-### 安装PX4
-
-您需要安装 PX4 开发工具链才能使用模拟器。
-
-::: info The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). 您只需要安装 PX4 当您需要模拟器时(如我们在本指南中所做的那样), 或者如果您正在创建一个发布自定义uORB话题。
-:::
-
-通过以下方式在 Ubuntu 上配置一个 PX4 开发环境:
-
-```sh
-cd
-git clone https://github.com/PX4/PX4-Autopilot.git --recursive
-bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
-cd PX4-Autopilot/
-make px4_sitl
-```
-
-Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag.
-
-For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md).
-
-### 安装 ROS 2
-
-安装 ROS 2 及其依赖:
-
-1. Install ROS 2.
-
- :::: tabs
-
- ::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
-
- ```sh
- sudo apt update && sudo apt install locales
- sudo locale-gen en_US en_US.UTF-8
- sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
- export LANG=en_US.UTF-8
- sudo apt install software-properties-common
- sudo add-apt-repository universe
- sudo apt update && sudo apt install curl -y
- sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
- echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- sudo apt update && sudo apt upgrade -y
- sudo apt install ros-humble-desktop
- sudo apt install ros-dev-tools
- source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
- ```
-
- The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
-
- ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
-
- - Follow the official installation guide: [Install ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/Linux-Install-Debians/).
-
- You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), *and* the development tools (`ros-dev-tools`).
-:::
-
- ::::
-
-1. 一些Python 依赖关系也必须安装 (使用 **`pip`** 或 **`apt`**):
-
- ```sh
- pip install --user -U empy==3.3.4 pyros-genmsg setuptools
- ```
-
-
-
-### 安装Micro XRCE-DDS 代理(Agent)& 客户端(Client)
-
-For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
-
-#### 设置代理(Agent)
-
-代理(Agent)可以通过 [数种方式](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation) 安装到任务计算机上。 下面我们将演示如何从源代码构建“独立”代理(Agent),并连接到在 PX4 模拟器上运行的客户端(Client)。
-
-设置并启动代理:
-
-1. 打开一个终端。
-1. 输入以下命令从仓库获取源代码并构建代理(Agent):
-
- ```sh
- git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
- cd Micro-XRCE-DDS-Agent
- mkdir build
- cd build
- cmake ..
- make
- sudo make install
- sudo ldconfig /usr/local/lib/
- ```
-
-1. 启动代理并设置以连接运行在模拟器上的 uXRCE-DDS客户端(Client):
-
- ```sh
- MicroXRCEAgent udp4 -p 8888
- ```
-
-代理正在运行,但在我们启动PX4 (下一步)之前,您不会看到太多。
-
-::: info
-You can leave the agent running in this terminal!
-请注意,每个连接端口只允许一个代理(Agent)。
-:::
-
-#### 启动客户端(Client)
-
-PX4 模拟器自动启动 uXRCE-DDS客户端,连接到本地主机上的 UDP 8888 端口。
-
-启动模拟器(和客户端Client):
-
-1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
-
- :::: tabs
-
- ::: tab humble
- - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
-
- ```sh
- make px4_sitl gz_x500
- ```
-
-:::
-
- ::: tab foxy
- - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
-
- ```sh
- make px4_sitl gazebo-classic
- ```
-
-:::
-
- ::::
-
-代理(Agent)和客户端(Client)现在将运行并建立连接。
-
-PX4 终端显示 [NuttShell/PX4 系统控制台](../debug/system_console.md) PX4 启动和运行。 代理(Agent)连接后输出应该包含 `INFO` 显示创建数据写入的消息:
-
-```
-...
-INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us
-INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83
-INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168
-INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188
-...
-```
-
-Micro XRCE-DDS代理(Agent)终端也应开始显示输出,因为DDS网络中创建了相同的主题:
-
-```
-...
-[1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1)
-[1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3)
-[1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1)
-...
-```
-
-### Build ROS 2 Workspace
-
-本节将展示如何在您的主目录中创建一个 ROS 2 工作空间(将源代码放在别处需要修改相关指令)。
-
-[px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) 软件包克隆到一个工作区文件夹,然后使用 `colcon` 工具来构建工作区。 The example is run using `ros2 launch`.
-
-::: info The example builds the [ROS 2 Listener](#ros-2-listener) example application, located in [px4_ros_com](https://github.com/PX4/px4_ros_com). [px4_msgs](https://github.com/PX4/px4_msgs) is needed too so that the example can interpret PX4 ROS 2 topics.
-:::
-
-
-#### Building the Workspace
-
-To create and build the workspace:
-
-1. Open a new terminal.
-1. Create and navigate into a new workspace directory using:
-
- ```sh
- mkdir -p ~/ws_sensor_combined/src/
- cd ~/ws_sensor_combined/src/
- ```
-
- ::: info
-A naming convention for workspace folders can make it easier to manage workspaces.
-:::
-
-1. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
- This builds all the folders under `/src` using the sourced toolchain.
-
-
-#### Running the Example
-
-To run the executables that you just built, you need to source `local_setup.bash`. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
-
-::: info The [ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay) recommend that you _open a new terminal_ for running your executables.
-:::
-
-In a new terminal:
-
-1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/humble/setup.bash
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ~/ws_sensor_combined/
- source /opt/ros/foxy/setup.bash
- ```
-
-:::
-
- ::::
-
-1. Source the `local_setup.bash`.
-
- ```sh
- source install/local_setup.bash
- ```
-1. Now launch the example. Note here that we use `ros2 launch`, which is described below.
-
- ```
- ros2 launch px4_ros_com sensor_combined_listener.launch.py
- ```
-
-If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
-
-```sh
-RECEIVED DATA FROM SENSOR COMBINED
-================================
-ts: 870938190
-gyro_rad[0]: 0.00341645
-gyro_rad[1]: 0.00626475
-gyro_rad[2]: -0.000515705
-gyro_integral_dt: 4739
-accelerometer_timestamp_relative: 0
-accelerometer_m_s2[0]: -0.273381
-accelerometer_m_s2[1]: 0.0949186
-accelerometer_m_s2[2]: -9.76044
-accelerometer_integral_dt: 4739
-```
-
-## Controlling a Vehicle
-
-To control applications, ROS 2 applications:
-
-- subscribe to (listen to) telemetry topics published by PX4
-- publish to topics that cause PX4 to perform some action.
-
-The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md). For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
-
-The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
-
-## Compatibility Issues
-
-This section contains information that may affect how you write your ROS code.
-
-### ROS 2 Subscriber QoS Settings
-
-ROS 2 code that subscribes to topics published by PX4 _must_ specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the [listener example source code](#ros-2-listener)):
-
-```cpp
-...
-rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
-auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
-subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
-...
-```
-
-This is needed because the ROS 2 default [Quality of Service (QoS) settings](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-profiles) are different from the settings used by PX4. Not all combinations of publisher-subscriber [Qos settings are possible](https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities), and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
-
-
-
-
-### ROS 2 & PX4 Frame Conventions
-
-The local/world and body frames used by ROS and PX4 are different.
-
-| Frame | PX4 | ROS |
-| ----- | ------------------------------------------------ | ---------------------------------------------- |
-| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p) |
-| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) |
-
-:::tip
-See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames.
-:::
-
-Both frames are shown in the image below (FRD on the left/FLU on the right).
-
-![Reference frames](../../assets/lpe/ref_frames.png)
-
-The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
-
-- To rotate a vector from ENU to NED two basic rotations must be performed:
-
- - first a pi/2 rotation around the `Z`-axis (up),
- - then a pi rotation around the `X`-axis (old East/new North).
-- To rotate a vector from NED to ENU two basic rotations must be performed:
--
- - first a pi/2 rotation around the `Z`-axis (down),
- - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
-- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
-- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient.
-
-Examples of vectors that require rotation are:
-
-- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them.
-- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them.
-
-Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
-
-[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions.
-
-### ROS, Gazebo and PX4 time synchronization
-
-By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated.
-
-For Gazebo simulations PX4 uses the Gazebo `/clock` topic as [time source](../sim_gazebo_gz/index.md#px4-gazebo-time-synchronization) instead. This clock is always slightly off-sync w.r.t. the OS clock (the real time factor is never exactly one) and it can can even run much faster or much slower depending on the [user preferences](http://sdformat.org/spec?elem=physics&ver=1.9). Note that this is different from the [simulation lockstep](../simulation/index.md#lockstep-simulation) procedure adopted with Gazebo Classic.
-
-ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes.
-
-#### ROS2 nodes use the OS clock as time source
-
-This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behavior of the ROS2 nodes. The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. No further action is required by the user.
-
-#### ROS2 nodes use the Gazebo clock as time source
-
-In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. Read through the [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs to find out the right version that has to be installed depending on your ROS2 and Gazebo versions.
-
-Once the package is installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge:
-
-```sh
-ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
-```
-
-At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)).
-
-This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. By doing so, Gazebo will act as main and only time source for both ROS2 and PX4.
-
-## ROS 2 Example Applications
-
-### ROS 2 Listener
-
-The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4.
-
-Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message.
-
-::: info [Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example.
-:::
-
-The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes:
-
-```cpp
-#include
-#include
-```
-
-Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-/**
- * @brief Sensor Combined uORB topic data callback
- */
-class SensorCombinedListener : public rclcpp::Node
-{
-```
-
-This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
-
-```cpp
-public:
- explicit SensorCombinedListener() : Node("sensor_combined_listener")
- {
- rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
- auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile);
-
- subscription_ = this->create_subscription("/fmu/out/sensor_combined", qos,
- [this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
- std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
- std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
- std::cout << "=============================" << std::endl;
- std::cout << "ts: " << msg->timestamp << std::endl;
- std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
- std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
- std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
- std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
- std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
- std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
- std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
- std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
- std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
- });
- }
-```
-
-::: info The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings),
-:::
-
-The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic.
-
-```cpp
-private:
- rclcpp::Subscription::SharedPtr subscription_;
-};
-```
-
-The instantiation of the `SensorCombinedListener` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting sensor_combined listener node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). This allows it to be launched using the [`ros2 launch`](#ros2-launch) command.
-
-### ROS 2 Advertiser
-
-A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
-
-Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header.
-
-```cpp
-#include
-#include
-#include
-
-using namespace std::chrono_literals;
-```
-
-Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class.
-
-```cpp
-class DebugVectAdvertiser : public rclcpp::Node
-{
-```
-
-The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
-
-```cpp
-public:
- DebugVectAdvertiser() : Node("debug_vect_advertiser") {
- publisher_ = this->create_publisher("fmu/debug_vect/in", 10);
- auto timer_callback =
- [this]()->void {
- auto debug_vect = px4_msgs::msg::DebugVect();
- debug_vect.timestamp = std::chrono::time_point_cast(std::chrono::steady_clock::now()).time_since_epoch().count();
- std::string name = "test";
- std::copy(name.begin(), name.end(), debug_vect.name.begin());
- debug_vect.x = 1.0;
- debug_vect.y = 2.0;
- debug_vect.z = 3.0;
- RCLCPP_INFO(this->get_logger(), "\033[97m Publishing debug_vect: time: %llu x: %f y: %f z: %f \033[0m",
- debug_vect.timestamp, debug_vect.x, debug_vect.y, debug_vect.z);
- this->publisher_->publish(debug_vect);
- };
- timer_ = this->create_wall_timer(500ms, timer_callback);
- }
-
-private:
- rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
-};
-```
-
-The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function.
-
-```cpp
-int main(int argc, char *argv[])
-{
- std::cout << "Starting debug_vect advertiser node..." << std::endl;
- setvbuf(stdout, NULL, _IONBF, BUFSIZ);
- rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
-
- rclcpp::shutdown();
- return 0;
-}
-```
-
-### Offboard Control
-
-For a complete reference example on how to use Offboard control with PX4, see: [ROS 2 Offboard control example](../ros/ros2_offboard_control.md).
-
-## Using Flight Controller Hardware
-
-ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel.
-
-For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client).
-
-## Custom uORB Topics
-
-ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. Therefore,
-
-- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
-- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be:
-
- ```sh
- rm ~/px4_ros_com/src/px4_msgs/msg/*.msg
- cp ~/PX4-Autopilot/mgs/*.msg ~/px4_ros_com/src/px4_msgs/msg/
- ```
-
- ::: info Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
-:::
-
-## Customizing the Topic Namespace
-
-Custom topic namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
-
-- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles.
-- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
-
-
-::: info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml). Therefore, commands like:
-
-```sh
-uxrce_dds_client start -n uav_1
-```
-
-or
-
-```sh
-PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
-```
-
-will generate topics under the namespaces:
-
-```sh
-/uav_1/fmu/in/ # for subscribers
-/uav_1/fmu/out/ # for publishers
-```
-:::
-
-## ros2 CLI
-
-The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
-
-### ros2 topic list
-
-Use `ros2 topic list` to list the topics visible to ROS 2:
-
-```sh
-ros2 topic list
-```
-
-If PX4 is connected to the agent, the result will be a list of topic types:
-
-```
-/fmu/in/obstacle_distance
-/fmu/in/offboard_control_mode
-/fmu/in/onboard_computer_status
-...
-```
-
-Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload.
-
-### ros2 topic echo
-
-Use `ros2 topic echo` to show the details of a particular topic.
-
-Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages.
-
-```sh
-ros2 topic echo /fmu/out/vehicle_status
-```
-
-The command will echo the topic details as they update.
-
-```
----
-timestamp: 1675931593364359
-armed_time: 0
-takeoff_time: 0
-arming_state: 1
-latest_arming_reason: 0
-latest_disarming_reason: 0
-nav_state_timestamp: 3296000
-nav_state_user_intention: 4
-nav_state: 4
-failure_detector_status: 0
-hil_state: 0
-...
----
-```
-
-### ros2 topic hz
-
-You can get statistics about the rates of messages using `ros2 topic hz`. For example, to get the rates for `SensorCombined`:
-
-```
-ros2 topic hz /fmu/out/sensor_combined
-```
-
-The output will look something like:
-
-```sh
-average rate: 248.187
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2724
-average rate: 248.006
- min: 0.000s max: 0.012s std dev: 0.00147s window: 2972
-average rate: 247.330
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3212
-average rate: 247.497
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3464
-average rate: 247.458
- min: 0.000s max: 0.012s std dev: 0.00149s window: 3712
-average rate: 247.485
- min: 0.000s max: 0.012s std dev: 0.00148s window: 3960
-```
-
-### ros2 launch
-
-The `ros2 launch` command is used to start a ROS 2 launch file. For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example.
-
-You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
-
-For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html)
-
-
-
-## Troubleshooting
-
-### Missing dependencies
-
-The standard installation should include all the tools needed by ROS 2.
-
-If any are missing, they can be added separately:
-- **`colcon`** build tools should be in the development tools. It can be installed using:
- ```sh
- sudo apt install python3-colcon-common-extensions
- ```
-- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- sudo apt install ros-humble-eigen3-cmake-module
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- sudo apt install ros-foxy-eigen3-cmake-module
- ```
-
-:::
-
- ::::
-
-
-## Additional information
-
-- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
-- [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations)
+
diff --git a/zh/ros/ros2_multi_vehicle.md b/zh/ros/ros2_multi_vehicle.md
index b48ee1b0b988..6449c4011507 100644
--- a/zh/ros/ros2_multi_vehicle.md
+++ b/zh/ros/ros2_multi_vehicle.md
@@ -1,49 +1 @@
-# Multi-Vehicle Simulation with ROS 2
-
-[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. This is particular useful in simulation as only one agent needs to be started.
-
-## Setup and Requirements
-
-The only requirements are
-
-- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)).
-- To be able to use [ROS 2](./ros2_comm.md) in a single vehicle simulation.
-
-## Principle of Operation
-
-In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY):
-
-```sh
-param set UXRCE_DDS_KEY $((px4_instance+1))
-```
-
-::: info
-By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID).
-:::
-
-Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-topic-namespace) in the form `px4_$px4_instance` is added:
-
-```sh
-uxrce_dds_ns="-n px4_$px4_instance"
-```
-
-::: info
-The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above.
-:::
-
-The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic).
-
-The default client configuration in simulation is summarized as follows:
-
-| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace |
-| ------------------ | -------------- | ---------------- | --------------------- |
-| not provided | 0 | `px4_instance+1` | none |
-| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` |
-| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` |
-
-## Adjusting the `target_system` value
-
-PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. In all other situations, the messages are ignored. Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value.
-
-For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages.
+
diff --git a/zh/ros/ros2_offboard_control.md b/zh/ros/ros2_offboard_control.md
index 7cba49a84243..ad1f47e679c4 100644
--- a/zh/ros/ros2_offboard_control.md
+++ b/zh/ros/ros2_offboard_control.md
@@ -1,196 +1 @@
-# ROS 2 Offboard 控制示例
-
-下面的 C++ 示例显示如何在ROS 2 节点中进行 [offboard模式](../flight_modes/offboard.md) 下的位置控制。
-
-示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。
-
-它已在 Ubuntu 20.04 ROS 2 Foxy环境及不低于 PX4 v1.13 的 `main` 分支进行了测试。
-
-:::warning
-*Offboard* 控制模式是危险的。 如果你是在一个真正的无人机平台上进行试验,请保证你已经设置了切换回手动的开关来防止紧急情况的发生。
-:::
-
-::: info ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). 当主题发布或订阅时,坐标系类型之间没有隐含转换!
-
-这个例子按照PX4的定义在NED坐标系下发布位置。 订阅来自在不同坐标系发布的节点数据(例如ENU, ROS/ROS 2中的标准坐标系),使用 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) 库中的辅助函数来进行转换。
-:::
-
-## 尝试一下
-
-按照 [ROS 2 用户向导](../ros/ros2_comm.md) 中的说明来安装PX 并运行模拟器,安装ROS 2, 并启动XRCE-DDS代理。
-
-然后,我们可以采用 [ROS 2 用户向导 > 构建 ROS 2 工作空间](../ros/ros2_comm.md#build-ros-2-workspace) 中相似的步骤来运行这个例子。
-
-构建并运行示例:
-
-1. 打开一个新的终端。
-1. 使用以下方法创建并切换至新的 colcon工作目录:
-
- ```sh
- mkdir -p ~/ws_offboard_control/src/
- cd ~/ws_offboard_control/src/
- ```
-
-1. 克隆 [px4_msgs](https://github.com/PX4/px4_msgs) 仓库到 `/src` 目录(每一个 ROS 2 PX4 工作区都需要这个仓库!):
-
- ```sh
- git clone https://github.com/PX4/px4_msgs.git
- # checkout the matching release branch if not using PX4 main.
- ```
-
-1. 克隆示例仓库 [px4_ros_com](https://github.com/PX4/px4_ros_com) 到 `/src` 目录:
-
- ```sh
- git clone https://github.com/PX4/px4_ros_com.git
- ```
-
-1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
-
- :::: tabs
-
- ::: tab humble
- ```sh
- cd ..
- source /opt/ros/humble/setup.bash
- colcon build
- ```
-
-:::
-
- ::: tab foxy
- ```sh
- cd ..
- source /opt/ros/foxy/setup.bash
- colcon build
- ```
-
-:::
-
- ::::
-
-1. 执行工作空间环境配置脚本 `local_setup.bash`:
-
- ```sh
- source install/local_setup.bash
- ```
-1. 启动例程。
-
- ```
- ros2 run px4_ros_com offboard_control
- ```
-
-飞行器将解锁、起飞至5米并悬停等待(永久)。
-
-## 实现
-
-Offboard控制示例的源代码见 [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) 目录的 [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp) 。
-
-::: info PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)).
-:::
-
-PX4 在offboard模式下解锁或者在飞行过程中切换至offboard模式都需要飞行器已经收到 `OffboardControlMode` 消息。 此外,如果 `OffboardControlMode` 消息的频率低于2Hz,PX4 将会切换出offboard模式。 该行为在ROS 2 节点的主循环中实现的,如下所示:
-
-```cpp
-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();
- }
-
- // OffboardControlMode needs to be paired with TrajectorySetpoint
- publish_offboard_control_mode();
- publish_trajectory_setpoint();
-
- // stop the counter after reaching 11
- if (offboard_setpoint_counter_ < 11) {
- offboard_setpoint_counter_++;
- }
-};
-timer_ = this->create_wall_timer(100ms, timer_callback);
-```
-
-循环运行在一个100毫秒计时器。 在前10个周期中,它调用 `publish_offboard_control_mode()` 和 `publish_trajectory_setpoint()` 发送 [OffboardControlMode](../msg_docs/OffboardControlMode.md) 和 [TracjectorySetpoint](../msg_docs/TrajectorySetpoint.md) 消息到 PX4。 `OffboardControlMode` 消息已经被接到,所以PX4将允许被解锁一旦切换至offboard模式后, `TrajectorySetpoint` 将被忽略(直到飞行器处于offboard模式)。
-
-在 10 个周期后调用 `publish_vehicle_command()` 切换至offboard模式,并调用 `arm()` 来解锁飞行器。 在飞行器解锁并和切换模式后,它将开始跟踪位置设定值。 在每个周期内仍然发送设定值,确保飞行器不会切换出offboard模式。
-
-`publish_offboard_control_mode()` 和 `publish_trajectory_setpoint()` 方法的实现如下。 发布 [OffboardControlMode](../msg_docs/OffboardControlMode.md) 和 [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) 消息到 PX4 (依次)。
-
-`OffboardControlMode` 是必须的以通知PX4 offboard模式所需使用的控制 _类型_ 。 这里我们只使用 _位置控制_, 所以 `position` 字段设置为 `true` 所有其他字段设置为 `false`。
-
-```cpp
-/**
- * @brief Publish the offboard control mode.
- * For this example, only position and altitude controls are active.
- */
-void OffboardControl::publish_offboard_control_mode()
-{
- OffboardControlMode msg{};
- msg.position = true;
- msg.velocity = false;
- msg.acceleration = false;
- msg.attitude = false;
- msg.body_rate = false;
- msg.thrust_and_torque = false;
- msg.direct_actuator = false;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- offboard_control_mode_publisher_->publish(msg);
-}
-```
-
-`TrajectorySetpoint` 提供了位置设置值。 在这种情况下, `x`, `y`, `z` 和 `yaw` 字段被赋值为某些值,但它们可以根据算法动态更新,甚至也可以通过另一个订阅的回调函数来生成。
-
-```cpp
-/**
- * @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_trajectory_setpoint()
-{
- TrajectorySetpoint msg{};
- msg.position = {0.0, 0.0, -5.0};
- msg.yaw = -3.14; // [-PI:PI]
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- trajectory_setpoint_publisher_->publish(msg);
-}
-```
-
-`publish_vehicle_command()` 方法发送 [VehicleCommand](../msg_docs/VehicleCommand.md) 带命令的消息到飞行控制器。 我们使用上面的方式来切换至offboard模式,也使用 `arm()` 来解锁飞行器。 此示例中我们没有 `disarm()` ,但它也用于执行该函数。
-
-```cpp
-/**
- * @brief Publish vehicle commands
- * @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
- * @param param1 Command parameter 1
- * @param param2 Command parameter 2
- */
-void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
-{
- VehicleCommand msg{};
- msg.param1 = param1;
- msg.param2 = param2;
- msg.command = command;
- msg.target_system = 1;
- msg.target_component = 1;
- msg.source_system = 1;
- msg.source_component = 1;
- msg.from_external = true;
- msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
- vehicle_command_publisher_->publish(msg);
-}
-```
-
-::: info [VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. 参数和命令字段与 [MAVLink 命令](https://mavlink.io/en/messages/common.html#mav_commands) 及其参数值一致。
-:::
-
-
-
+