diff --git a/aip_x2_gen2_launch/config/dual_return_filter.param.yaml b/aip_x2_gen2_launch/config/dual_return_filter.param.yaml
index 75168e7b..a87fef47 100644
--- a/aip_x2_gen2_launch/config/dual_return_filter.param.yaml
+++ b/aip_x2_gen2_launch/config/dual_return_filter.param.yaml
@@ -1,13 +1,16 @@
/**:
ros__parameters:
- roi_mode: "Fixed_azimuth_ROI" # description="options: `No_ROI`, `Fixed_xyz_ROI` or `Fixed_azimuth_ROI`"/>
- weak_first_local_noise_threshold: 2 # description="for No_ROI roi_mode, recommended value is 10" />
- visibility_error_threshold: 0.95
- visibility_warn_threshold: 0.97
- max_distance: 10.0
x_max: 18.0
x_min: -12.0
y_max: 2.0
y_min: -2.0
z_max: 10.0
z_min: 0.0
+ max_distance: 10.0
+ max_azimuth_diff: 50.0
+ weak_first_distance_ratio: 1.004
+ general_distance_ratio: 1.03
+ weak_first_local_noise_threshold: 2
+ roi_mode: "Fixed_azimuth_ROI"
+ visibility_error_threshold: 0.92
+ visibility_warn_threshold: 0.95
diff --git a/aip_x2_gen2_launch/launch/hesai_OT128.launch.xml b/aip_x2_gen2_launch/launch/hesai_OT128.launch.xml
deleted file mode 100644
index 8bbaddca..00000000
--- a/aip_x2_gen2_launch/launch/hesai_OT128.launch.xml
+++ /dev/null
@@ -1,74 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/aip_x2_gen2_launch/launch/hesai_QT128.launch.xml b/aip_x2_gen2_launch/launch/hesai_QT128.launch.xml
deleted file mode 100644
index 67b9f0b8..00000000
--- a/aip_x2_gen2_launch/launch/hesai_QT128.launch.xml
+++ /dev/null
@@ -1,72 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/aip_x2_gen2_launch/launch/lidar.launch.xml b/aip_x2_gen2_launch/launch/lidar.launch.xml
index bddb9a2a..01ffe80a 100644
--- a/aip_x2_gen2_launch/launch/lidar.launch.xml
+++ b/aip_x2_gen2_launch/launch/lidar.launch.xml
@@ -27,9 +27,10 @@
-
+
+
-
+
@@ -37,15 +38,18 @@
-
+
+
+
-
+
+
+
-
@@ -55,14 +59,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -70,12 +80,16 @@
-
+
+
+
-
+
+
+
@@ -87,14 +101,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -102,12 +122,16 @@
-
+
+
+
-
+
+
+
@@ -119,14 +143,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -134,12 +164,16 @@
-
+
+
+
-
+
+
+
@@ -151,15 +185,21 @@
+
+
+
+
+
-
+
+
-
+
@@ -167,12 +207,16 @@
-
+
+
+
-
+
+
+
@@ -184,14 +228,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -199,12 +249,16 @@
-
+
+
+
-
+
+
+
@@ -216,14 +270,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -231,12 +291,16 @@
-
+
+
+
-
+
+
+
@@ -248,14 +312,20 @@
+
+
+
+
+
-
+
+
-
+
@@ -263,12 +333,16 @@
-
+
+
+
-
+
+
+
@@ -280,6 +354,11 @@
+
+
+
+
+
diff --git a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py
index e8a4a55a..c288f0e5 100644
--- a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py
+++ b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py
@@ -19,8 +19,6 @@
# from launch.conditions import LaunchConfigurationNotEquals
from launch.conditions import IfCondition
-from launch.conditions import LaunchConfigurationEquals
-from launch.conditions import LaunchConfigurationNotEquals
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
@@ -110,9 +108,11 @@ def str2vector(string):
"ptp_transport_type",
"ptp_switch_type",
"ptp_domain",
+ "ptp_lock_threshold",
"diag_span",
"calibration_file",
"launch_hw",
+ "udp_only",
),
"retry_hw": True,
},
@@ -243,13 +243,13 @@ def str2vector(string):
ring_outlier_filter_loader = LoadComposableNodes(
composable_node_descriptions=[ring_outlier_filter_component],
target_container=container,
- condition=LaunchConfigurationNotEquals("return_mode", "Dual"),
+ condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_dual_return_filter")),
)
dual_return_filter_loader = LoadComposableNodes(
composable_node_descriptions=[dual_return_filter_component],
target_container=container,
- condition=LaunchConfigurationEquals("return_mode", "Dual"),
+ condition=launch.conditions.IfCondition(LaunchConfiguration("use_dual_return_filter")),
)
blockage_diag_loader = LoadComposableNodes(
@@ -288,6 +288,8 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("host_ip", "255.255.255.255", "host ip address")
add_launch_arg("sync_angle", "0")
add_launch_arg("cut_angle", "0.0")
+ add_launch_arg("ptp_lock_threshold", "100")
+ add_launch_arg("udp_only", "false")
# add_launch_arg("point_filters", "{}", "point filter definitions in JSON format")
add_launch_arg("base_frame", "base_link", "base frame id")
add_launch_arg("min_range", "0.3", "minimum view range for Velodyne sensors")
@@ -331,6 +333,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("calibration_file", "")
add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame")
+ add_launch_arg("use_dual_return_filter", "false")
set_container_executable = SetLaunchConfiguration(
"container_executable",
diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml
index e2b1b04b..f0fc0d31 100644
--- a/aip_xx1_launch/launch/lidar.launch.xml
+++ b/aip_xx1_launch/launch/lidar.launch.xml
@@ -3,12 +3,13 @@
-
+
+
@@ -23,6 +24,7 @@
+
@@ -48,6 +50,7 @@
+
@@ -73,6 +76,7 @@
+
@@ -98,6 +102,7 @@
+
diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml
index c2e659a0..853eff63 100644
--- a/aip_xx1_launch/launch/sensing.launch.xml
+++ b/aip_xx1_launch/launch/sensing.launch.xml
@@ -4,7 +4,8 @@
-
+
+
@@ -13,6 +14,7 @@
+
diff --git a/common_sensor_launch/launch/hesai_OT128.launch.xml b/common_sensor_launch/launch/hesai_OT128.launch.xml
index 4debfa6c..c30acb0a 100644
--- a/common_sensor_launch/launch/hesai_OT128.launch.xml
+++ b/common_sensor_launch/launch/hesai_OT128.launch.xml
@@ -18,6 +18,7 @@
+
@@ -42,6 +43,8 @@
+
+
diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml
index 7ee9423a..ee951dd7 100644
--- a/common_sensor_launch/launch/hesai_XT32.launch.xml
+++ b/common_sensor_launch/launch/hesai_XT32.launch.xml
@@ -19,6 +19,7 @@
+
@@ -43,7 +44,9 @@
+
+
diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py
index 15f208d4..35c9ae4e 100644
--- a/common_sensor_launch/launch/nebula_node_container.launch.py
+++ b/common_sensor_launch/launch/nebula_node_container.launch.py
@@ -128,19 +128,27 @@ def create_parameter_dict(*args):
**create_parameter_dict(
"host_ip",
"sensor_ip",
+ "multicast_ip",
+ "advanced_diagnostics",
"data_port",
- "gnss_port",
"return_mode",
"min_range",
"max_range",
"frame_id",
"scan_phase",
- "cloud_min_angle",
- "cloud_max_angle",
"dual_return_distance_threshold",
"rotation_speed",
+ "cloud_min_angle",
+ "cloud_max_angle",
+ "gnss_port",
"packet_mtu_size",
"setup_sensor",
+ "udp_only",
+ "ptp_profile",
+ "ptp_transport_type",
+ "ptp_switch_type",
+ "ptp_domain",
+ "diag_span",
),
},
],
@@ -298,42 +306,6 @@ def create_parameter_dict(*args):
)
)
- if IfCondition(LaunchConfiguration("launch_driver")).evaluate(context):
- nodes.append(
- ComposableNode(
- package="nebula_ros",
- plugin=sensor_make + "HwInterfaceRosWrapper",
- # node is created in a global context, need to avoid name clash
- name=sensor_make.lower() + "_hw_interface_ros_wrapper_node",
- parameters=[
- {
- "sensor_model": sensor_model,
- "calibration_file": sensor_calib_fp,
- **create_parameter_dict(
- "sensor_ip",
- "host_ip",
- "scan_phase",
- "return_mode",
- "frame_id",
- "rotation_speed",
- "data_port",
- "gnss_port",
- "cloud_min_angle",
- "cloud_max_angle",
- "packet_mtu_size",
- "dual_return_distance_threshold",
- "setup_sensor",
- "ptp_profile",
- "ptp_transport_type",
- "ptp_switch_type",
- "ptp_domain",
- "retry_hw",
- ),
- }
- ],
- )
- )
-
if IfCondition(LaunchConfiguration("enable_blockage_diag")).evaluate(context):
nodes.append(
ComposableNode(
@@ -377,8 +349,8 @@ def create_parameter_dict(*args):
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=nodes,
- condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="both",
+ condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
)
load_composable_nodes = LoadComposableNodes(
@@ -405,10 +377,17 @@ def add_launch_arg(name: str, default_value=None, description=None):
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("udp_only", "False", "use UDP only")
add_launch_arg("retry_hw", "false", "retry hw")
add_launch_arg("sensor_ip", "192.168.1.201", "device ip address")
+ add_launch_arg(
+ "multicast_ip",
+ "",
+ "the multicast group the sensor shall broadcast to. leave empty to disable multicast",
+ )
add_launch_arg("host_ip", "255.255.255.255", "host ip address")
- add_launch_arg("scan_phase", "0.0")
+ add_launch_arg("sync_angle", "0")
+ add_launch_arg("cut_angle", "0.0")
add_launch_arg("base_frame", "base_link", "base frame id")
add_launch_arg("min_range", "0.3", "minimum view range for Velodyne sensors")
add_launch_arg("max_range", "300.0", "maximum view range for Velodyne sensors")
@@ -422,6 +401,8 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("frame_id", "lidar", "frame id")
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox")
+ add_launch_arg("diag_span", "1000")
+ add_launch_arg("advanced_diagnostics", "false")
add_launch_arg("use_multithread", "False", "use multithread")
add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication")
add_launch_arg("lidar_container_name", "nebula_node_container")
@@ -432,6 +413,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("ptp_transport_type", "L2")
add_launch_arg("ptp_switch_type", "TSN")
add_launch_arg("ptp_domain", "0")
+ add_launch_arg("ptp_lock_threshold", "100")
add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame")
add_launch_arg("enable_blockage_diag", "true")
add_launch_arg("horizontal_ring_id", "64")
diff --git a/common_sensor_launch/launch/velodyne_VLP16.launch.xml b/common_sensor_launch/launch/velodyne_VLP16.launch.xml
index 02fe8820..c6e71866 100644
--- a/common_sensor_launch/launch/velodyne_VLP16.launch.xml
+++ b/common_sensor_launch/launch/velodyne_VLP16.launch.xml
@@ -24,6 +24,7 @@
+
@@ -50,6 +51,7 @@
+
diff --git a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml
index 219fcaa4..52d4d489 100644
--- a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml
+++ b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml
@@ -24,6 +24,7 @@
+
@@ -50,6 +51,7 @@
+
diff --git a/common_sensor_launch/launch/velodyne_VLS128.launch.xml b/common_sensor_launch/launch/velodyne_VLS128.launch.xml
index 272b038a..fba3d1ed 100644
--- a/common_sensor_launch/launch/velodyne_VLS128.launch.xml
+++ b/common_sensor_launch/launch/velodyne_VLS128.launch.xml
@@ -24,6 +24,7 @@
+
@@ -50,6 +51,7 @@
+