Skip to content

Commit

Permalink
Merge branch 'main' into feat/gnss_poser/subscribe_map_projector_info
Browse files Browse the repository at this point in the history
  • Loading branch information
kminoda authored Aug 30, 2023
2 parents a1df5fd + ad2e34a commit 623a5e6
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 28 deletions.
28 changes: 10 additions & 18 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
# limitations under the License.

import os
import warnings

from ament_index_python.packages import get_package_share_directory
import launch
Expand Down Expand Up @@ -73,31 +72,17 @@ def create_parameter_dict(*args):
sensor_model = LaunchConfiguration("sensor_model").perform(context)
sensor_make, sensor_extension = get_lidar_make(sensor_model)
nebula_decoders_share_dir = get_package_share_directory("nebula_decoders")
nebula_ros_share_dir = get_package_share_directory("nebula_ros")

# Config
sensor_params_fp = LaunchConfiguration("config_file").perform(context)
if sensor_params_fp == "":
warnings.warn("No config file provided, using sensor model default", RuntimeWarning)
sensor_params_fp = os.path.join(
nebula_ros_share_dir, "config", sensor_make.lower(), sensor_model + ".yaml"
)

# Calibration file
sensor_calib_fp = os.path.join(
nebula_decoders_share_dir,
"calibration",
sensor_make.lower(),
sensor_model + sensor_extension,
)
if not os.path.exists(sensor_params_fp):
sensor_params_fp = os.path.join(nebula_ros_share_dir, "config", "BaseParams.yaml")
assert os.path.exists(
sensor_params_fp
), "Sensor params yaml file under config/ was not found: {}".format(sensor_params_fp)
assert os.path.exists(
sensor_calib_fp
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)
with open(sensor_params_fp, "r") as f:
sensor_params = yaml.safe_load(f)["/**"]["ros__parameters"]

nodes = []

Expand All @@ -107,11 +92,13 @@ def create_parameter_dict(*args):
plugin=sensor_make + "DriverRosWrapper",
name=sensor_make.lower() + "_driver_ros_wrapper_node",
parameters=[
sensor_params,
{
"calibration_file": sensor_calib_fp,
"sensor_model": sensor_model,
**create_parameter_dict(
"host_ip",
"sensor_ip",
"data_port",
"return_mode",
"min_range",
"max_range",
Expand Down Expand Up @@ -243,6 +230,9 @@ def create_parameter_dict(*args):
"gnss_port",
"cloud_min_angle",
"cloud_max_angle",
"packet_mtu_size",
"dual_return_distance_threshold",
"setup_sensor",
),
}
],
Expand Down Expand Up @@ -275,6 +265,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("sensor_model", description="sensor model name")
add_launch_arg("config_file", "", description="sensor configuration file")
add_launch_arg("launch_driver", "True", "do launch driver")
add_launch_arg("setup_sensor", "True", "configure sensor")
add_launch_arg("sensor_ip", "192.168.1.201", "device ip address")
add_launch_arg("host_ip", "255.255.255.255", "host ip address")
add_launch_arg("scan_phase", "0.0")
Expand All @@ -285,6 +276,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("cloud_max_angle", "360", "maximum view angle setting on device")
add_launch_arg("data_port", "2368", "device data port number")
add_launch_arg("gnss_port", "2380", "device gnss port number")
add_launch_arg("packet_mtu_size", "1500", "packet mtu size")
add_launch_arg("rotation_speed", "600", "rotational frequency")
add_launch_arg("dual_return_distance_threshold", "0.1", "dual return distance threshold")
add_launch_arg("frame_id", "lidar", "frame id")
Expand Down
6 changes: 3 additions & 3 deletions common_sensor_launch/launch/velodyne_VLP16.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="min_range" default="0.4"/>
<arg name="sensor_frame" default="velodyne"/>
<arg name="return_mode" default="SingleStrongest"/>
<arg name="device_ip" default="192.168.1.201"/>
<arg name="sensor_ip" default="192.168.1.201"/>
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="scan_phase" default="0.0"/>
Expand All @@ -23,7 +23,7 @@
<arg name="max_range" value="$(var max_range)"/>
<arg name="min_range" value="$(var min_range)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<arg name="sensor_ip" value="$(var device_ip)"/>
<arg name="sensor_ip" value="$(var sensor_ip)"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="$(var data_port)"/>
<arg name="scan_phase" value="$(var scan_phase)"/>
Expand All @@ -38,6 +38,6 @@

<!-- Velodyne Monitor -->
<include file="$(find-pkg-share velodyne_monitor)/launch/velodyne_monitor.launch.xml" if="$(var launch_driver)">
<arg name="ip_address" value="$(var device_ip)"/>
<arg name="ip_address" value="$(var sensor_ip)"/>
</include>
</launch>
6 changes: 3 additions & 3 deletions common_sensor_launch/launch/velodyne_VLS128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="min_range" default="0.5"/>
<arg name="sensor_frame" default="velodyne"/>
<arg name="return_mode" default="SingleStrongest"/>
<arg name="device_ip" default="192.168.1.201"/>
<arg name="sensor_ip" default="192.168.1.201"/>
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="scan_phase" default="0.0"/>
Expand All @@ -23,7 +23,7 @@
<arg name="max_range" value="$(var max_range)"/>
<arg name="min_range" value="$(var min_range)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<arg name="sensor_ip" value="$(var device_ip)"/>
<arg name="sensor_ip" value="$(var sensor_ip)"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="$(var data_port)"/>
<arg name="scan_phase" value="$(var scan_phase)"/>
Expand All @@ -38,6 +38,6 @@

<!-- Velodyne Monitor -->
<include file="$(find-pkg-share velodyne_monitor)/launch/velodyne_monitor.launch.xml" if="$(var launch_driver)">
<arg name="ip_address" value="$(var device_ip)"/>
<arg name="ip_address" value="$(var sensor_ip)"/>
</include>
</launch>
8 changes: 4 additions & 4 deletions sample_sensor_kit_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLS128.launch.xml">
<arg name="max_range" value="250.0"/>
<arg name="sensor_frame" value="velodyne_top"/>
<arg name="device_ip" value="192.168.1.201"/>
<arg name="sensor_ip" value="192.168.1.201"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2368"/>
<arg name="scan_phase" value="300.0"/>
Expand All @@ -31,7 +31,7 @@
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="5.0"/>
<arg name="sensor_frame" value="velodyne_left"/>
<arg name="device_ip" value="192.168.1.202"/>
<arg name="sensor_ip" value="192.168.1.202"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2369"/>
<arg name="scan_phase" value="180.0"/>
Expand All @@ -49,7 +49,7 @@
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="5.0"/>
<arg name="sensor_frame" value="velodyne_right"/>
<arg name="device_ip" value="192.168.1.203"/>
<arg name="sensor_ip" value="192.168.1.203"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2370"/>
<arg name="scan_phase" value="180.0"/>
Expand All @@ -67,7 +67,7 @@
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="1.5"/>
<arg name="sensor_frame" value="velodyne_rear"/>
<arg name="device_ip" value="192.168.1.204"/>
<arg name="sensor_ip" value="192.168.1.204"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2371"/>
<arg name="scan_phase" value="180.0"/>
Expand Down

0 comments on commit 623a5e6

Please sign in to comment.