Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
Signed-off-by: Tomohito Ando <[email protected]>
  • Loading branch information
TomohitoAndo committed Jun 21, 2024
1 parent c04c1a5 commit a3645c5
Show file tree
Hide file tree
Showing 3 changed files with 397 additions and 177 deletions.
26 changes: 24 additions & 2 deletions aip_x2_launch/launch/hesai_OT128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,26 @@
<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="cloud_min_angle" default="90"/>
<arg name="cloud_max_angle" default="270"/>
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="ptp_switch_type" default="TSN"/>
<arg name="ptp_domain" default="0"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>
<arg name="setup_sensor" default="true"/>

<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)" />

<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 +52,16 @@
<arg name="use_multithread" value="true"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="setup_sensor" value="$(var setup_sensor)"/>

<arg name="distance_range" value="$(var enable_blockage_diag)"/>
<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)"/>

</include>
</launch>
32 changes: 23 additions & 9 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,16 @@
<arg name="launch_driver" default="true"/>
<arg name="setup_sensor" default="true"/>
<arg name="host_ip" default="192.168.1.11"/>
<!-- <arg name="host_ip" default="255.255.255.255"/> -->
<!-- <arg name="host_ip" default="224.0.3.3"/> -->
<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 @@ -30,7 +33,7 @@
<arg name="sensor_ip" value="192.168.1.202"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2321"/>
<arg name="scan_phase" value="270.0"/>
<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"/>
Expand All @@ -39,18 +42,29 @@
<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>

<group>
<!-- <group>
<push-ros-namespace namespace="rear_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/hesai_OT128.launch.xml">
<arg name="setup_sensor" value="$(var setup_sensor)"/>
<arg name="sensor_frame" value="pandar_40p_rear"/>
<arg name="sensor_ip" value="192.168.1.203"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2322"/>
<arg name="scan_phase" value="180.0"/>
<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"/>
Expand All @@ -70,7 +84,7 @@
<arg name="sensor_ip" value="192.168.1.212"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2376"/>
<arg name="scan_phase" value="270.0"/>
<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"/>
Expand All @@ -92,7 +106,7 @@
<arg name="sensor_ip" value="192.168.1.213"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2377"/>
<arg name="scan_phase" value="180.0"/>
<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"/>
Expand All @@ -104,10 +118,10 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>
</group> -->

<!-- LiDARs connected to Sub ECU -->
<group>
<!-- <group>
<push-ros-namespace namespace="left_upper" />
<include file="$(find-pkg-share aip_x2_launch)/launch/hesai_OT128.launch.xml">
<arg name="setup_sensor" value="$(var setup_sensor)"/>
Expand Down Expand Up @@ -189,7 +203,7 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
</group> -->

</group>
</launch>
Loading

0 comments on commit a3645c5

Please sign in to comment.