From 0720c301e21351d8410c8d2556856e4bda0633d5 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Fri, 22 Nov 2024 09:22:27 +1100 Subject: [PATCH] New translations collision_prevention.md (Chinese Simplified) --- zh/computer_vision/collision_prevention.md | 275 +++++++++++++-------- 1 file changed, 173 insertions(+), 102 deletions(-) diff --git a/zh/computer_vision/collision_prevention.md b/zh/computer_vision/collision_prevention.md index 93516da7ebee..32ed523a3994 100644 --- a/zh/computer_vision/collision_prevention.md +++ b/zh/computer_vision/collision_prevention.md @@ -1,89 +1,101 @@ # 防撞功能 _Collision Prevention_ may be used to automatically slow and stop a vehicle before it can crash into an obstacle. +It can be enabled for multicopter vehicles when using acceleration-based [Position mode](../flight_modes_mc/position.md) (or VTOL vehicles in MC mode). -It can be enabled for multicopter vehicles in [Position mode](../flight_modes_mc/position.md), and can use sensor data from an offboard companion computer, offboard rangefinders over MAVLink, a rangefinder attached to the flight controller, or any combination of the above. +## 综述 -如果传感器的测量范围不够大,防撞功能可能会限制无人机的最大飞行速度。 -它也会阻止在没有传感器数据的方向上运动(例如:如果后方没有传感器数据,将无法向后方飞行 )。 +The vehicle restricts the current velocity in order to slow down as it gets closer to obstacles and adapts the acceleration setpoint in order to disallow collision trajectories. +为了远离(或与之平行的)障碍物,用户必须使无人机/无人车朝向不靠近障碍物的设定点移动。 +如果存在一个”更好”的设定点,这个设定点在请求设定点的任何一侧,并且在固定的间隙内,算法将对设定点方向做最小的调整。 -:::tip -If high flight speeds are critical, consider disabling collision prevention when not needed. -::: +Collision prevention prevents motion in directions where no sensor data is available (i.e. if you have no rear-sensor data, you will not be able to fly backwards). +It may also restrict vehicle maximum speed if the sensor range isn't large enough! + +Multiple sensors can be used to get information about, and prevent collisions with, objects _around_ the vehicle. +If multiple sources supply data for the _same_ orientation, the system uses the data that reports the smallest distance to an object. + +The feature requires obstacle information from a [distance sensor](../sensor/rangefinders.md). +The sensor may be connected to the flight controller (recommended). +It can also be used with distance information provided by an external system via MAVLink, but this is currently untested (see [companion setup](#companion) below). + +The [rangefinders](#rangefinder) that have been tested when directly connected to PX4 are listed below, along with setup instructions. +The [PX4 Configuration](#px4-configuration) specific to collision-prevention is the same for all sensors and independent of whether data is provided by a connected sensor or MAVLink. :::tip -Ensure that you have sensors/sensor data in all directions that you want to fly (when collision prevention is enabled). + +- If high flight speeds are critical, consider disabling collision prevention when not needed. +- Ensure that you have sensors/sensor data in all directions that you want to fly, including backwards (when collision prevention is enabled). + ::: -## 综述 +## Supported Rangefinders {#rangefinder} -_Collision Prevention_ is enabled on PX4 by setting the parameter for minimum allowed approach distance ([CP_DIST](#CP_DIST)). +Collision Prevention has been tested with the following rangefinders attached to PX4 (not for providing data [supplied over MAVLink](#companion)). -The feature requires obstacle information from an external system (sent using the MAVLink [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE) message) and/or a [distance sensor](../sensor/rangefinders.md) connected to the flight controller. +### 兰宝 PSK-CM8JL65-CC5 -:::info -Multiple sensors can be used to get information about, and prevent collisions with, objects _around_ the vehicle. -If multiple sources supply data for the _same_ orientation, the system uses the data that reports the smallest distance to an object. -::: +At time of writing PX4 allows you to use the [Lanbao PSK-CM8JL65-CC5](../sensor/cm8jl65_ir_distance_sensor.md) IR distance sensor for collision prevention "out of the box", with minimal additional configuration: -为了在靠近障碍物时减速,无人机限制了最大速度,并且在达到最小允许间距时停止移动。 -为了远离(或与之平行的)障碍物,用户必须使无人机/无人车朝向不靠近障碍物的设定点移动。 -如果存在一个”更好”的设定点,这个设定点在请求设定点的任何一侧,并且在固定的间隙内,算法将对设定点方向做最小的调整。 +1. [Attach and configure the sensor](../sensor/cm8jl65_ir_distance_sensor.md). +2. Set the sensor orientation using [SENS_CM8JL65_R_0](../advanced_config/parameter_reference.md#SENS_CM8JL65_R_0). +3. [Configure and enable collision prevention](#px4-configuration) -Users are notified through _QGroundControl_ while _Collision Prevention_ is actively controlling velocity setpoints. +### LightWare LiDAR SF45 Rotating Lidar -PX4 软件配置在下一章节中。 -If you are using a distance sensor attached to your flight controller for collision prevention, it will need to be attached and configured as described in [PX4 Distance Sensor](#rangefinder). -If you are using a companion computer to provide obstacle information see [companion setup](#companion). +PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](https://www.lightwarelidar.com/shop/sf45-b-50-m/) rotating lidar which provides 320 degree sensing. -## PX4 (软件) 设置 +The SF45 must be connected via a UART/serial port and configured as described below: -Configure collision prevention by [setting the following parameters](../advanced_config/parameters.md) in _QGroundControl_: +1. [LightWare Studio](https://www.lightwarelidar.com/resources-software) configuration: -| 参数 | 描述 | -| ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST) | 设置最小允许距离(无人机/无人车可以接近障碍物的最近距离)。 Set negative to disable _collision prevention_.
> **Warning** This value is the distance to the sensors, not the outside of your vehicle or propellers. 确保一个安全距离。 | -| [CP_DELAY](../advanced_config/parameter_reference.md#CP_DELAY) | 设置传感器和速度设定值跟踪延迟。 See [Delay Tuning](#delay_tuning) below. | -| [CP_GUIDE_ANG](../advanced_config/parameter_reference.md#CP_GUIDE_ANG) | 如果在该方向上发现的障碍物较少,则设置无人机/无人车可能偏离的角度(在指令方向的两侧)。 See [Guidance Tuning](#angle_change_tuning) below. | -| [CP_GO_NO_DATA](../advanced_config/parameter_reference.md#CP_GO_NO_DATA) | Set to 1 to allow the vehicle to move in directions where there is no sensor coverage (default is 0/`False`). | -| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Set to `Direct velocity` or `Smoothed velocity` to enable Collision Prevention in Position Mode (default is `Acceleration based`). | + - In the LightWare Studio app enable scanning, set the scan angle, and change the baud rate to `921600`. -## 算法描述 +2. Add [lightware_sf45_serial](../modules/modules_driver_distance_sensor.md#lightware-sf45-serial) driver to PX4 firmware: -所有传感器的数据融合到机身周围的 36 个扇区中,每个扇区包含传感器数据和上次观测时间信息,或者指示该扇区没有可用数据。 -当控制无人机向特定的方向移动时,就会检查该方向半球内的所有扇区,以查看此次移动是否会使机身靠近任何障碍物。 -如果是这样,无人机的速度就会受到限制。 + 1. Open [menuconfig](../hardware/porting_guide_config.md#px4-menuconfig-setup) + 2. Under **drivers > Distance sensors** select `lightware_sf45_serial`. + 3. Recompile and upload to the flight controller. -This velocity restriction takes into account both the inner velocity loop tuned by [MPC_XY_P](../advanced_config/parameter_reference.md#MPC_XY_P), as well as the [jerk-optimal velocity controller](../config_mc/mc_jerk_limited_type_trajectory.md) via [MPC_JERK_MAX](../advanced_config/parameter_reference.md#MPC_JERK_MAX) and [MPC_ACC_HOR](../advanced_config/parameter_reference.md#MPC_ACC_HOR). -The velocity is restricted such that the vehicle will stop in time to maintain the distance specified in [CP_DIST](#CP_DIST). -还考虑到每个扇区的传感器范围,通过相同的机制限制了速度。 +3. [Set the following parameters](../advanced_config/parameters.md) via QGC to configure the driver: -:::info -If there is no sensor data in a particular direction, velocity in that direction is restricted to 0 (preventing the vehicle from crashing into unseen objects). -If you wish to move freely into directions without sensor coverage, this can be enabled by setting [CP_GO_NO_DATA](#CP_GO_NO_DATA) to 1. -::: + - [SENS_EN_SF45_CFG](../advanced_config/parameter_reference.md#SENS_EN_SF45_CFG): Set to the serial port you have the sensor connected to. + Make sure GPS or Telemetry are not enabled on this port. + - [SF45_ORIENT_CFG](../advanced_config/parameter_reference.md#SF45_ORIENT_CFG): Set the orientation of the sensor (facing up or down) + - [SF45_UPDATE_CFG](../advanced_config/parameter_reference.md#SF45_UPDATE_CFG): Set the update rate + - [SF45_YAW_CFG](../advanced_config/parameter_reference.md#SF45_YAW_CFG): Set the yaw orientation -Delay, both in the vehicle tracking velocity setpoints and in receiving sensor data from external sources, is conservatively estimated via the [CP_DELAY](#CP_DELAY) parameter. -This should be [tuned](#delay_tuning) to the specific vehicle. +4. [Configure and enable collision prevention](#px4-configuration) -If the sectors adjacent to the commanded sectors are 'better' by a significant margin, the direction of the requested input can be modified by up to the angle specified in [CP_GUIDE_ANG](#CP_GUIDE_ANG). -这有助于微调用户输入,以“引导”机身绕过障碍物,而不是卡在障碍物上。 +PX4 will emit the [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE) message when collision prevention is enabled. +In QGroundControl you should this in the [MAVLink console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) if collision prevention is configured correctly and active. -### 航程数据丢失 +The obstacle overlay in QGC will look like this: -If the autopilot does not receive range data from any sensor for longer than 0.5s, it will output a warning _No range data received, no movement allowed_. -这会导致强制将 xy 的速度设置为 0。 -After 5 seconds of not receiving any data, the vehicle will switch into [HOLD mode](../flight_modes_mc/hold.md). -If you want the vehicle to be able to move again, you will need to disable Collision Prevention by either setting the parameter [CP_DIST](#CP_DIST) to a negative value, or switching to a mode other than [Position mode](../flight_modes_mc/position.md) (e.g. to _Altitude mode_ or _Stabilized mode_). +![sf45](../../assets/sf45/sf45_obstacle_map.png) -如果连接了多个传感器,但是其中有一个传感器失去连接,仍然能够在有传感器数据上报的视野(FOV)范围内飞行。 -故障传感器的数据会失效,并且该传感器覆盖的区域会被视为未覆盖区域,意味着无法移动到该区域。 +### Other Rangefinders -:::warning -Be careful when enabling [CP_GO_NO_DATA=1](#CP_GO_NO_DATA), which allows the vehicle to fly outside the area with sensor coverage. -如果多个传感器中有一个失去连接,故障传感器所覆盖的区域将被视为未覆盖,可以在该区域移动不受限制。 +其他传感器的使能需要修改驱动代码来设置传感器方向和视觉范围。 + +- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST). +- 修改驱动程序以设置方向。 + This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`). +- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`). + +:::tip +You can see the required modifications from the [feature PR](https://github.com/PX4/PX4-Autopilot/pull/12179). +请回馈你的更改! ::: +## PX4 配置 + +_Collision Prevention_ is enabled on PX4 by [setting the parameter](../advanced_config/parameters.md) for minimum allowed approach distance in QGroundControl to a positive value ([CP_DIST](#CP_DIST)). +Note that this value is the distance to the sensors, not the outside of your vehicle or propellers (set a safe margin!). + +In addition you will need to tune the [sendor delay](#delay_tuning) and [angle change tuning](#angle_change_tuning). +You may choose to enable [CP_GO_NO_DATA](#CP_GO_NO_DATA) in order to allow unprotected movement in directions where there is no rangefinder data/sensor. + ### CP_DELAY Delay Tuning {#delay_tuning} There are two main sources of delay which should be accounted for: _sensor delay_, and vehicle _velocity setpoint tracking delay_. @@ -115,75 +127,76 @@ The guidance feature will never direct the vehicle in a direction without sensor 如果只有一个距离传感器指向前方时无人机感到“卡住”,这可能是因为由于缺乏信息,制导无法安全地调整方向。 ::: -## PX4 Distance Sensor {#rangefinder} +### 参数 -### 兰宝 PSK-CM8JL65-CC5 +All relevant parameters are listed below: -At time of writing PX4 allows you to use the [Lanbao PSK-CM8JL65-CC5](../sensor/cm8jl65_ir_distance_sensor.md) IR distance sensor for collision prevention "out of the box", with minimal additional configuration: +| 参数 | 描述 | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST) | Minimum allowed distance from the sensor (the closest distance that the vehicle can approach the obstacle). Set negative to _disable_ collision prevention. | +| [CP_DELAY](../advanced_config/parameter_reference.md#CP_DELAY) | Sensor and velocity setpoint tracking delay. See [Delay Tuning](#delay_tuning) below. | +| [CP_GUIDE_ANG](../advanced_config/parameter_reference.md#CP_GUIDE_ANG) | Angle (to both sides of the commanded direction) within which the vehicle may deviate if it finds fewer obstacles in that direction. See [Guidance Tuning](#angle_change_tuning) below. | +| [CP_GO_NO_DATA](../advanced_config/parameter_reference.md#CP_GO_NO_DATA) | Set to `1` to allow the vehicle to move in directions where there is no sensor coverage (default is 0/`False`). | +| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Set to `Acceleration based` (default). Collision prevention is disabled for `Direct velocity` and `Smoothed velocity`. | -- First [attach and configure the sensor](../sensor/cm8jl65_ir_distance_sensor.md), and enable collision prevention (as described above, using [CP_DIST](#CP_DIST)). -- Set the sensor orientation using [SENS_CM8JL65_R_0](../advanced_config/parameter_reference.md#SENS_CM8JL65_R_0). +## 算法描述 -### LightWare LiDAR SF45 Rotating Lidar +The data from all sensors are fused into an internal representation of 72 sectors around the vehicle, each containing either the sensor data and information about when it was last observed, or an indication that no data for the sector was available. +When the vehicle is commanded to move in a particular direction, all sectors in the hemisphere of that direction are checked to see if the movement will bring the vehicle closer than allowed to any obstacles. 如果是这样,无人机的速度就会受到限制。 -PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](https://www.lightwarelidar.com/shop/sf45-b-50-m/) rotating lidar which provides 320 degree sensing. +The Algorithm then can be split intwo two parts, the constraining of the acceleration setpoint coming from the operator, and the compensation of the current velocity of the vehicle. -The SF45 must be connected via a UART/serial port and configured as described below (In addition to the [collision prevention setup](#px4-software-setup)). +:::info +If there is no sensor data in a particular direction, movement in that direction is restricted to 0 (preventing the vehicle from crashing into unseen objects). +If you wish to move freely into directions without sensor coverage, this can be enabled by setting [CP_GO_NO_DATA](#CP_GO_NO_DATA) to 1. +::: -[LightWare Studio](https://www.lightwarelidar.com/resources-software) configuration: +### Acceleration Constraining -- In the LightWare Studio app enable scanning, set the scan angle, and change the baud rate to `921600`. +For this we split out Acceleration Setpoint into two components, one parallel to the closest distance to the obstacle and one normal to it. Then we scale each of these components according the the figure below. +![Scalefactor](../../assets/computer_vision/collision_prevention/scalefactor.png) -PX4 Configuration: + -- Add the [lightware_sf45_serial](../modules/modules_driver_distance_sensor.md#lightware-sf45-serial) driver in [menuconfig](../hardware/porting_guide_config.md#px4-menuconfig-setup): - - Under **drivers > Distance sensors** select `lightware_sf45_serial`. - - Recompile and upload to the flight controller. -- [Set the following parameters](../advanced_config/parameters.md) via QGC: - - [SENS_EN_SF45_CFG](../advanced_config/parameter_reference.md#SENS_EN_SF45_CFG): Set to the serial port you have the sensor connected to. - Make sure GPS or Telemetry are not enabled on this port. - - [SF45_ORIENT_CFG](../advanced_config/parameter_reference.md#SF45_ORIENT_CFG): Set the orientation of the sensor (facing up or down) - - [SF45_UPDATE_CFG](../advanced_config/parameter_reference.md#SF45_UPDATE_CFG): Set the update rate - - [SF45_YAW_CFG](../advanced_config/parameter_reference.md#SF45_YAW_CFG): Set the yaw orientation +### Velocity compensation -In QGroundControl you should see an [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE) message in the [MAVLink console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) if collision prevention is configured correctly and active. +This velocity restriction takes into account the [jerk-optimal velocity controller](../config_mc/mc_jerk_limited_type_trajectory.md) via [MPC_JERK_MAX](../advanced_config/parameter_reference.md#MPC_JERK_MAX) and [MPC_ACC_HOR](../advanced_config/parameter_reference.md#MPC_ACC_HOR). Whereby +The current velocity is compared with the maximum allowed velocity so that we are still able to break based on the maximal allowed jerk, acceleration and delay. from this we are able to use the proportional gain of the acceleration controller([MPC_XY_VEL_P_ACC](../advanced_config/parameter_reference.md#MPC_XY_VEL_P_ACC)) to transform it into an acceleration. -The obstacle overlay in QGC will look like this: +### Delay -![sf45](../../assets/sf45/sf45_obstacle_map.png) +The delay associated with collision prevention, both in the vehicle tracking velocity setpoints and in receiving sensor data from external sources, is conservatively estimated via the [CP_DELAY](#CP_DELAY) parameter. +This should be [tuned](#delay_tuning) to the specific vehicle. -### Rangefinder Support +If the sectors adjacent to the commanded sectors are 'better' by a significant margin, the direction of the requested input can be modified by up to the angle specified in [CP_GUIDE_ANG](#CP_GUIDE_ANG). +这有助于微调用户输入,以“引导”机身绕过障碍物,而不是卡在障碍物上。 -其他传感器的使能需要修改驱动代码来设置传感器方向和视觉范围。 +### 航程数据丢失 -- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST). -- 修改驱动程序以设置方向。 - This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`). -- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`). +If the autopilot does not receive range data from any sensor for longer than 0.5s, it will output a warning _No range data received, no movement allowed_. +这会导致强制将 xy 的速度设置为 0。 +After 5 seconds of not receiving any data, the vehicle will switch into [HOLD mode](../flight_modes_mc/hold.md). +If you want the vehicle to be able to move again, you will need to disable Collision Prevention by either setting the parameter [CP_DIST](#CP_DIST) to a negative value, or switching to a mode other than [Position mode](../flight_modes_mc/position.md) (e.g. to _Altitude mode_ or _Stabilized mode_). -:::tip -You can see the required modifications from the [feature PR](https://github.com/PX4/PX4-Autopilot/pull/12179). -请回馈你的更改! +如果连接了多个传感器,但是其中有一个传感器失去连接,仍然能够在有传感器数据上报的视野(FOV)范围内飞行。 +故障传感器的数据会失效,并且该传感器覆盖的区域会被视为未覆盖区域,意味着无法移动到该区域。 + +:::warning +Be careful when enabling [CP_GO_NO_DATA=1](#CP_GO_NO_DATA), which allows the vehicle to fly outside the area with sensor coverage. +如果多个传感器中有一个失去连接,故障传感器所覆盖的区域将被视为未覆盖,可以在该区域移动不受限制。 ::: ## Companion Setup {#companion} +:::warning +The companion implementation/setup is currently untested (the original companion project was unmaintained and has been archived). +::: + If using a companion computer or external sensor, it needs to supply a stream of [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE) messages, which should reflect when and where obstacle were detected. The minimum rate at which messages _must_ be sent depends on vehicle speed - at higher rates the vehicle will have a longer time to respond to detected obstacles. - -:::info Initial testing of the system used a vehicle moving at 4 m/s with `OBSTACLE_DISTANCE` messages being emitted at 10Hz (the maximum rate supported by the vision system). 在更高的速度或更低的距离信息更新频率下,该系统应该也能达到不错的效果。 -::: - -The tested companion software is the _local_planner_ from the [PX4/PX4-Avoidance](https://github.com/PX4/PX4-Avoidance) repo. -For more information on hardware and software setup see: [PX4/PX4-Avoidance > Run on Hardware](https://github.com/PX4/PX4-Avoidance#run-on-hardware). - - - -The hardware and software should be set up as described in the [PX4/PX4-Avoidance](https://github.com/PX4/PX4-Avoidance) repo. -In order to emit `OBSTACLE_DISTANCE` messages you must use the _rqt_reconfigure_ tool and set the parameter `send_obstacles_fcu` to true. ## Gazebo 仿真 @@ -196,12 +209,70 @@ make px4_sitl gz_x500_lidar_2d Next, adjust the relevant parameters to the appropriate values and add arbitrary obstacles to your simulation world to test the collision prevention functionality. -The diagram below shows how the simulation looks when viewed in Gazebo. +The diagram below shows a simulation of collision prevention as viewed in Gazebo. ![RViz image of collision detection using the x500\_lidar\_2d model in Gazebo](../../assets/simulation/gazebo/vehicles/x500_lidar_2d_viz.png) - +## Sensor Data Overview (Implementation Details) + +Collision Prevention has an internal obstacle distance map that divides the plane around the drone into 72 Sectors. +Internally this information is stored in the [`obstacle_distance`](../msg_docs/ObstacleDistance.md) UORB topic. +New sensor data is compared to the existing map, and used to update any sections that has changed. + +The angles in the `obstacle_distance` topic are defined as follows: + +![Obstacle\_Distance Angles](../../assets/computer_vision/collision_prevention/obstacle_distance_def.svg) + +The data from rangefinders, rotary lidars, or companion computers, is processed differently, as described below. + +### Rotary Lidars - +Rotary Lidars add their data directly to the [`obstacle_distance`](../msg_docs/ObstacleDistance.md) uORB topic. + +### Rangefinders + +Rangefinders publish their data to the [`distance_sensor`](../msg_docs/DistanceSensor.md) uORB topic. + +This data is then mapped onto the `obstacle_distance` topic. +All sectors which have any overlap with the orientation (`orientation` and `q`) of the rangefinder, and the horizontal field of view (`h_fov`) are assigned that measurement value. +For example, a distance sensor measuring from 9.99° to 10.01° the measurements will get added to the bin's corresponding to 5° and 10° covering the arc from 2.5° and 12.5° + +:::info +the quaternion `q` is only used if the `orientation` is set to `ROTATION_CUSTOM`. +::: - +### 机载电脑 + +Companion computers update the `obstacle_distance` topic using ROS2 or the [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE) MAVLink message. + + + +