Skip to content

Commit

Permalink
chore: add pandar.launch.xml
Browse files Browse the repository at this point in the history
  • Loading branch information
0x126 committed Jul 23, 2024
1 parent 02202d2 commit 56507f7
Show file tree
Hide file tree
Showing 2 changed files with 236 additions and 5 deletions.
220 changes: 220 additions & 0 deletions aip_x2_launch/launch/pandar.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,220 @@
<launch>

<arg name="launch_driver" default="true" />
<arg name="use_concat_filter" default="true" />
<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="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" />
<group>
<push-ros-namespace namespace="front_lower" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="Pandar40P" />
<arg name="frame_id" value="pandar_40p_front" />
<arg name="device_ip" value="192.168.110.201" />
<arg name="lidar_port" value="2321" />
<arg name="gps_port" value="10121" />
<arg name="scan_phase" value="270.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="vertical_bins" value ="40" />
<arg name="horizontal_ring_id" value="12" />
<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)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>
<group>
<push-ros-namespace namespace="front_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="PandarQT" />
<arg name="frame_id" value="pandar_qt_front" />
<arg name="device_ip" value="192.168.120.211" />
<arg name="lidar_port" value="2331" />
<arg name="gps_port" value="10131" />
<arg name="scan_phase" value="270.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<arg name="distance_range" value="[0.1, 7.5]"/>
<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)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

<group>
<push-ros-namespace namespace="left_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="Pandar40P" />
<arg name="frame_id" value="pandar_40p_left" />
<arg name="device_ip" value="192.168.110.202" />
<arg name="lidar_port" value="2322" />
<arg name="gps_port" value="10122" />
<arg name="scan_phase" value="305.0" />
<arg name="angle_range" value="[90.0, 305.0]"/>
<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="vertical_bins" value ="40" />
<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)" />
<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>

<group>
<push-ros-namespace namespace="left_lower" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="PandarQT" />
<arg name="frame_id" value="pandar_qt_left" />
<arg name="device_ip" value="192.168.120.212" />
<arg name="lidar_port" value="2332" />
<arg name="gps_port" value="10132" />
<arg name="scan_phase" value="270.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<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)" />
<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>

<group>
<push-ros-namespace namespace="right_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="Pandar40P" />
<arg name="frame_id" value="pandar_40p_right" />
<arg name="device_ip" value="192.168.120.203" />
<arg name="lidar_port" value="2323" />
<arg name="gps_port" value="10123" />
<arg name="scan_phase" value="270.0" />
<arg name="angle_range" value="[55.0, 270.0]"/>
<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="vertical_bins" value ="40" />
<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)" />
<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>

<group>
<push-ros-namespace namespace="right_lower" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="PandarQT" />
<arg name="frame_id" value="pandar_qt_right" />
<arg name="device_ip" value="192.168.120.213" />
<arg name="lidar_port" value="2333" />
<arg name="gps_port" value="10133" />
<arg name="scan_phase" value="270.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<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)" />
<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>

<group>
<push-ros-namespace namespace="rear_lower" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="Pandar40P" />
<arg name="frame_id" value="pandar_40p_rear" />
<arg name="device_ip" value="192.168.110.204" />
<arg name="lidar_port" value="2324" />
<arg name="gps_port" value="10124" />
<arg name="scan_phase" value="180.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="vertical_bins" value ="40" />
<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)" />
<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>

<group>
<push-ros-namespace namespace="rear_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="PandarQT" />
<arg name="frame_id" value="pandar_qt_rear" />
<arg name="device_ip" value="192.168.120.214" />
<arg name="lidar_port" value="2334" />
<arg name="gps_port" value="10134" />
<arg name="scan_phase" value="180.0" />
<arg name="angle_range" value="[90.0, 270.0]"/>
<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)" />
<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>

<include file="$(find-pkg-share aip_x2_launch)/launch/pointcloud_preprocessor.launch.py">
<arg name="base_frame" value="base_link" />
<arg name="use_intra_process" value="true" />
<arg name="use_multithread" value="true" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
</launch>
21 changes: 16 additions & 5 deletions aip_x2_launch/launch/sensing.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,22 @@
<group>

<!-- LiDAR Driver -->
<include file="$(find-pkg-share aip_x2_launch)/launch/lidar.launch.xml">
<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)"/>
</include>
<let name="launch_nebula" value="true" if="$(var scenario_simulation)"/>
<group if="$(var launch_nebula)">
<include file="$(find-pkg-share aip_x2_launch)/launch/lidar.launch.xml">
<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)"/>
</include>
</group>

<group unless="$(var launch_nebula)">
<include file="$(find-pkg-share aip_x2_launch)/launch/pandar.launch.xml">
<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)"/>
</include>
</group>

<!-- IMU Driver -->
<include file="$(find-pkg-share aip_x2_launch)/launch/imu.launch.xml">
Expand Down

0 comments on commit 56507f7

Please sign in to comment.