Skip to content

Commit

Permalink
ci(pre-commit): update pre-commit-hooks-ros (autowarefoundation#625)
Browse files Browse the repository at this point in the history
* ci(pre-commit): update pre-commit-hooks-ros

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
  • Loading branch information
TomohitoAndo and pre-commit-ci[bot] committed May 16, 2022
1 parent 62b3aea commit e8d8120
Show file tree
Hide file tree
Showing 4 changed files with 114 additions and 2 deletions.
8 changes: 7 additions & 1 deletion launch/tier4_planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@

<arg name="vehicle_info_param_file" />

<!-- pointcloud container -->
<arg name="use_pointcloud_container" default="true" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<group>
<push-ros-namespace namespace="planning"/>
<!-- mission planning module -->
Expand All @@ -16,7 +20,9 @@
<group>
<push-ros-namespace namespace="scenario_planning"/>
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/scenario_planning.launch.xml">
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)" />
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@
<arg name="common_param_path"/>
<arg name="vehicle_info_param_file" />

<!-- pointcloud container -->
<arg name="use_pointcloud_container" default="true" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<!-- lane_driving scenario -->
<group>
<push-ros-namespace namespace="lane_driving"/>
Expand All @@ -13,6 +17,13 @@
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)" />
<arg name="use_multithread" value="true" />
</include>

<!-- compare map module -->
<include file="$(find-pkg-share planning_launch)/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py">
<arg name="use_multithread" value="true" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<!-- motion planning module -->
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
# Copyright 2021 Tier IV, Inc. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
def add_launch_arg(name: str, default_value=None):
return DeclareLaunchArgument(name, default_value=default_value)

set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
condition=UnlessCondition(LaunchConfiguration("use_multithread")),
)

set_container_mt_executable = SetLaunchConfiguration(
"container_executable",
"component_container_mt",
condition=IfCondition(LaunchConfiguration("use_multithread")),
)

composable_nodes = [
ComposableNode(
package="compare_map_segmentation",
plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent",
name="voxel_based_compare_map_filter_node",
remappings=[
("input", "/perception/obstacle_segmentation/pointcloud"),
("map", "/map/pointcloud_map"),
("output", "compare_map_filtered/pointcloud"),
],
parameters=[
{
"distance_threshold": 0.7,
}
],
extra_arguments=[
{"use_intra_process_comms": False} # this node has QoS of transient local
],
),
]

compare_map_container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=composable_nodes,
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)

load_composable_nodes = LoadComposableNodes(
composable_node_descriptions=composable_nodes,
target_container=LaunchConfiguration("container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)

return LaunchDescription(
[
add_launch_arg("use_multithread", "true"),
add_launch_arg("use_pointcloud_container", "true"),
add_launch_arg("container_name", "compare_map_container"),
set_container_executable,
set_container_mt_executable,
compare_map_container,
load_composable_nodes,
]
)
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@
<arg name="common_param_path" default="$(find-pkg-share tier4_planning_launch)/config/scenario_planning/common/common.param.yaml"/>
<arg name="vehicle_info_param_file" />

<!-- pointcloud container -->
<arg name="use_pointcloud_container" default="true" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<!-- scenario selector -->
<include file="$(find-pkg-share scenario_selector)/launch/scenario_selector.launch.xml">
<arg name="input_lane_driving_trajectory" value="/planning/scenario_planning/lane_driving/trajectory"/>
Expand Down Expand Up @@ -40,7 +44,9 @@
<!-- lane driving -->
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/lane_driving.launch.xml">
<arg name="common_param_path" value="$(var common_param_path)"/>
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)" />
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
<!-- parking -->
<include file="$(find-pkg-share tier4_planning_launch)/launch/scenario_planning/parking.launch.py">
Expand Down

0 comments on commit e8d8120

Please sign in to comment.