Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat/add OT128 and QT128 launch files #218

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/spell_check_pr.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,6 @@ jobs:
--output .github/workflows/.cspell.json \
https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json

- uses: streetsidesoftware/cspell-action@v1.3.4
- uses: streetsidesoftware/cspell-action@v1
with:
config: ".github/workflows/.cspell.json"
4 changes: 2 additions & 2 deletions aip_x1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ def launch_setup(context, *args, **kwargs):
"min_points": 400,
"min_inliers": 200,
"max_iterations": 50,
"height_threshold": 0.15,
"height_threshold": 0.18,
"plane_slope_threshold": 10.0,
"voxel_size_x": 0.2,
"voxel_size_y": 0.2,
Expand Down Expand Up @@ -254,7 +254,7 @@ def launch_setup(context, *args, **kwargs):
{
"map_frame": "map",
"map_layer_name": "elevation",
"height_diff_thresh": 0.15,
"height_diff_thresh": 0.18,
"input_frame": "map",
"output_frame": "base_link",
}
Expand Down
8 changes: 4 additions & 4 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<arg name="lidar_port" value="2321" />
<arg name="gps_port" value="10121" />
<arg name="scan_phase" value="0.0" />
<arg name="return_mode" value="Strongest" />
<arg name="return_mode" value="Dual" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/front_lower.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
Expand Down Expand Up @@ -50,7 +50,7 @@
<arg name="lidar_port" value="2322" />
<arg name="gps_port" value="10122" />
<arg name="scan_phase" value="0.0" />
<arg name="return_mode" value="Strongest" />
<arg name="return_mode" value="Dual" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/left_upper.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
Expand Down Expand Up @@ -84,7 +84,7 @@
<arg name="lidar_port" value="2323" />
<arg name="gps_port" value="10123" />
<arg name="scan_phase" value="0.0" />
<arg name="return_mode" value="Strongest" />
<arg name="return_mode" value="Dual" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/right_upper.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
Expand Down Expand Up @@ -118,7 +118,7 @@
<arg name="lidar_port" value="2324" />
<arg name="gps_port" value="10124" />
<arg name="scan_phase" value="0.0" />
<arg name="return_mode" value="Strongest" />
<arg name="return_mode" value="Dual" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/rear_lower.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
Expand Down
40 changes: 36 additions & 4 deletions aip_x2_launch/launch/pandar_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
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
Expand Down Expand Up @@ -86,8 +88,8 @@ def create_parameter_dict(*args):
cropbox_parameters["negative"] = True

vehicle_info = get_vehicle_info(context)
cropbox_parameters["min_x"] = vehicle_info["min_longitudinal_offset"]
cropbox_parameters["max_x"] = vehicle_info["max_longitudinal_offset"]
cropbox_parameters["min_x"] = vehicle_info["min_longitudinal_offset"] - 0.15
cropbox_parameters["max_x"] = vehicle_info["max_longitudinal_offset"] + 0.15
cropbox_parameters["min_y"] = vehicle_info["min_lateral_offset"]
cropbox_parameters["max_y"] = vehicle_info["max_lateral_offset"]
cropbox_parameters["min_z"] = vehicle_info["min_height_offset"]
Expand Down Expand Up @@ -173,6 +175,23 @@ def create_parameter_dict(*args):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

dual_return_filter_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::DualReturnOutlierFilterComponent",
name="dual_return_filter",
remappings=[
("input", "rectified/pointcloud_ex"),
("output", "outlier_filtered/pointcloud"),
],
parameters=[
{
"vertical_bins": LaunchConfiguration("vertical_bins"),
"visibility_threshold": LaunchConfiguration("visibility_threshold"),
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

container = ComposableNodeContainer(
name="pandar_node_container",
namespace="pointcloud_preprocessor",
Expand All @@ -184,7 +203,6 @@ def create_parameter_dict(*args):
right_mirror_crop_component,
left_mirror_crop_component,
undistort_component,
ring_outlier_filter_component,
],
)

Expand All @@ -194,7 +212,19 @@ def create_parameter_dict(*args):
condition=launch.conditions.IfCondition(LaunchConfiguration("launch_driver")),
)

return [container, driver_loader]
ring_outlier_filter_loader = LoadComposableNodes(
composable_node_descriptions=[ring_outlier_filter_component],
target_container=container,
condition=LaunchConfigurationNotEquals("return_mode", "Dual"),
)

dual_return_filter_loader = LoadComposableNodes(
composable_node_descriptions=[dual_return_filter_component],
target_container=container,
condition=LaunchConfigurationEquals("return_mode", "Dual"),
)

return [container, driver_loader, ring_outlier_filter_loader, dual_return_filter_loader]


def generate_launch_description():
Expand All @@ -221,6 +251,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("vehicle_mirror_param_file")
add_launch_arg("use_multithread", "true")
add_launch_arg("use_intra_process", "true")
add_launch_arg("vertical_bins", "40")
add_launch_arg("visibility_threshold", "0.5")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
38 changes: 38 additions & 0 deletions common_sensor_launch/launch/hesai_OT128.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<launch>

<!-- Params -->
<arg name="launch_driver" default="true"/>

<arg name="model" default="Pandar128E4X"/>
<arg name="sensor_frame" default="pandar"/>
<arg name="return_mode" default="Strongest"/>
<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"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<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)"/>
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<arg name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="ptp_profile" value="802.1as"/>
<arg name="ptp_transport_type" value="L2"/>
</include>
</launch>
38 changes: 38 additions & 0 deletions common_sensor_launch/launch/hesai_QT128.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<launch>

<!-- Params -->
<arg name="launch_driver" default="true"/>

<arg name="model" default="PandarQT128"/>
<arg name="sensor_frame" default="pandar"/>
<arg name="return_mode" default="Strongest"/>
<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"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<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)"/>
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<arg name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="UDP"/>
</include>
</launch>
Loading