Skip to content

Commit

Permalink
chore: update sensor launch
Browse files Browse the repository at this point in the history
  • Loading branch information
t4-x2 committed May 16, 2024
1 parent b0a4269 commit 7e11d6b
Show file tree
Hide file tree
Showing 6 changed files with 372 additions and 196 deletions.
96 changes: 20 additions & 76 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<launch>

<arg name="launch_driver" default="true"/>
<arg name="host_ip" default="192.168.1.11"/>
<arg name="use_concat_filter" default="true"/>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="vehicle_mirror_param_file"/>
Expand All @@ -9,74 +10,14 @@

<group>
<push-ros-namespace namespace="lidar" />
<group>
<push-ros-namespace namespace="front_lower" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_OT128.launch.xml">
<arg name="sensor_frame" value="pandar_40p_front"/>
<arg name="sensor_ip" value="192.168.1.201"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2368"/>
<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="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"/>
</include>
</group>
<group>
<push-ros-namespace namespace="front_upper" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_QT128.launch.xml">
<arg name="sensor_frame" value="pandar_qt_front"/>
<arg name="sensor_ip" value="192.168.1.211"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2372"/>
<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="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"/>
</include>
</group>

<group>
<push-ros-namespace namespace="left_upper" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_OT128.launch.xml">
<arg name="sensor_frame" value="pandar_40p_left"/>
<arg name="sensor_ip" value="192.168.1.202"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2369"/>
<arg name="scan_phase" value="305.0"/>
<!-- <arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="305"/> -->
<arg name="cloud_min_angle" value="0"/>
<arg name="cloud_max_angle" value="360"/>
<arg name="return_mode" value="FirstStrongest"/>
<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"/>
</include>
</group>

<group>
<push-ros-namespace namespace="left_lower" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_QT128.launch.xml">
<arg name="sensor_frame" value="pandar_qt_left"/>
<arg name="sensor_ip" value="192.168.1.212"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2373"/>
<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="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"/>
</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="use_pointcloud_container" value="true"/>
<arg name="pointcloud_container_name" value="pointcloud_container"/>
</include>

<group>
<push-ros-namespace namespace="right_upper" />
Expand All @@ -91,10 +32,11 @@
<arg name="cloud_min_angle" value="0"/>
<arg name="cloud_max_angle" value="360"/>
<arg name="return_mode" value="FirstStrongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="0"/>
<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"/>

</include>
</group>

Expand All @@ -109,6 +51,10 @@
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="UDP"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="0"/>
<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"/>
Expand All @@ -126,6 +72,8 @@
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="0"/>
<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"/>
Expand All @@ -143,19 +91,15 @@
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<arg name="return_mode" value="Strongest"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_transport_type" value="UDP"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_domain" value="0"/>
<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"/>
</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="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
</launch>
39 changes: 30 additions & 9 deletions aip_x2_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import LoadComposableNodes, ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


Expand All @@ -37,16 +37,18 @@ def launch_setup(context, *args, **kwargs):
parameters=[
{
"input_topics": [
"/sensing/lidar/front_upper/pointcloud",
"/sensing/lidar/front_lower/pointcloud",
"/sensing/lidar/left_upper/pointcloud",
"/sensing/lidar/left_lower/pointcloud",
# "/sensing/lidar/front_upper/pointcloud",
# "/sensing/lidar/front_lower/pointcloud",
# "/sensing/lidar/left_upper/pointcloud",
# "/sensing/lidar/left_lower/pointcloud",
"/sensing/lidar/right_upper/pointcloud",
"/sensing/lidar/right_lower/pointcloud",
"/sensing/lidar/rear_upper/pointcloud",
"/sensing/lidar/rear_lower/pointcloud",
],
"input_offset": [0.025, 0.025, 0.01, 0.0, 0.05, 0.05, 0.05, 0.05],
"input_offset": [
# 0.005, 0.025, 0.050, 0.005,
0.050, 0.005, 0.005, 0.025],
"timeout_sec": 0.075,
"output_frame": LaunchConfiguration("base_frame"),
"input_twist_topic_type": "twist",
Expand All @@ -55,11 +57,30 @@ def launch_setup(context, *args, **kwargs):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

measure_component = ComposableNode(
package="topic_delay",
plugin="TopicDelay",
name="measure_concat",
parameters=[
{
"cloud_topic": "concatenated/pointcloud",
}
]
)

# load concat or passthrough filter
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component],
# concat_loader = ComposableNodeContainer(
# composable_node_descriptions=[concat_component, measure_component],
# namespace="",
# package='rclcpp_components',
# executable='component_container_mt',
# name=LaunchConfiguration("pointcloud_container_name"),
# condition=IfCondition(LaunchConfiguration("use_concat_filter")),
# )

concat_loader = loader = LoadComposableNodes(
composable_node_descriptions=[concat_component, measure_component],
target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_concat_filter")),
)

return [concat_loader]
Expand Down
Loading

0 comments on commit 7e11d6b

Please sign in to comment.