Skip to content

Commit

Permalink
feat: add robosense Bpearl and Helios Lidar launch files for users (#102
Browse files Browse the repository at this point in the history
)

Signed-off-by: ismetatabay <[email protected]>
  • Loading branch information
ismetatabay authored Sep 3, 2024
1 parent f8c256f commit fcc7cde
Show file tree
Hide file tree
Showing 3 changed files with 90 additions and 9 deletions.
25 changes: 16 additions & 9 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,15 +77,18 @@ 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(
Expand Down Expand Up @@ -129,6 +134,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
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>

0 comments on commit fcc7cde

Please sign in to comment.