Skip to content

Commit

Permalink
fix: change velodyne to use min and max angle parameters instead of v…
Browse files Browse the repository at this point in the history
…iew angle, increase max view angle to 360

Signed-off-by: David Wong <[email protected]>
  • Loading branch information
drwnz committed Jul 27, 2023
1 parent 0e9f78e commit fa8e704
Show file tree
Hide file tree
Showing 7 changed files with 61 additions and 346 deletions.
78 changes: 39 additions & 39 deletions aip_xx1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<launch>

<arg name="launch_driver" default="true" />
<arg name="host_ip" default="192.168.1.10" />
<arg name="use_concat_filter" default="true" />
<arg name ="vehicle_id" default="$(env VEHICLE_ID default)" />
<arg name="vehicle_mirror_param_file" />
<arg name="launch_driver" default="true"/>
<arg name="host_ip" default="192.168.1.10"/>
<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"/>

Expand All @@ -14,69 +14,69 @@
<group>
<push-ros-namespace namespace="top"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLS128.launch.xml">
<arg name="max_range" value="250.0" />
<arg name="sensor_frame" value="velodyne_top" />
<arg name="max_range" value="250.0"/>
<arg name="sensor_frame" value="velodyne_top"/>
<arg name="device_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="300.0" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="scan_phase" value="300.0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="left"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="5.0" />
<arg name="sensor_frame" value="velodyne_left" />
<arg name="max_range" value="5.0"/>
<arg name="sensor_frame" value="velodyne_left"/>
<arg name="device_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="180.0" />
<arg name="view_direction" value="0.0" />
<arg name="view_width" value="1.9" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="scan_phase" value="180.0"/>
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="right"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="5.0" />
<arg name="sensor_frame" value="velodyne_right" />
<arg name="max_range" value="5.0"/>
<arg name="sensor_frame" value="velodyne_right"/>
<arg name="device_ip" value="192.168.1.203"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2370"/>
<arg name="scan_phase" value="180.0" />
<arg name="view_direction" value="0.0" />
<arg name="view_width" value="1.9" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="scan_phase" value="180.0"/>
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="rear"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="max_range" value="1.5" />
<arg name="sensor_frame" value="velodyne_rear" />
<arg name="max_range" value="1.5"/>
<arg name="sensor_frame" value="velodyne_rear"/>
<arg name="device_ip" value="192.168.1.204"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2371"/>
<arg name="scan_phase" value="180.0" />
<arg name="view_direction" value="0.0" />
<arg name="view_width" value="1.9" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="scan_phase" value="180.0"/>
<arg name="cloud_min_angle" value="300"/>
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand All @@ -102,10 +102,10 @@
</group> -->

<include file="$(find-pkg-share aip_xx1_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="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="container_name" value="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container"/>
</include>

Expand Down
2 changes: 1 addition & 1 deletion common_sensor_launch/launch/hesai_XT32.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<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="359"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
Expand Down
12 changes: 4 additions & 8 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,8 +117,8 @@ def create_parameter_dict(*args):
"max_range",
"frame_id",
"scan_phase",
"view_direction",
"view_width",
"cloud_min_angle",
"cloud_max_angle",
"dual_return_distance_threshold",
),
},
Expand Down Expand Up @@ -281,17 +281,13 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("base_frame", "base_link", "base frame id")
add_launch_arg("min_range", "0.3", "minimum view range for Velodyne sensors")
add_launch_arg("max_range", "300.0", "maximum view range for Velodyne sensors")
add_launch_arg("cloud_min_angle", "0", "minimum view angle for Hesai sensors")
add_launch_arg("cloud_max_angle", "359", "maximum view angle for Hesai sensors")
add_launch_arg("cloud_min_angle", "0", "minimum view angle setting on device")
add_launch_arg("cloud_max_angle", "360", "maximum view angle setting on device")
add_launch_arg("data_port", "2368", "device data port number")
add_launch_arg("gnss_port", "2380", "device gnss port number")
add_launch_arg("rotation_speed", "600.0", "rotational frequency")
add_launch_arg("dual_return_distance_threshold", "0.1", "dual return distance threshold")
add_launch_arg("frame_id", "lidar", "frame id")
add_launch_arg(
"view_direction", "0.0", "lidar view direction: 0~6.28 [rad] for Velodyne sensors"
)
add_launch_arg("view_width", "6.28", "lidar angle: 0~6.28 [rad] for Velodyne sensors")
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox")
add_launch_arg(
Expand Down
8 changes: 4 additions & 4 deletions common_sensor_launch/launch/velodyne_VLP16.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="scan_phase" default="0.0"/>
<arg name="view_direction" default="0.0"/>
<arg name="view_width" default="6.28"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>
Expand All @@ -29,8 +29,8 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="$(var data_port)"/>
<arg name="scan_phase" value="$(var scan_phase)"/>
<arg name="view_direction" value="$(var view_direction)"/>
<arg name="view_width" value="$(var view_width)"/>
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="false"/>
Expand Down
18 changes: 9 additions & 9 deletions common_sensor_launch/launch/velodyne_VLP32C.launch.xml
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
<launch>

<!-- Params -->
<arg name="launch_driver" default="true" />
<arg name="launch_driver" default="true"/>

<arg name="model" default="VLP32"/>
<arg name="max_range" default="200.0" />
<arg name="min_range" default="0.4" />
<arg name="max_range" default="200.0"/>
<arg name="min_range" default="0.4"/>
<arg name="sensor_frame" default="velodyne"/>
<arg name="return_mode" default="SingleStrongest"/>
<arg name="device_ip" default="192.168.1.201"/>
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="scan_phase" default="0.0"/>
<arg name="view_direction" default="0.0"/>
<arg name="view_width" default="6.28"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>
Expand All @@ -29,11 +29,11 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="$(var data_port)"/>
<arg name="scan_phase" value="$(var scan_phase)"/>
<arg name="view_direction" value="$(var view_direction)"/>
<arg name="view_width" value="$(var view_width)"/>
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="false" />
<arg name="use_multithread" value="false" />
<arg name="use_intra_process" value="false"/>
<arg name="use_multithread" value="false"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
Expand Down
8 changes: 4 additions & 4 deletions common_sensor_launch/launch/velodyne_VLS128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="scan_phase" default="0.0"/>
<arg name="view_direction" default="0.0"/>
<arg name="view_width" default="6.28"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>
Expand All @@ -29,8 +29,8 @@
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="$(var data_port)"/>
<arg name="scan_phase" value="$(var scan_phase)"/>
<arg name="view_direction" value="$(var view_direction)"/>
<arg name="view_width" value="$(var view_width)"/>
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
Expand Down
Loading

0 comments on commit fa8e704

Please sign in to comment.