Skip to content

Commit

Permalink
fix: to run with udp awsim (#390)
Browse files Browse the repository at this point in the history
* now it can launch

* Fixed to run lidar driver

Signed-off-by: Shintaro Sakoda <[email protected]>

* ci(pre-commit): autofix

---------

Signed-off-by: Shintaro Sakoda <[email protected]>
Co-authored-by: jpntaxi2 <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
3 people authored Feb 12, 2025
1 parent 21efc83 commit 6ebfda0
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 46 deletions.
7 changes: 6 additions & 1 deletion aip_xx1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,11 @@
<arg name="launch_driver" default="true"/>
<arg name="host_ip" default="192.168.1.10"/>
<arg name="use_concat_filter" default="true"/>
<arg name ="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="enable_blockage_diag" default="true"/>
<arg name="udp_only" default="false"/>

<group>
<push-ros-namespace namespace="lidar"/>
Expand All @@ -21,6 +22,7 @@
<arg name="data_port" value="2368"/>
<arg name="scan_phase" value="300.0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="vertical_bins" value="128"/>
Expand All @@ -43,6 +45,7 @@
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="vertical_bins" value="16"/>
Expand All @@ -65,6 +68,7 @@
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="vertical_bins" value="16"/>
Expand All @@ -87,6 +91,7 @@
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="vertical_bins" value="16"/>
Expand Down
4 changes: 3 additions & 1 deletion aip_xx1_launch/launch/sensing.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@
<arg name="vehicle_mirror_param_file" description="path to the file of vehicle mirror position yaml"/>
<arg name="perception_mode" default="camera_lidar_fusion" description="select perception mode. camera_lidar_fusion, lidar, camera"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name ="vehicle_id" default="$(env VEHICLE_ID default)" />
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="udp_only" default="false"/>

<group>

Expand All @@ -13,6 +14,7 @@
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="udp_only" value="$(var udp_only)"/>
</include>

<!-- Camera Driver -->
Expand Down
64 changes: 20 additions & 44 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
),
},
],
Expand Down Expand Up @@ -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",
Expand All @@ -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():
Expand All @@ -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")
Expand All @@ -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")
Expand Down

0 comments on commit 6ebfda0

Please sign in to comment.