Skip to content

Commit

Permalink
fix: change for x1 bench
Browse files Browse the repository at this point in the history
Signed-off-by: kimurariku <[email protected]>
  • Loading branch information
kimurariku committed Feb 12, 2025
1 parent cc02a7b commit cadb756
Show file tree
Hide file tree
Showing 7 changed files with 30 additions and 63 deletions.
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
27 changes: 10 additions & 17 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,23 +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>
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:include filename="$(find pandar_description)/urdf/pandar_xt32.xacro"/>
<xacro:PandarXT-32
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,12 +26,6 @@
pandar_temperature: default
pandar_ptp: default

# velodyne
velodyne_connection: default
velodyne_temperature: default
velodyne_rpm: default

sensing_topic_status: default

# imu
gyro_bias_estimator: default
2 changes: 1 addition & 1 deletion aip_x1_launch/launch/imu.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<push-ros-namespace namespace="imu"/>

<arg name="launch_driver" default="true" />
<arg name="interface" default="canIMU"/>
<arg name="interface" default="fintekcan3"/>
<arg name="receiver_interval_sec" default="0.01"/>
<arg name ="vehicle_id" default="$(env VEHICLE_ID default)" />

Expand Down
25 changes: 15 additions & 10 deletions aip_x1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>

<arg name="launch_driver" default="true" />
<arg name="host_ip" default="127.0.0.1"/>
<arg name="host_ip" default="192.168.1.100"/>
<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 @@ -14,25 +14,30 @@

<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"/>
<arg name="scan_phase" value="180.0" />
<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.201" />
<arg name="data_port" value="2368" />
<arg name="gnss_port" value="10121" />
<arg name="scan_phase" value="0.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.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">
<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="sensor_ip" value="192.168.1.202" />
<arg name="data_port" value="2369" />
<arg name="gnss_port" value="10121" />
<arg name="scan_phase" value="0.0" />
<arg name="cloud_min_angle" value="0"/>
Expand Down
6 changes: 3 additions & 3 deletions common_sensor_launch/launch/hesai_XT32.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<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"/>
<arg name="ptp_profile" value="1588v2"/>
<arg name="ptp_switch_type" value="TSN"/>
<arg name="ptp_transport_type" value="UDP"/>
<arg name="ptp_profile" value="automotive"/>
<arg name="ptp_switch_type" value="NON_TSN"/>
<arg name="ptp_transport_type" value="L2"/>
<arg name="setup_sensor" value="true"/>
<arg name="retry_hw" value="true"/>
<arg name="container_name" value="$(var container_name)"/>
Expand Down

0 comments on commit cadb756

Please sign in to comment.