Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(aip_x1): use XT-32 for top lidar #391

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion aip_x1_description/config/sensor_kit_calibration.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
sensor_kit_base_link:
velodyne_top_base_link:
pandar_xt32_top_base_link:
x: 0.000
y: 0.000
z: 0.000
Expand Down
1 change: 0 additions & 1 deletion aip_x1_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>pandar_description</depend>
<depend>velodyne_description</depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
29 changes: 10 additions & 19 deletions aip_x1_description/urdf/sensor_kit.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="sensor_kit_macro" params="parent x y z roll pitch yaw">
<xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
<xacro:include filename="$(find pandar_description)/urdf/pandar_xt32.xacro"/>
<xacro:include filename="$(find imu_description)/urdf/imu.xacro"/>

<xacro:arg name="gpu" default="false"/>
Expand All @@ -20,25 +20,16 @@
<!-- sensor -->
<xacro:property name="calibration" value="${xacro.load_yaml('$(arg config_dir)/sensor_kit_calibration.yaml')}"/>
<!-- lidar -->
<xacro:VLP-16
<xacro:PandarXT-32
name="pandar_xt32_top"
parent="sensor_kit_base_link"
name="velodyne_top"
topic="/points_raw"
hz="10"
samples="220"
gpu="$(arg gpu)"
>
<origin
xyz="${calibration['sensor_kit_base_link']['velodyne_top_base_link']['x']}
${calibration['sensor_kit_base_link']['velodyne_top_base_link']['y']}
${calibration['sensor_kit_base_link']['velodyne_top_base_link']['z']}"
rpy="${calibration['sensor_kit_base_link']['velodyne_top_base_link']['roll']}
${calibration['sensor_kit_base_link']['velodyne_top_base_link']['pitch']}
${calibration['sensor_kit_base_link']['velodyne_top_base_link']['yaw']}"
/>
</xacro:VLP-16>

<xacro:include filename="$(find pandar_description)/urdf/pandar_xt32.xacro"/>
x="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['pandar_xt32_top_base_link']['yaw']}"
/>
<xacro:PandarXT-32
name="pandar_xt32_front_center"
parent="sensor_kit_base_link"
Expand Down
25 changes: 0 additions & 25 deletions aip_x1_launch/config/diagnostic_aggregator/sensor_kit.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,31 +17,6 @@
type: diagnostic_aggregator/AnalyzerGroup
path: lidar
analyzers:
velodyne:
type: diagnostic_aggregator/AnalyzerGroup
path: velodyne
analyzers:
health_monitoring:
type: diagnostic_aggregator/AnalyzerGroup
path: health_monitoring
analyzers:
connection:
type: diagnostic_aggregator/GenericAnalyzer
path: connection
contains: [": velodyne_connection"]
timeout: 3.0

temperature:
type: diagnostic_aggregator/GenericAnalyzer
path: temperature
contains: [": velodyne_temperature"]
timeout: 3.0

rpm:
type: diagnostic_aggregator/GenericAnalyzer
path: rpm
contains: [": velodyne_rpm"]
timeout: 3.0
pandar:
type: diagnostic_aggregator/AnalyzerGroup
path: pandar
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,6 @@
pandar_temperature: default
pandar_ptp: default

# velodyne
velodyne_connection: default
velodyne_temperature: default
velodyne_rpm: default

sensing_topic_status: default

# imu
Expand Down
22 changes: 13 additions & 9 deletions aip_x1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,20 +13,24 @@
<push-ros-namespace namespace="lidar"/>

<group>
<push-ros-namespace namespace="top"/>
<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="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2368"/>
<push-ros-namespace namespace="top" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="sensor_frame" value="pandar_xt32_top" />
<arg name="sensor_ip" value="192.168.1.20" />
<arg name="data_port" value="2368" />
<arg name="gnss_port" value="10121" />
<arg name="scan_phase" value="180.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="config_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1/xt32_top.csv" />
<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="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="front_center" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
Expand All @@ -40,7 +44,7 @@
<arg name="min_range" value="0.05"/>
<arg name="max_range" value="200.0"/>
<arg name="return_mode" value="Strongest" />
<arg name="config_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1/xt32.csv" />
<arg name="config_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1/xt32_front_center.csv" />
<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 Down
Loading