-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Migrate sensor driver to the official Ouster ROS 2 driver to mitigate points missing issue.
- Loading branch information
Showing
7 changed files
with
112 additions
and
163 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,14 @@ | ||
<launch> | ||
<include file="$(find-pkg-share av_ouster_launch)/launch/driver_launch.py"> | ||
<arg name="params_file" value="$(find-pkg-share av_ouster_launch)/params/av_ouster_config.yaml"/> | ||
</include> | ||
<arg name="ouster_ns" default="sensor/lidar/top"/> | ||
<group> | ||
<push-ros-namespace namespace="$(var ouster_ns)"/> | ||
<node pkg="ouster_ros" exec="os_driver" name="os_driver" output="screen"> | ||
<param from="$(find-pkg-share av_ouster_launch)/params/av_ouster_config.yaml"/> | ||
</node> | ||
</group> | ||
|
||
<!-- HACK: configure and activate the sensor node via a process execute since state | ||
transition is currently not available through launch.xml format --> | ||
<executable cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_driver configure" launch-prefix="bash -c 'sleep 0; $0 $@'" output="screen"/> | ||
<executable cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_driver activate" launch-prefix="bash -c 'sleep 1; $0 $@'" output="screen"/> | ||
</launch> |
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,52 +1,89 @@ | ||
/**: | ||
ros__parameters: | ||
lidar_ip: 172.31.2.10 | ||
computer_ip: 172.31.0.1 | ||
lidar_mode: "2048x10" | ||
imu_port: 0 | ||
# sensor_hostname[required]: hostname or IP address of the sensor (IP4 or | ||
# IP6). | ||
sensor_hostname: '172.31.2.10' | ||
# udp_dest[optional]: hostname or multicast group IP where the sensor will | ||
# send UDP data packets. | ||
udp_dest: '172.31.0.1' | ||
# mtp_dest[optional]: hostname IP address for receiving data packets via | ||
# multicast, by default it is INADDR_ANY, so packets will be received on | ||
# first available network interface. | ||
mtp_dest: '' | ||
# mtp_main[optional]: if true, then configure and reinit the sensor, | ||
# otherwise start client with active configuration of sensor | ||
mtp_main: false | ||
# lidar_mode[optional]: resolution and rate; possible values: { 512x10, | ||
# 512x20, 1024x10, 1024x20, 2048x10, 4096x5 }. Leave empty to remain on | ||
# current the lidar mode. | ||
lidar_mode: '2048x10' | ||
# timestamp_mode[optional]: method used to timestamp measurements; possible | ||
# values: | ||
# - TIME_FROM_INTERNAL_OSC | ||
# - TIME_FROM_SYNC_PULSE_IN | ||
# - TIME_FROM_PTP_1588 | ||
# - TIME_FROM_ROS_TIME: This option uses the time of reception of first | ||
# packet of a LidarScan as the timestamp of the IMU, | ||
# PointCloud2 and LaserScan messages. | ||
timestamp_mode: 'TIME_FROM_ROS_TIME' | ||
# ptp_utc_tai_offset[optional]: UTC/TAI offset in seconds to apply when | ||
# TIME_FROM_PTP_1588 timestamp mode is used. | ||
ptp_utc_tai_offset: -37.0 | ||
# udp_profile_lidar[optional]: lidar packet profile; possible values: | ||
# - LEGACY: not recommended | ||
# - RNG19_RFL8_SIG16_NIR16 | ||
# - RNG15_RFL8_NIR8 | ||
# - RNG19_RFL8_SIG16_NIR16_DUAL | ||
# - FUSA_RNG15_RFL8_NIR8_DUAL | ||
udp_profile_lidar: 'LEGACY' | ||
# metadata[optional]: path to save metadata file to, if left empty a file | ||
# with the sensor hostname or ip will be crearted in ~/.ros folder. | ||
metadata: '' | ||
# lidar_port[optional]: port value should be in the range [0, 65535]. If you | ||
# use 0 as the port value then the first available port number will be | ||
# assigned. | ||
lidar_port: 0 | ||
sensor_frame: laser_data_frame | ||
laser_frame: lidar_ouster_top | ||
imu_frame: imu_data_frame | ||
|
||
# if False, data are published with sensor data QoS. This is preferable | ||
# for production but default QoS is needed for rosbag. | ||
# See: https://github.com/ros2/rosbag2/issues/125 | ||
use_system_default_qos: True | ||
|
||
# Set the method used to timestamp measurements. | ||
# Valid modes are: | ||
# | ||
# TIME_FROM_INTERNAL_OSC | ||
# TIME_FROM_SYNC_PULSE_IN | ||
# TIME_FROM_PTP_1588 | ||
# TIME_FROM_ROS_RECEPTION | ||
# | ||
# (See this project's README and/or the Ouster Software Guide for more | ||
# information). | ||
# | ||
timestamp_mode: TIME_FROM_ROS_RECEPTION | ||
|
||
# Mask-like-string used to define the data processors that should be | ||
# activated upon startup of the driver. This will determine the topics | ||
# that are available for client applications to consume. The defacto | ||
# reference for these values are defined in: | ||
# `include/ros2_ouster/processors/processor_factories.hpp` | ||
# | ||
# For convenience, the available data processors are: | ||
# | ||
# IMG - Provides 8-bit image topics suitable for ML applications encoding | ||
# the range, ambient and intensity data from a scan | ||
# PCL - Provides a point cloud encoding of a LiDAR scan | ||
# IMU - Provides a data stream from the LiDARs integral IMU | ||
# SCAN - Provides a synthesized 2D LaserScan from the 3D LiDAR data | ||
# | ||
# To construct a valid string for this parameter join the tokens from above | ||
# (in any combination) with the pipe character. For example, valid strings | ||
# include (but are not limited to): | ||
# | ||
# IMG|PCL | ||
# IMG|PCL|IMU|SCAN | ||
# PCL | ||
# | ||
# imu_port[optional]: port value should be in the range [0, 65535]. If you | ||
# use 0 as the port value then the first available port number will be | ||
# assigned. | ||
imu_port: 0 | ||
# sensor_frame[optional]: name to use when referring to the sensor frame. | ||
sensor_frame: lidar_ouster_top | ||
# lidar_frame[optional]: name to use when referring to the lidar frame. | ||
lidar_frame: lidar_ouster_sensor | ||
# imu_frame[optional]: name to use when referring to the imu frame. | ||
imu_frame: imu_ouster | ||
# point_cloud_frame[optional]: which frame of reference to use when | ||
# generating PointCloud2 or LaserScan messages, select between the values of | ||
# lidar_frame and sensor_frame. | ||
point_cloud_frame: lidar_ouster_top | ||
# proc_mask[optional]: use any combination of the 4 flags IMG, PCL, IMU and | ||
# SCAN to enable or disable their respective messages. | ||
proc_mask: PCL | ||
# scan_ring[optional]: use this parameter in conjunction with the SCAN flag | ||
# to select which beam of the LidarScan to use when producing the LaserScan | ||
# message. Choose a value the range [0, sensor_beams_count). | ||
scan_ring: 0 | ||
# use_system_default_qos[optional]: if false, data are published with sensor | ||
# data QoS. This is preferable for production but default QoS is needed for | ||
# rosbag. See: https://github.com/ros2/rosbag2/issues/125 | ||
use_system_default_qos: true | ||
# point_type[optional]: choose from: {original, native, xyz, xyzi, xyzir} | ||
# Here is a brief description of each option: | ||
# - original: This uses the original point representation ouster_ros::Point | ||
# of the ouster-ros driver. | ||
# - native: directly maps all fields as published by the sensor to an | ||
# equivalent point cloud representation with the addition of ring | ||
# and timestamp fields. | ||
# - xyz: the simplest point type, only has {x, y, z} | ||
# - xyzi: same as xyz point type but adds intensity (signal) field. this | ||
# type is not compatible with the low data profile. | ||
# - xyzir: same as xyzi type but adds ring (channel) field. | ||
# this type is same as Velodyne point cloud type | ||
# this type is not compatible with the low data profile. | ||
# for more details about the fields of each point type and their data refer | ||
# to the following header files: | ||
# - ouster_ros/os_point.h | ||
# - ouster_ros/sensor_point_types.h | ||
# - ouster_ros/common_point_types.h. | ||
point_type: original |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters