diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml
index 3a628503..693c5e25 100644
--- a/aip_xx1_launch/launch/lidar.launch.xml
+++ b/aip_xx1_launch/launch/lidar.launch.xml
@@ -3,10 +3,11 @@
-
+
+
@@ -21,6 +22,7 @@
+
@@ -43,6 +45,7 @@
+
@@ -65,6 +68,7 @@
+
@@ -87,6 +91,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/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py
index 691722a1..6b0a5821 100644
--- a/common_sensor_launch/launch/nebula_node_container.launch.py
+++ b/common_sensor_launch/launch/nebula_node_container.launch.py
@@ -127,20 +127,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",
),
},
],
@@ -248,40 +255,6 @@ def create_parameter_dict(*args):
output="both",
)
- driver_component = 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",
- "ptp_lock_threshold",
- "retry_hw",
- ),
- }
- ],
- )
-
blockage_diag_component = ComposableNode(
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::BlockageDiagComponent",
@@ -307,18 +280,13 @@ def create_parameter_dict(*args):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
- driver_component_loader = LoadComposableNodes(
- composable_node_descriptions=[driver_component],
- target_container=container,
- condition=IfCondition(LaunchConfiguration("launch_driver")),
- )
blockage_diag_loader = LoadComposableNodes(
composable_node_descriptions=[blockage_diag_component],
target_container=container,
condition=IfCondition(LaunchConfiguration("enable_blockage_diag")),
)
- return [container, driver_component_loader, blockage_diag_loader]
+ return [container, blockage_diag_loader]
def generate_launch_description():
@@ -339,8 +307,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
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")
@@ -354,6 +328,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")