Skip to content

Commit

Permalink
chore: update blockage param for aip_x2_launch
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen committed Mar 18, 2024
1 parent cdb212b commit a694f2e
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 4 deletions.
29 changes: 26 additions & 3 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@
<arg name="use_concat_filter" default="true" />
<arg name="vehicle_id" default="$(env VEHICLE_ID default)" />
<arg name="vehicle_mirror_param_file" />
<arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="dual_return_filter_param_file" default="$(find-pkg-share aip_x2_launch)/config/dual_return_filter.param.yaml"/>
<arg name="enable_blockage_diag" default="true"/>

<group>
<push-ros-namespace namespace="lidar" />
Expand All @@ -26,6 +26,9 @@
<arg name="return_mode" value="Strongest" />
<arg name="min_azimuth_deg" value="135.0"/>
<arg name="max_azimuth_deg" value="225.0"/>
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
Expand All @@ -46,6 +49,9 @@
<arg name="vertical_bins" value ="64" />
<arg name="horizontal_ring_id" value="40" />
<arg name="return_mode" value="First" />
<arg name="is_channel_order_top2down" value="false"/>
<arg name="horizontal_resolution" value="0.6"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/front_upper.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
Expand All @@ -68,6 +74,9 @@
<arg name="horizontal_ring_id" value="12" />
<arg name="min_azimuth_deg" value="225.0"/>
<arg name="max_azimuth_deg" value="315.0"/>
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<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)" />
Expand All @@ -89,6 +98,9 @@
<arg name="distance_range" value="[0.1, 7.5]"/>
<arg name="vertical_bins" value ="64" />
<arg name="horizontal_ring_id" value="54" />
<arg name="is_channel_order_top2down" value="false"/>
<arg name="horizontal_resolution" value="0.6"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="return_mode" value="First" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/left_lower.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
Expand All @@ -112,6 +124,9 @@
<arg name="horizontal_ring_id" value="12" />
<arg name="min_azimuth_deg" value="45.0"/>
<arg name="max_azimuth_deg" value="135.0"/>
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<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)" />
Expand All @@ -133,6 +148,9 @@
<arg name="distance_range" value="[0.1, 7.5]"/>
<arg name="vertical_bins" value ="64" />
<arg name="horizontal_ring_id" value="54" />
<arg name="is_channel_order_top2down" value="false"/>
<arg name="horizontal_resolution" value="0.6"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="return_mode" value="First" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/right_lower.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
Expand All @@ -156,6 +174,9 @@
<arg name="horizontal_ring_id" value="12" />
<arg name="min_azimuth_deg" value="135.0"/>
<arg name="max_azimuth_deg" value="225.0"/>
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="return_mode" value="Strongest" />
<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)" />
Expand All @@ -177,6 +198,9 @@
<arg name="distance_range" value="[0.1, 7.5]"/>
<arg name="vertical_bins" value ="64" />
<arg name="horizontal_ring_id" value="40" />
<arg name="is_channel_order_top2down" value="false"/>
<arg name="horizontal_resolution" value="0.6"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="return_mode" value="First" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/rear_upper.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
Expand All @@ -189,8 +213,7 @@
<arg name="base_frame" value="base_link" />
<arg name="use_intra_process" value="true" />
<arg name="use_multithread" value="true" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
Expand Down
10 changes: 9 additions & 1 deletion aip_x2_launch/launch/pandar_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,10 @@ def get_pandar_monitor_info():
return p


def str2vector(string):
return [float(x) for x in string.strip("[]").split(",")]


def get_vehicle_info(context):
# TODO(TIER IV): Use Parameter Substitution after we drop Galactic support
# https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py
Expand Down Expand Up @@ -232,6 +236,7 @@ def create_parameter_dict(*args):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

distance_range = str2vector(context.perform_substitution(LaunchConfiguration("distance_range")))
blockage_diag_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::BlockageDiagComponent",
Expand All @@ -245,7 +250,9 @@ def create_parameter_dict(*args):
"angle_range": LaunchConfiguration("angle_range"),
"horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"),
"vertical_bins": LaunchConfiguration("vertical_bins"),
"model": LaunchConfiguration("model"),
"is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"),
"max_distance_range": distance_range[1],
"horizontal_resolution": LaunchConfiguration("horizontal_resolution"),
}
]
+ [load_composable_node_param("blockage_diagnostics_param_file")],
Expand Down Expand Up @@ -323,6 +330,7 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("input_frame", LaunchConfiguration("base_frame"))
add_launch_arg("output_frame", LaunchConfiguration("base_frame"))
add_launch_arg("dual_return_filter_param_file")
add_launch_arg("horizontal_resolution", "0.4")
add_launch_arg(
"blockage_diagnostics_param_file",
[FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"],
Expand Down

0 comments on commit a694f2e

Please sign in to comment.