Skip to content

Commit

Permalink
feat: use nebula driver for aip_x1_1 sensor configuration (#235)
Browse files Browse the repository at this point in the history
* feat: use nebula driver for aip_x1_1

Signed-off-by: 1222-takeshi <[email protected]>

* ci(pre-commit): autofix

* chore: remove comment out

Signed-off-by: 1222-takeshi <[email protected]>

* chore: remove unnecessary changes

Signed-off-by: 1222-takeshi <[email protected]>

---------

Signed-off-by: 1222-takeshi <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and Autumn60 committed Sep 17, 2024
1 parent 9a252f8 commit b2f6c1a
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 17 deletions.
26 changes: 15 additions & 11 deletions aip_x1_1_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="127.0.0.1"/>
<arg name="use_concat_filter" default="true" />
<arg name="use_radius_search" default="false" />
<arg name="vehicle_id" default="$(env VEHICLE_ID default)" />
Expand All @@ -12,10 +13,11 @@

<group>
<push-ros-namespace namespace="top"/>
<include file="$(find-pkg-share aip_x1_1_launch)/launch/velodyne_VLP16.launch.xml">
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="sensor_frame" value="velodyne_top" />
<arg name="device_ip" value="192.168.1.20"/>
<arg name="port" value="2368"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2368"/>
<arg name="scan_phase" value="180.0" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
Expand All @@ -25,18 +27,20 @@

<group>
<push-ros-namespace namespace="front_center" />
<include file="$(find-pkg-share aip_x1_1_launch)/launch/pandar_node_container.launch.py">
<arg name="model" value="PandarXT-32" />
<arg name="frame_id" value="pandar_xt32_front_center" />
<arg name="device_ip" value="192.168.3.201" />
<arg name="lidar_port" value="2321" />
<arg name="gps_port" value="10121" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="sensor_frame" value="pandar_xt32_front_center" />
<arg name="sensor_ip" value="192.168.3.201" />
<arg name="data_port" value="2321" />
<arg name="gnss_port" value="10121" />
<arg name="scan_phase" value="0.0" />
<arg name="angle_range" value="[0.0, 360.0]"/>
<arg name="distance_range" value="[0.05, 200.0]"/>
<arg name="cloud_min_angle" value="0"/>
<arg name="cloud_max_angle" value="360"/>
<arg name="min_range" value="0.05"/>
<arg name="max_range" value="200.0"/>
<arg name="return_mode" value="Strongest" />
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1_1/xt32.csv" />
<arg name="config_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1_1/xt32.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
</include>
</group>

Expand Down
6 changes: 1 addition & 5 deletions aip_x1_1_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,22 +10,18 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<exec_depend>common_sensor_launch</exec_depend>
<exec_depend>compare_map_segmentation</exec_depend>
<exec_depend>elevation_map_loader</exec_depend>
<exec_depend>ground_segmentation</exec_depend>
<exec_depend>imu_corrector</exec_depend>
<exec_depend>individual_params</exec_depend>
<exec_depend>occupancy_grid_map_outlier_filter</exec_depend>
<exec_depend>pandar_driver</exec_depend>
<exec_depend>pandar_pointcloud</exec_depend>
<exec_depend>pointcloud_preprocessor</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>ros2_socketcan</exec_depend>
<exec_depend>tamagawa_imu_driver</exec_depend>
<exec_depend>topic_state_monitor</exec_depend>
<exec_depend>velodyne_driver</exec_depend>
<exec_depend>velodyne_monitor</exec_depend>
<exec_depend>velodyne_pointcloud</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
1 change: 0 additions & 1 deletion common_sensor_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
<exec_depend>dummy_diag_publisher</exec_depend>
<exec_depend>nebula_sensor_driver</exec_depend>
<exec_depend>velodyne_monitor</exec_depend>
<!-- <exec_depend>nebula_sensor_driver</exec_depend> -->

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down

0 comments on commit b2f6c1a

Please sign in to comment.