Skip to content

Commit

Permalink
finish pythonic transformation for launch system
Browse files Browse the repository at this point in the history
Signed-off-by: Yuxuan Liu <[email protected]>
  • Loading branch information
HinsRyu committed Jun 12, 2024
1 parent b20cfcd commit e304ed2
Show file tree
Hide file tree
Showing 4 changed files with 81 additions and 65 deletions.
24 changes: 12 additions & 12 deletions aip_xx1_launch/config/lidar_gen2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ launches:
parameters:
max_range: 300.0
sensor_frame: hesai_top
sensor_ip: "192.168.1.201"
sensor_ip: 192.168.1.201
data_port: 2368
scan_phase: 160
vertical_bins: 128
Expand All @@ -13,7 +13,7 @@ launches:
parameters:
max_range: 300.0
sensor_frame: hesai_front_left
sensor_ip: "192.168.1.21"
sensor_ip: 192.168.1.21
data_port: 2369
scan_phase: 50.0
cloud_min_angle: 50
Expand All @@ -25,7 +25,7 @@ launches:
parameters:
max_range: 300.0
sensor_frame: hesai_front_right
sensor_ip: "192.168.1.22"
sensor_ip: 192.168.1.22
data_port: 2370
scan_phase: 310.0
cloud_min_angle: 40
Expand All @@ -35,7 +35,7 @@ launches:
parameters:
max_range: 10.0
sensor_frame: hesai_side_left
sensor_ip: "192.168.1.23"
sensor_ip: 192.168.1.23
data_port: 2371
scan_phase: 90.0
cloud_min_angle: 90
Expand All @@ -45,25 +45,25 @@ launches:
parameters:
max_range: 10.0
sensor_frame: hesai_side_right
sensor_ip: "192.168.1.24"
sensor_ip: 192.168.1.24
data_port: 2372
scan_phase: 270.0
cloud_min_angle: 90
cloud_max_angle: 270

preprocessor:
input_topics:
- "/sensing/lidar/top/pointcloud_before_sync"
- "/sensing/lidar/side_left/pointcloud_before_sync"
- "/sensing/lidar/side_right/pointcloud_before_sync"
- "/sensing/lidar/front_left/pointcloud_before_sync"
- "/sensing/lidar/front_right/pointcloud_before_sync"
- /sensing/lidar/top/pointcloud_before_sync
- /sensing/lidar/side_left/pointcloud_before_sync
- /sensing/lidar/side_right/pointcloud_before_sync
- /sensing/lidar/front_left/pointcloud_before_sync
- /sensing/lidar/front_right/pointcloud_before_sync
input_offset:
- 0.035
- 0.025
- 0.025
- 0.025
- 0.025
timeout_sec: 0.095
input_twist_topic_type: "twist"
publish_synchronized_pointcloud: true
input_twist_topic_type: twist
publish_synchronized_pointcloud: true
20 changes: 10 additions & 10 deletions aip_xx1_launch/config/lidar_launch.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ launches:
parameters:
max_range: 250.0
sensor_frame: velodyne_top
sensor_ip: "192.168.1.201"
sensor_ip: 192.168.1.201
data_port: 2368
scan_phase: 300.0
vertical_bins: 128
Expand All @@ -16,7 +16,7 @@ launches:
parameters:
max_range: 5.0
sensor_frame: velodyne_left
sensor_ip: "192.168.1.202"
sensor_ip: 192.168.1.202
data_port: 2369
scan_phase: 180.0
cloud_min_angle: 300
Expand All @@ -30,7 +30,7 @@ launches:
parameters:
max_range: 5.0
sensor_frame: velodyne_right
sensor_ip: "192.168.1.203"
sensor_ip: 192.168.1.203
data_port: 2370
scan_phase: 180.0
cloud_min_angle: 300
Expand All @@ -44,7 +44,7 @@ launches:
parameters:
max_range: 1.5
sensor_frame: velodyne_rear
sensor_ip: "192.168.1.204"
sensor_ip: 192.168.1.204
data_port: 2371
scan_phase: 180.0
cloud_min_angle: 300
Expand All @@ -56,15 +56,15 @@ launches:

preprocessor:
input_topics:
- "/sensing/lidar/top/pointcloud"
- "/sensing/lidar/left/pointcloud"
- "/sensing/lidar/right/pointcloud"
- "/sensing/lidar/rear/ointcloud"
- /sensing/lidar/top/pointcloud
- /sensing/lidar/left/pointcloud
- /sensing/lidar/right/pointcloud
- /sensing/lidar/rear/pointcloud
input_offset:
- 0.035
- 0.025
- 0.025
- 0.025
timeout_sec: 0.095
input_twist_topic_type: "twist"
publish_synchronized_pointcloud: false
input_twist_topic_type: twist
publish_synchronized_pointcloud: false
Original file line number Diff line number Diff line change
Expand Up @@ -13,19 +13,34 @@
# limitations under the License.


from launch import LaunchDescription
from copy import deepcopy
from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
from launch.actions import OpaqueFunction
from launch.substitutions import LaunchConfiguration, EnvironmentVariable
from launch_ros.actions import PushRosNamespace
import os
from typing import Any
from typing import List

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import IncludeLaunchDescription
from launch.actions import OpaqueFunction
from launch.launch_description_sources import AnyLaunchDescriptionSource
from launch.launch_description_sources import PythonLaunchDescriptionSource
import os
from launch.substitutions import EnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import PushRosNamespace
import yaml


def join_list_of_arguments(arguments: List[Any]) -> str:
"""Join a list of arguments into a string, used by Include Launch Description.
Example:
join_list_of_arguments([1,2,3]) -> "[1, 2, 3]"
"""
return f"[{', '.join([str(arg) for arg in arguments])}]"


def generate_launch_dictionary():
path_dictionary = {
"hesai_OT128": AnyLaunchDescriptionSource(
Expand Down Expand Up @@ -77,7 +92,7 @@ def load_yaml(yaml_file_path):
path_dictionary = generate_launch_dictionary()

base_parameters = {}
base_parameters["host_ip"] = LaunchConfiguration("host_ip").perform(context)
base_parameters["host_ip"] = LaunchConfiguration("host_ip")
base_parameters["vehicle_mirror_param_file"] = LaunchConfiguration(
"vehicle_mirror_param_file"
).perform(context)
Expand All @@ -86,15 +101,15 @@ def load_yaml(yaml_file_path):
base_parameters["pointcloud_container_name"] = LaunchConfiguration(
"pointcloud_container_name"
).perform(context)
base_parameters["enable_blockage_diag"] = LaunchConfiguration(
"enable_blockage_diag"
).perform(context)
base_parameters["enable_blockage_diag"] = LaunchConfiguration("enable_blockage_diag").perform(
context
)

sub_launch_actions = []
for launch in config["launches"]:
launch_parameters = deepcopy(base_parameters)
launch_parameters.update(launch["parameters"]) # dict
launch_parameter_list_tuple = [(str(k),str(v)) for k,v in launch_parameters.items()]
launch_parameters.update(launch["parameters"]) # dict
launch_parameter_list_tuple = [(str(k), str(v)) for k, v in launch_parameters.items()]
sub_launch_action = GroupAction(
[
PushRosNamespace(launch["namespace"]),
Expand All @@ -106,6 +121,7 @@ def load_yaml(yaml_file_path):
)
sub_launch_actions.append(sub_launch_action)

processor_dict = config["preprocessor"]
sub_launch_actions.append(
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -119,13 +135,17 @@ def load_yaml(yaml_file_path):
("base_frame", "base_link"),
("use_multithread", "true"),
("use_intra_process", "true"),
("use_pointcloud_container", LaunchConfiguration(
"use_pointcloud_container"
)),
("pointcloud_container_name", LaunchConfiguration(
"pointcloud_container_name"
))
]
("use_pointcloud_container", LaunchConfiguration("use_pointcloud_container")),
("pointcloud_container_name", LaunchConfiguration("pointcloud_container_name")),
("input_topics", join_list_of_arguments(processor_dict["input_topics"])),
("input_offset", join_list_of_arguments(processor_dict["input_offset"])),
("timeout_sec", str(processor_dict["timeout_sec"])),
("input_twist_topic_type", str(processor_dict["input_twist_topic_type"])),
(
"publish_synchronized_pointcloud",
str(processor_dict["publish_synchronized_pointcloud"]),
),
],
)
)
return [
Expand All @@ -146,9 +166,7 @@ def generate_launch_description():
launch_arguments.append(config_file_arg)

def add_launch_arg(name: str, default_value=None, **kwargs):
launch_arguments.append(
DeclareLaunchArgument(name, default_value=default_value, **kwargs)
)
launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value, **kwargs))

add_launch_arg("launch_driver", "true")
add_launch_arg("host_ip", "192.168.1.10")
Expand All @@ -158,9 +176,7 @@ def add_launch_arg(name: str, default_value=None, **kwargs):
default_value=EnvironmentVariable("VEHICLE_ID", default_value="default"),
)
add_launch_arg("vehicle_mirror_param_file")
add_launch_arg(
"use_pointcloud_container", "false", description="launch pointcloud container"
)
add_launch_arg("use_pointcloud_container", "false", description="launch pointcloud container")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("enable_blockage_diag", "false")

Expand Down
36 changes: 18 additions & 18 deletions aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch.launch_description_sources import AnyLaunchDescriptionSource


def launch_setup(context, *args, **kwargs):
# set concat filter as a component
Expand All @@ -37,24 +37,16 @@ def launch_setup(context, *args, **kwargs):
],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/pointcloud_before_sync",
"/sensing/lidar/side_left/pointcloud_before_sync",
"/sensing/lidar/side_right/pointcloud_before_sync",
"/sensing/lidar/front_left/pointcloud_before_sync",
"/sensing/lidar/front_right/pointcloud_before_sync",
],
"input_topics": LaunchConfiguration("input_topics"),
"output_frame": LaunchConfiguration("base_frame"),
"input_offset": [
0.035,
0.025,
0.025,
0.025,
0.025,
], # each sensor will wait 60, 70, 70, 70ms
"timeout_sec": 0.095, # set shorter than 100ms
"input_twist_topic_type": "twist",
"publish_synchronized_pointcloud": True,
"input_offset": LaunchConfiguration(
"input_offset"
), # each sensor will wait 60, 70, 70, 70ms
"timeout_sec": LaunchConfiguration("timeout_sec"), # set shorter than 100ms
"input_twist_topic_type": LaunchConfiguration("input_twist_topic_type"),
"publish_synchronized_pointcloud": LaunchConfiguration(
"publish_synchronized_pointcloud"
),
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand Down Expand Up @@ -98,6 +90,14 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")
add_launch_arg(
"input_topics",
"[/sensing/lidar/top/pointcloud, /sensing/lidar/left/pointcloud, /sensing/lidar/right/pointcloud, /sensing/lidar/rear/pointcloud]",
)
add_launch_arg("input_offset", "[0.035, 0.025, 0.025, 0.025]")
add_launch_arg("timeout_sec", "0.095")
add_launch_arg("input_twist_topic_type", "twist")
add_launch_arg("publish_synchronized_pointcloud", "False")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down

0 comments on commit e304ed2

Please sign in to comment.