Skip to content
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,18 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import OpaqueFunction
from launch.conditions import LaunchConfigurationEquals
from launch.conditions import LaunchConfigurationNotEquals
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml


Expand All @@ -33,11 +32,13 @@ def launch_setup(context, *args, **kwargs):
with open(vehicle_info_param_path, "r") as f:
vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"]

ground_segmentation_param_path = os.path.join(
get_package_share_directory("autoware_ground_segmentation"),
"config",
"ground_segmentation.param.yaml",
)
ground_segmentation_param_path = PathJoinSubstitution(
[
FindPackageShare("autoware_ground_segmentation"),
"config",
"ground_segmentation.param.yaml",
]
).perform(context)

with open(ground_segmentation_param_path, "r") as f:
ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"]
Expand Down Expand Up @@ -90,13 +91,11 @@ def generate_launch_description():
def add_launch_arg(name: str, default_value=None):
return DeclareLaunchArgument(name, default_value=default_value)

default_vehicle_info_param = os.path.join(
get_package_share_directory("autoware_vehicle_info_utils"), "config/vehicle_info.param.yaml"
)

vehicle_info_param = DeclareLaunchArgument(
"vehicle_info_param_file",
default_value=default_vehicle_info_param,
default_value=PathJoinSubstitution(
[FindPackageShare("autoware_vehicle_info_utils"), "config", "vehicle_info.param.yaml"]
),
description="Path to config file for vehicle information",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,18 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml


Expand Down Expand Up @@ -162,14 +163,24 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("output/stixel", "virtual_scan/stixel"),
add_launch_arg(
"param_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/laserscan_based_occupancy_grid_map.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"laserscan_based_occupancy_grid_map.param.yaml",
]
),
),
add_launch_arg("updater_type", "binary_bayes_filter"),
add_launch_arg(
"updater_param_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/updater.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"binary_bayes_filter_updater.param.yaml",
]
),
),
add_launch_arg("input_obstacle_pointcloud", "false"),
add_launch_arg("input_obstacle_and_raw_pointcloud", "true"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,18 @@
# limitations under the License.


from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml

# In this file, we use "ogm" as a meaning of occupancy grid map
Expand Down Expand Up @@ -275,14 +276,24 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("output", "occupancy_grid"),
add_launch_arg(
"multi_lidar_fusion_config_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml",
]
),
),
add_launch_arg("updater_type", "binary_bayes_filter"),
add_launch_arg(
"updater_param_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/binary_bayes_filter_updater.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"binary_bayes_filter_updater.param.yaml",
]
),
),
set_container_executable,
set_container_mt_executable,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,18 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml


Expand Down Expand Up @@ -173,14 +174,24 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("output", "occupancy_grid"),
add_launch_arg(
"param_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/pointcloud_based_occupancy_grid_map.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"pointcloud_based_occupancy_grid_map.param.yaml",
]
),
),
add_launch_arg("updater_type", "binary_bayes_filter"),
add_launch_arg(
"updater_param_file",
get_package_share_directory("autoware_probabilistic_occupancy_grid_map")
+ "/config/binary_bayes_filter_updater.param.yaml",
PathJoinSubstitution(
[
FindPackageShare("autoware_probabilistic_occupancy_grid_map"),
"config",
"binary_bayes_filter_updater.param.yaml",
]
),
),
set_container_executable,
set_container_mt_executable,
Expand Down
Loading