Датчики відстані (далекодобива)
Distance sensors provide distance measurement that can be used for terrain following, terrain holding (i.e. precision hovering for photography), improved landing behaviour (conditional range aid), warning of regulatory height limits, collision prevention, etc.
This section lists the distance sensors supported by PX4 (linked to more detailed documentation), and provides information about the generic configuration required for all rangefinders, testing, and simulation with Gazebo or Gazebo-Classic. Додаткову інформацію щодо налаштування та конфігурації надається в темах, посилених нижче (та в бічній панелі).
Підтримувані дальномери
ARK Flow
ARK Flow is an open-source Time-of-Flight (ToF) and optical flow sensor module, which is capable of measuring distances from 8cm to 30m. Він може бути підключений до контролера польоту через свій порт CAN1, що дозволяє підключати додаткові датчики через свій порт CAN2. It supports DroneCAN, runs PX4 DroneCAN Firmware, and is packed into a tiny form factor.
Лідар Holybro ST VL53L1X
The VL53L1X is a state-of-the-art, Time-of-Flight (ToF), laser-ranging sensor, enhancing the ST FlightSense™ product family. Це найшвидший мініатюрний датчик ToF на ринку з точним вимірюванням до 4 м і швидкою частотою вимірювання до 50 Гц.
It comes with a JST GHR 4 pin connector that is compatible with the I2C port on Pixhawk 4, Pixhawk 5X, and other flight controllers that follow the Pixhawk Connector Standard).
Lidar-Lite
Lidar-Lite is a compact, high-performance optical distant measurement rangefinder. Він має діапазон сенсора від (5см - 40м) і може бути підключений до портів PWM або I2C.
MaxBotix I2CXL-MaxSonar-EZ
The MaxBotix I2CXL-MaxSonar-EZ range has a number of relatively short-ranged sonar based rangefinders that are suitable for assisted takeoff/landing and collision avoidance. Ці можуть бути підключені за допомогою порту I2C.
The rangefinders are enabled using the parameter SENS_EN_MB12XX.
Лідари Lightware
Lightware SFxx Lidar provide a broad range of lightweight “laser altimeters” that are suitable for many drone applications.
PX4 підтримує: SF11/c та SF/LW20. PX4 також може бути використаний з наступними припиненими моделями: SF02, SF10/a, SF10/b, SF10/c.
Others may be supported via the RaccoonLab Cyphal and DroneCAN Rangefinder Adapter described below.
PX4 also supports the LightWare LiDAR SF45 Rotating Lidar for collision prevention applications.
Дальніміри TeraRanger
TeraRanger provide a number of lightweight distance measurement sensors based on infrared Time-of-Flight (ToF) technology. Вони зазвичай швидші і мають більший діапазон, ніж ехолокатори, і менші та легші, ніж системи на основі лазера.
PX4 підтримує наступні моделі, підключені через шину I2C: TeraRanger One, TeraRanger Evo 60m та TeraRanger Evo 600Hz.
Стандартний радарний висотомір Ainstein US-D1
The Ainstein US-D1 Standard Radar Altimeter is compact microwave rangefinder that has been optimised for use on UAVs. Він має діапазон виявлення близько 50м. Особливі переваги цього продукту полягають в тому, що він може ефективно працювати в усіх погодних умовах і на всіх типах місцевості (включаючи воду).
LeddarOne
LeddarOne is small Lidar module with a narrow, yet diffuse beam that offers excellent overall detection range and performance, in a robust, reliable, cost-effective package. Він має діапазон сенсора від (5см - 40м) і може бути підключений до портів PWM або I2C.
TFmini
The Benewake TFmini Lidar is a tiny, low cost, and low power LIDAR with 12m range.
PSK-CM8JL65-CC5
DiscontinuedThe Lanbao PSK-CM8JL65-CC5 ToF Infrared Distance Measuring Sensor is a very small (38 mm x 18mm x 7mm, <10g) IR distance sensor with a 0.17m-8m range and millimeter resolution. Це повинно бути підключено до шини UART/серійного порту.
Avionics Anonymous UAVCAN Laser Altimeter Interface
The Avionics Anonymous UAVCAN Laser Altimeter Interface allows several common rangefinders (e.g. Lightware SF11/c, SF30/D, etc) to be connected to the CAN bus via DroneCAN, a more robust interface than I2C.
RaccoonLab Cyphal and DroneCAN Rangefinder Adapter
The RaccoonLab Cyphal and DroneCAN Rangefinder Adapter allows several common rangefinders to be connected to the CAN bus via Cyphal or DroneCAN, providing a more robust interface than I2C or UART. This adapter efficiently reads measurements via I2C or UART and publishes range data in meters, making it a versatile solution for UAVs, robotics, and technical documentation applications.
Supported rangefinders include:
- LightWare LW20/C
- TF-Luna
- Garmin Lite V3
- VL53L1CB
RaccoonLab Cyphal and DroneCAN µRANGEFINDER
RaccoonLab µRANGEFINDER is designed to measure distance and publish it via Cyphal/DroneCAN protocols. It can be used to estimate precision landing or object avoidance.
Features:
- VL53L1CBV0FY-1 sensor
- Input voltage sensor
- CAN connectors: 2 UCANPHY Micro (JST-GH 4).
Configuration/Setup
Rangefinders are usually connected to either a serial (PWM) or I2C port (depending on the device driver), and are enabled on the port by setting a particular parameter.
The hardware and software setup that is specific to each distance sensor is covered in their individual topics.
The generic configuration that is common to all distance sensors, covering both the physical setup and usage, is given below.
Generic Configuration
The common rangefinder configuration is specified using EKF2_RNG_* parameters. These include (non exhaustively):
- EKF2_RNG_POS_X, EKF2_RNG_POS_Y, EKF2_RNG_POS_Z - offset of the rangefinder from the vehicle centre of gravity in X, Y, Z directions.
- EKF2_RNG_PITCH - A value of 0 degrees (default) corresponds to the range finder being exactly aligned with the vehicle vertical axis (i.e. straight down), while 90 degrees indicates that the range finder is pointing forward. Simple trigonometry is used to calculate the distance to ground if a non-zero pitch is used.
- EKF2_RNG_DELAY - approximate delay of data reaching the estimator from the sensor.
- EKF2_RNG_SFE - Range finder range dependent noise scaler.
- EKF2_RNG_NOISE - Measurement noise for range finder fusion
Тестування
The easiest way to test the rangefinder is to vary the range and compare to the values detected by PX4. The sections below show some approaches to getting the measured range.
QGroundControl MAVLink Inspector
The QGroundControl MAVLink Inspector lets you view messages sent from the vehicle, including DISTANCE_SENSOR
information from the rangefinder. The main difference between the tools is that the Analyze tool can plot values in a graph.
INFO
The messages that are sent depend on the vehicle configuration. You will only get DISTANCE_SENSOR
messages if the connected vehicle has a rangefinder installed and is publishing sensor values.
To view the rangefinder output:
Open the menu Q > Select Tool > Analyze Tools:
Select the message
DISTANCE_SENSOR
, and then check the plot checkbox againstcurrent_distance
. The tool will then plot the result:
QGroundControl MAVLink Console
You can also use the QGroundControl MAVLink Console to observe the distance_sensor
uORB topic:
sh
listener distance_sensor 5
INFO
The QGroundControl MAVLink Console works when connected to Pixhawk or other NuttX targets, but not the Simulator. On the Simulator you can run the commands directly in the terminal.
For more information see: Development > Debugging/Logging > Sensor/Topic Debugging using the Listener Command.
Симуляція
Gazebo Simulation
Lidar and sonar rangefinders can be used in the Gazebo simulator. To do this you must start the simulator using a vehicle model that includes the rangefinder.
Downward facing sensors that write to the DistanceSensor UORB topic can be used to test use cases such as landing and terrain following:
Quadrotor(x500) with 1D LIDAR (Down-facing)
shmake px4_sitl gz_x500_lidar_down
Front-facing sensors that write to ObstacleDistance can be used to test Collision Prevention:
- sh
make px4_sitl gz_x500_lidar_2d
Quadrotor(x500) with 1D LIDAR (Front-facing)
shmake px4_sitl gz_x500_lidar_front
Gazebo-Classic Simulation
Lidar and sonar rangefinders can be used in the Gazebo Classic simulator. To do this you must start the simulator using a vehicle model that includes the rangefinder.
The iris optical flow model includes a Lidar rangefinder:
sh
make px4_sitl gazebo-classic_iris_opt_flow
The typhoon_h480 includes a sonar rangefinder:
sh
make px4_sitl gazebo-classic_typhoon_h480
If you need to use a different vehicle you can include the model in its configuration file. You can see how in the respective Iris and Typhoon configuration files:
- xml
<include> <uri>model://lidar</uri> <pose>-0.12 0 0 0 3.1415 0</pose> </include> <joint name="lidar_joint" type="revolute"> <child>lidar::link</child> <parent>iris::base_link</parent> <axis> <xyz>0 0 1</xyz> <limit> <upper>0</upper> <lower>0</lower> </limit> </axis> </joint>
- xml
<include> <uri>model://sonar</uri> </include> <joint name="sonar_joint" type="revolute"> <child>sonar_model::link</child> <parent>typhoon_h480::base_link</parent> <axis> <xyz>0 0 1</xyz> <limit> <upper>0</upper> <lower>0</lower> </limit> </axis> </joint>