Skip to content

Commit

Permalink
add new folders
Browse files Browse the repository at this point in the history
Signed-off-by: Yuxuan Liu <[email protected]>
  • Loading branch information
HinsRyu committed Jun 17, 2024
1 parent 0680405 commit 53e0b0f
Show file tree
Hide file tree
Showing 17 changed files with 892 additions and 287 deletions.
16 changes: 16 additions & 0 deletions aip_xx1_gen2_launch/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 3.5)
project(aip_xx1_gen2_launch)

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package(INSTALL_TO_SHARE
launch
data
config
)
109 changes: 109 additions & 0 deletions aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/**:
ros__parameters:
sensing:
type: diagnostic_aggregator/AnalyzerGroup
path: sensing
analyzers:
node_alive_monitoring:
type: diagnostic_aggregator/AnalyzerGroup
path: node_alive_monitoring
analyzers:
topic_status:
type: diagnostic_aggregator/GenericAnalyzer
path: topic_status
contains: [": sensing_topic_status"]
timeout: 1.0

lidar:
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

gnss:
type: diagnostic_aggregator/AnalyzerGroup
path: gnss
analyzers:
health_monitoring:
type: diagnostic_aggregator/AnalyzerGroup
path: health_monitoring
analyzers:
connection:
type: diagnostic_aggregator/GenericAnalyzer
path: connection
contains: [": gnss_connection"]
timeout: 3.0

data:
type: diagnostic_aggregator/GenericAnalyzer
path: data
contains: [": gnss_data"]
timeout: 3.0

antenna:
type: diagnostic_aggregator/GenericAnalyzer
path: antenna
contains: [": gnss_antenna"]
timeout: 3.0

tx_usage:
type: diagnostic_aggregator/GenericAnalyzer
path: tx_usage
contains: [": gnss_tx_usage"]
timeout: 3.0

spoofing:
type: diagnostic_aggregator/GenericAnalyzer
path: spoofing
contains: [": gnss_spoofing"]
timeout: 3.0

jamming:
type: diagnostic_aggregator/GenericAnalyzer
path: jamming
contains: [": gnss_jamming"]
timeout: 3.0

fix_topic_status:
type: diagnostic_aggregator/GenericAnalyzer
path: fix_topic_status
contains: [": fix topic status"]
timeout: 3.0

imu:
type: diagnostic_aggregator/AnalyzerGroup
path: imu
analyzers:
bias_monitoring:
type: diagnostic_aggregator/AnalyzerGroup
path: bias_monitoring
analyzers:
gyro_bias_validator:
type: diagnostic_aggregator/GenericAnalyzer
path: gyro_bias_validator
contains: [": gyro_bias_validator"]
timeout: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
# Description:
# name: diag name
# is_active: Force update or not
# status: diag status set by dummy diag publisher "OK, Warn, Error, Stale"
#
# Note:
#
# default values are:
# is_active: "true"
# status: "OK"
---
/**:
ros__parameters:
required_diags:
# gnss
gnss_connection: default
gnss_data: default
gnss_antenna: default
gnss_tx_usage: default
gnss_spoofing: default
gnss_jamming: default
fix topic status: default

# velodyne
velodyne_connection: default
velodyne_temperature: default
velodyne_rpm: default

# imu
gyro_bias_estimator: default
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
update_rate_hz: 20.0
new_frame_id: "base_link"
timeout_threshold: 1.0
input_topics: ["/sensing/radar/front_center/detected_objects", "/sensing/radar/front_left/detected_objects", "/sensing/radar/rear_left/detected_objects", "/sensing/radar/rear_center/detected_objects", "/sensing/radar/rear_right/detected_objects", "/sensing/radar/front_right/detected_objects"]
20 changes: 20 additions & 0 deletions aip_xx1_gen2_launch/data/traffic_light_camera.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
image_width: 1920
image_height: 1080
camera_name: traffic_light/camera
camera_matrix:
rows: 3
cols: 3
data: [2410.755261, 0.000000, 922.621401, 0.000000, 2403.573140, 534.752500, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
projection_matrix:
rows: 3
cols: 4
data: [2370.254883, 0.000000, 920.136018, 0.000000, 0.000000, 2388.885254, 535.599668, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
19 changes: 19 additions & 0 deletions aip_xx1_gen2_launch/launch/camera.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<launch>

<arg name="launch_driver" default="true" />
<arg name="camera_type" default="left" />

<group>
<push-ros-namespace namespace="camera"/>
<group>
<push-ros-namespace namespace="traffic_light"/>

<!-- (usb_cam_node is assumed to have launched on logging PC) -->
<node pkg="topic_tools" exec="relay" name="tl_camera_info_relay" output="log"
args="$(var camera_type)/camera_info camera_info"/>

<node pkg="topic_tools" exec="relay" name="tl_compressed_image_relay" output="log"
args="$(var camera_type)/image_raw/compressed image_raw/compressed"/>
</group>
</group>
</launch>
41 changes: 41 additions & 0 deletions aip_xx1_gen2_launch/launch/gnss.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<launch>

<arg name="launch_driver" default="true" />
<arg name="gnss_receiver" default="ublox" description="ublox(default) or septentrio"/>

<group>
<push-ros-namespace namespace="gnss"/>

<!-- Switch topic name -->
<let name="navsatfix_topic_name" value="ublox/nav_sat_fix" if="$(eval &quot;'$(var gnss_receiver)'=='ublox'&quot;)" />
<let name="navpvt_topic_name" value="ublox/navpvt" if="$(eval &quot;'$(var gnss_receiver)'=='ublox'&quot;)" />
<let name="navsatfix_topic_name" value="septentrio/nav_sat_fix" if="$(eval &quot;'$(var gnss_receiver)'=='septentrio'&quot;)"/>
<let name="navpvt_topic_name" value="septentrio/navpvt/unused" if="$(eval &quot;'$(var gnss_receiver)'=='septentrio'&quot;)"/>

<!-- Ublox Driver -->
<group if="$(eval &quot;'$(var gnss_receiver)'=='ublox'&quot;)">
<node pkg="ublox_gps" name="ublox" exec="ublox_gps_node" if="$(var launch_driver)" respawn="true" respawn_delay="10.0">
<remap from="~/fix" to="~/nav_sat_fix" />
<param from="$(find-pkg-share ublox_gps)/config/c94_f9p_rover.yaml"/>
</node>
</group>

<!-- Septentrio GNSS Driver -->
<group if="$(eval &quot;'$(var launch_driver)' and '$(var gnss_receiver)'=='septentrio'&quot;)">
<include file="$(find-pkg-share septentrio_gnss_driver)/launch/mosaic_x5_rover.launch.xml" />
</group>

<!-- NavSatFix to MGRS Pose -->
<include file="$(find-pkg-share gnss_poser)/launch/gnss_poser.launch.xml">
<arg name="input_topic_fix" value="$(var navsatfix_topic_name)" />
<arg name="input_topic_navpvt" value="$(var navpvt_topic_name)" />

<arg name="output_topic_gnss_pose" value="pose" />
<arg name="output_topic_gnss_pose_cov" value="pose_with_covariance" />
<arg name="output_topic_gnss_fixed" value="fixed" />

<arg name="use_ublox_receiver" value="true" />
</include>

</group>
</launch>
39 changes: 39 additions & 0 deletions aip_xx1_gen2_launch/launch/imu.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<launch>

<group>
<push-ros-namespace namespace="imu"/>

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

<group>
<push-ros-namespace namespace="tamagawa"/>
<include file="$(find-pkg-share ros2_socketcan)/launch/socket_can_receiver.launch.py">
<arg name="interface" value="$(var interface)"/>
<arg name="interval_sec" value="$(var receiver_interval_sec)"/>
</include>
<node pkg="tamagawa_imu_driver" name="tag_can_driver" exec="tag_can_driver" if="$(var launch_driver)">
<remap from="/can/imu" to="from_can_bus"/>
<remap from="imu/data_raw" to="imu_raw"/>
<param name="imu_frame_id" value="tamagawa/imu_link"/>
</node>
</group>

<arg name="imu_raw_name" default="tamagawa/imu_raw"/>
<arg name="imu_corrector_param_file" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_xx1/imu_corrector.param.yaml"/>
<include file="$(find-pkg-share imu_corrector)/launch/imu_corrector.launch.xml">
<arg name="input_topic" value="$(var imu_raw_name)"/>
<arg name="output_topic" value="imu_data"/>
<arg name="param_file" value="$(var imu_corrector_param_file)"/>
</include>

<include file="$(find-pkg-share imu_corrector)/launch/gyro_bias_estimator.launch.xml">
<arg name="input_imu_raw" value="$(var imu_raw_name)"/>
<arg name="input_odom" value="/localization/kinematic_state"/>
<arg name="imu_corrector_param_file" value="$(var imu_corrector_param_file)"/>
</include>
</group>

</launch>
106 changes: 106 additions & 0 deletions aip_xx1_gen2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
<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="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<group>
<push-ros-namespace namespace="lidar"/>

<group>
<push-ros-namespace namespace="top"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_OT128.launch.xml">
<arg name="max_range" value="300.0"/>
<arg name="sensor_frame" value="hesai_top"/>
<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="160.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>

<group>
<push-ros-namespace namespace="front_left"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="max_range" value="300.0"/>
<arg name="sensor_frame" value="hesai_front_left"/>
<arg name="sensor_ip" value="192.168.1.21"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2369"/>
<arg name="scan_phase" value="50.0"/>
<arg name="cloud_min_angle" value="50"/>
<arg name="cloud_max_angle" value="320"/>
<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_right"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="max_range" value="300.0"/>
<arg name="sensor_frame" value="hesai_front_right"/>
<arg name="sensor_ip" value="192.168.1.22"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2370"/>
<arg name="scan_phase" value="310.0"/>
<arg name="cloud_min_angle" value="40"/>
<arg name="cloud_max_angle" value="310"/>
<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="side_left"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="max_range" value="10.0"/>
<arg name="sensor_frame" value="hesai_side_left"/>
<arg name="sensor_ip" value="192.168.1.23"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2371"/>
<arg name="scan_phase" value="90.0"/>
<arg name="cloud_min_angle" value="90"/>
<arg name="cloud_max_angle" value="270"/>
<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="side_right"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="max_range" value="10.0"/>
<arg name="sensor_frame" value="hesai_side_right"/>
<arg name="sensor_ip" value="192.168.1.24"/>
<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="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_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="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
</launch>
Loading

0 comments on commit 53e0b0f

Please sign in to comment.