Skip to content

Commit

Permalink
Merge branch 'main' into fix/add_new_parameters_for_distortion_corrector
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex authored Oct 3, 2024
2 parents aba267d + a5e7a2d commit e75b06b
Show file tree
Hide file tree
Showing 7 changed files with 124 additions and 18 deletions.
14 changes: 14 additions & 0 deletions common_sensor_launch/config/ring_outlier_filter_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
distance_ratio: 1.03
object_length_threshold: 0.1
num_points_threshold: 4
max_rings_num: 128
max_points_num_per_ring: 4000
publish_outlier_pointcloud: false
min_azimuth_deg: 0.0
max_azimuth_deg: 360.0
max_distance: 12.0
vertical_bins: 128
horizontal_bins: 36
noise_threshold: 2
46 changes: 32 additions & 14 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ def get_lidar_make(sensor_name):
return "Hesai", ".csv"
elif sensor_name[:3].lower() in ["hdl", "vlp", "vls"]:
return "Velodyne", ".yaml"
elif sensor_name.lower() in ["helios", "bpearl"]:
return "Robosense", None
return "unrecognized_sensor_model"


Expand Down Expand Up @@ -75,21 +77,28 @@ def create_parameter_dict(*args):
nebula_decoders_share_dir = get_package_share_directory("nebula_decoders")

# Calibration file
sensor_calib_fp = os.path.join(
nebula_decoders_share_dir,
"calibration",
sensor_make.lower(),
sensor_model + sensor_extension,
)
assert os.path.exists(
sensor_calib_fp
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)
if sensor_extension is not None: # Velodyne and Hesai
sensor_calib_fp = os.path.join(
nebula_decoders_share_dir,
"calibration",
sensor_make.lower(),
sensor_model + sensor_extension,
)
assert os.path.exists(
sensor_calib_fp
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)
else: # Robosense
sensor_calib_fp = ""

# Pointcloud preprocessor parameters
distortion_corrector_node_param = ParameterFile(
param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context),
allow_substs=True,
)
ring_outlier_filter_node_param = ParameterFile(
param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(context),
allow_substs=True,
)

nodes = []

Expand Down Expand Up @@ -129,6 +138,8 @@ def create_parameter_dict(*args):
# cSpell:ignore knzo25
# TODO(knzo25): fix the remapping once nebula gets updated
("velodyne_points", "pointcloud_raw_ex"),
# ("robosense_points", "pointcloud_raw_ex"), #for robosense
# ("pandar_points", "pointcloud_raw_ex"), # for hesai
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
Expand Down Expand Up @@ -199,11 +210,9 @@ def create_parameter_dict(*args):

# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
ring_outlier_filter_parameters = {"output_frame": LaunchConfiguration("frame_id")}
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
else:
ring_outlier_filter_parameters = {
"output_frame": ""
} # keep the output frame as the input frame
ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame
nodes.append(
ComposableNode(
package="autoware_pointcloud_preprocessor",
Expand All @@ -213,7 +222,7 @@ def create_parameter_dict(*args):
("input", "rectified/pointcloud_ex"),
("output", "pointcloud_before_sync"),
],
parameters=[ring_outlier_filter_parameters],
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)
Expand Down Expand Up @@ -312,6 +321,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
),
description="path to parameter file of distortion correction node",
)
add_launch_arg(
"ring_outlier_filter_node_param_path",
os.path.join(
common_sensor_share_dir,
"config",
"ring_outlier_filter_node.param.yaml",
),
description="path to parameter file of ring outlier filter node",
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
37 changes: 37 additions & 0 deletions common_sensor_launch/launch/robosense_Bpearl.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<launch>
<!-- Params -->
<arg name="launch_driver" default="true"/>
<arg name="model" default="Bpearl"/>
<arg name="max_range" default="30.0"/>
<arg name="min_range" default="0.4"/>
<arg name="sensor_frame" default="robosense"/>
<arg name="return_mode" default="SingleStrongest"/>
<arg name="sensor_ip" default="192.168.1.200"/>
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="gnss_port" default="7788"/>
<arg name="scan_phase" default="0.0"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="robosense_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="max_range" value="$(var max_range)"/>
<arg name="min_range" value="$(var min_range)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<arg name="sensor_ip" value="$(var sensor_ip)"/>
<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="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"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
</launch>
37 changes: 37 additions & 0 deletions common_sensor_launch/launch/robosense_Helios.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<launch>
<!-- Params -->
<arg name="launch_driver" default="true"/>
<arg name="model" default="Helios"/>
<arg name="max_range" default="150.0"/>
<arg name="min_range" default="0.2"/>
<arg name="sensor_frame" default="robosense"/>
<arg name="return_mode" default="SingleStrongest"/>
<arg name="sensor_ip" default="192.168.1.200"/>
<arg name="host_ip" default="255.255.255.255"/>
<arg name="data_port" default="2368"/>
<arg name="gnss_port" default="7788"/>
<arg name="scan_phase" default="0.0"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="robosense_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="max_range" value="$(var max_range)"/>
<arg name="min_range" value="$(var min_range)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
<arg name="sensor_ip" value="$(var sensor_ip)"/>
<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="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"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
</launch>
2 changes: 1 addition & 1 deletion sample_sensor_kit_launch/launch/gnss.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
</group>

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

Expand Down
4 changes: 2 additions & 2 deletions sample_sensor_kit_launch/launch/imu.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,13 @@

<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)/sample_sensor_kit/imu_corrector.param.yaml"/>
<include file="$(find-pkg-share imu_corrector)/launch/imu_corrector.launch.xml">
<include file="$(find-pkg-share autoware_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">
<include file="$(find-pkg-share autoware_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)"/>
Expand Down
2 changes: 1 addition & 1 deletion sample_sensor_kit_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<exec_depend>autoware_gnss_poser</exec_depend>
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
<exec_depend>common_sensor_launch</exec_depend>
<exec_depend>gnss_poser</exec_depend>
<exec_depend>tamagawa_imu_driver</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>ublox_gps</exec_depend>
Expand Down

0 comments on commit e75b06b

Please sign in to comment.