Use LiDAR-Lite v3 [GARMIN] with Pixracer r15
* Goal
- get data obtained from lidar connected with pixracer r15 via rostopic.
* reference
https://docs.px4.io/main/en/sensor/lidar_lite.html
Lidar-Lite | PX4 User Guide
Lidar-Lite LIDAR-Lite is a compact, high-performance optical distant measurement sensor solution for drone, robot or unmanned vehicle applications. It can be connected to either I2C or PWM. Where to Buy Pinouts The Lidar-Lite (v2, v3) pinout is shown below
docs.px4.io
https://github.com/mavlink/mavros/issues/664
How to use distance_sensor? send distance Sensor data to FCU for use as altitude · Issue #664 · mavlink/mavros
https://github.com/mavlink/mavros/blob/master/mavros_extras/src/plugins/distance_sensor.cpp ? this plugin blacklisted
github.com
* Procedure
1. Connect lidar-lite v3 to the pixracer
- we will use i2c, so connect to the GPS(i2c) Port
- Please connect 680 uF capacitor between power and ground
2. Change QgroundControl setting and reboot
- set SENS_EN_LL40LS to 2(i2c)
3. Change mavros settings
3.1 px4_config.yaml
- change order between (lidarlite_pub:) and (hrlv_ez4_pub:).
- change id of lidarlite_pub to 0, and id of hrlv_ez4_pub to 1
from
distance_sensor:
hrlv_ez4_pub:
id: 0
frame_id: "hrlv_ez4_sonar"
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
lidarlite_pub:
id: 1
frame_id: "lidarlite_laser"
orientation: PITCH_270
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
sonar_1_sub:
subscriber: true
id: 2
orientation: PITCH_270
horizontal_fov_ratio: 1.0 # horizontal_fov = horizontal_fov_ratio * msg.field_of_view
vertical_fov_ratio: 1.0 # vertical_fov = vertical_fov_ratio * msg.field_of_view
# custom_orientation: # Used for orientation == CUSTOM
# roll: 0
# pitch: 270
# yaw: 0
laser_1_sub:
subscriber: true
id: 3
orientation: PITCH_270
to
distance_sensor:
lidarlite_pub:
id: 0
frame_id: "lidarlite_laser"
orientation: PITCH_270
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
hrlv_ez4_pub:
id: 1
frame_id: "hrlv_ez4_sonar"
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
sonar_1_sub:
subscriber: true
id: 2
orientation: PITCH_270
horizontal_fov_ratio: 1.0 # horizontal_fov = horizontal_fov_ratio * msg.field_of_view
vertical_fov_ratio: 1.0 # vertical_fov = vertical_fov_ratio * msg.field_of_view
# custom_orientation: # Used for orientation == CUSTOM
# roll: 0
# pitch: 270
# yaw: 0
laser_1_sub:
subscriber: true
id: 3
orientation: PITCH_270
3.2 px4_pluginlists.yaml
comment these two.
- distance_sensor
- rangefinder
from
plugin_blacklist:
# common
- safety_area
# extras
- image_pub
- vibration
- distance_sensor
- rangefinder
- wheel_odometry
plugin_whitelist: []
#- 'sys_*'
to
plugin_blacklist:
# common
- safety_area
# extras
- image_pub
- vibration
#- distance_sensor
#- rangefinder
- wheel_odometry
plugin_whitelist: []
#- 'sys_*'
4. Run mavros and echo the topic
rostopic echo /mavros/distance_sensor/lidarlite_pub
End