Skip to content

Commit

Permalink
update lidar launch
Browse files Browse the repository at this point in the history
Signed-off-by: Tomohito Ando <[email protected]>
  • Loading branch information
TomohitoAndo committed Jun 25, 2024
1 parent 5488aad commit 0e704c6
Show file tree
Hide file tree
Showing 2 changed files with 125 additions and 25 deletions.
23 changes: 23 additions & 0 deletions aip_x2_launch/launch/hesai_QT128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,18 @@
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>

<arg name="distance_range" default="[0.5, 200.0]"/>
<arg name="blockage_range" default="[90.0, 270.0]"/>
<arg name="vertical_bins" default ="40" />
<arg name="horizontal_ring_id" default="12" />
<arg name="is_channel_order_top2down" default="true"/>
<arg name="horizontal_resolution" default="0.4"/>
<arg name="enable_blockage_diag" default="$(var enable_blockage_diag)"/>
<arg name="calibration" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2/pandar/front_lower.csv" />
<arg name="dual_return_filter_param_file" default="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" default="$(var vehicle_mirror_param_file)" />
<arg name="blockage_diagnostics_param_file" default="$(find-pkg-share aip_x2_launch)/config/blockage_diagnostics_param_file.yaml" />

<include file="$(find-pkg-share aip_x2_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
Expand All @@ -41,5 +53,16 @@
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="container_name" value="$(var container_name)"/>

<arg name="distance_range" value="$(var distance_range)"/>
<arg name="blockage_range" value="$(var blockage_range)"/>
<arg name="vertical_bins" value ="$(var vertical_bins)"/>
<arg name="horizontal_ring_id" value="$(var horizontal_ring_id)" />
<arg name="is_channel_order_top2down" value="$(var is_channel_order_top2down)"/>
<arg name="horizontal_resolution" value="$(var horizontal_resolution)"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(var calibration)"/>
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)"/>
<arg name="blockage_diagnostics_param_file" value="$(var blockage_diagnostics_param_file)"/>
</include>
</launch>
127 changes: 102 additions & 25 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<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"/>
<arg name="enable_blockage_diag" default="false"/>

<group>
<push-ros-namespace namespace="lidar" />
Expand All @@ -34,9 +34,9 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2321"/>
<arg name="scan_phase" value="90.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Dual"/>
<arg name="cloud_min_angle" value="350"/>
<arg name="cloud_max_angle" value="280"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="1"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
Expand Down Expand Up @@ -65,14 +65,25 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2322"/>
<arg name="scan_phase" value="0.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Dual"/>
<arg name="cloud_min_angle" value="78"/>
<arg name="cloud_max_angle" value="284"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="2"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -85,16 +96,27 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2376"/>
<arg name="scan_phase" value="90.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="cloud_min_angle" value="75"/>
<arg name="cloud_max_angle" value="285"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="L2"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="5"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -107,16 +129,27 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2377"/>
<arg name="scan_phase" value="0.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="cloud_min_angle" value="75"/>
<arg name="cloud_max_angle" value="285"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="L2"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="5"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -130,14 +163,25 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2323"/>
<arg name="scan_phase" value="270.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Dual"/>
<arg name="cloud_min_angle" value="80"/>
<arg name="cloud_max_angle" value="10"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="3"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -150,14 +194,25 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2324"/>
<arg name="scan_phase" value="180.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Dual"/>
<arg name="cloud_min_angle" value="87"/>
<arg name="cloud_max_angle" value="287"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="4"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -170,16 +225,27 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2378"/>
<arg name="scan_phase" value="270.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="cloud_min_angle" value="75"/>
<arg name="cloud_max_angle" value="285"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="L2"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="5"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand All @@ -192,16 +258,27 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2379"/>
<arg name="scan_phase" value="180.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="cloud_min_angle" value="75"/>
<arg name="cloud_max_angle" value="285"/>
<arg name="return_mode" value="LastStrongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="L2"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="5"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand Down

0 comments on commit 0e704c6

Please sign in to comment.