Skip to content
This repository has been archived by the owner on Mar 27, 2023. It is now read-only.

Commit

Permalink
Add planning container (#72)
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>
  • Loading branch information
Taichi Higashide and wep21 committed Apr 27, 2021
1 parent 22ce612 commit 4ac6374
Show file tree
Hide file tree
Showing 12 changed files with 689 additions and 26 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/**:
ros__parameters:
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
backward_path_length: 5.0
forward_path_length: 200.0
max_accel: -5.0
lane_change_prepare_duration: 4.0
lane_changing_duration: 8.0
backward_length_buffer_for_end_of_lane: 5.0
lane_change_finish_judge_buffer: 3.0
minimum_lane_change_length: 12.0
minimum_lane_change_velocity: 5.6
prediction_duration: 8.0
prediction_time_resolution: 0.5
drivable_area_resolution: 0.1
drivable_area_width: 100.0
drivable_area_height: 50.0
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
refine_goal_search_radius_range: 7.5
68 changes: 68 additions & 0 deletions planning_launch/launch/mission_planning/mission_planning.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
# 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.
import launch
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
container = ComposableNodeContainer(
name='mission_planning_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='mission_planner',
plugin='mission_planner::MissionPlannerLanelet2',
name='mission_planner',
remappings=[
('input/vector_map', '/map/vector_map'),
('input/goal_pose', '/planning/mission_planning/goal'),
('input/checkpoint', '/planning/mission_planning/checkpoint'),
('output/route', '/planning/mission_planning/route'),
('visualization_topic_name',
'/planning/mission_planning/route_marker'),
],
parameters=[
{
'map_frame': 'map',
'base_link_frame': 'base_link',
}
],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
),
ComposableNode(
package='mission_planner',
plugin='mission_planner::GoalPoseVisualizer',
name='goal_pose_visualizer',
remappings=[
('input/route', '/planning/mission_planning/route'),
('output/goal_pose',
'/planning/mission_planning/echo_back_goal_pose'),
],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)
],
)
return launch.LaunchDescription([
DeclareLaunchArgument("use_intra_process", default_value='false'),
container
])
2 changes: 1 addition & 1 deletion planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<!-- mission planning module -->
<group>
<push-ros-namespace namespace="mission_planning"/>
<include file="$(find-pkg-share planning_launch)/launch/mission_planning/mission_planning.launch.xml">
<include file="$(find-pkg-share planning_launch)/launch/mission_planning/mission_planning.launch.py">
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@
<!-- behavior planning module -->
<group>
<push-ros-namespace namespace="behavior_planning"/>
<include file="$(find-pkg-share planning_launch)/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml">
<include file="$(find-pkg-share planning_launch)/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py">
</include>
</group>

<!-- motion planning module -->
<group>
<push-ros-namespace namespace="motion_planning"/>
<include file="$(find-pkg-share planning_launch)/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml">
<include file="$(find-pkg-share planning_launch)/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py">
</include>
</group>
</group>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,242 @@
# 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 ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration, ExecuteProcess
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode

import os
import yaml


def generate_launch_description():
# lane change planner
lane_change_planner_param_path = os.path.join(
get_package_share_directory('planning_launch'),
'config',
'scenario_planning',
'lane_driving',
'behavior_planning',
'lane_change_planner',
'lane_change_planner.param.yaml',
)
with open(lane_change_planner_param_path, 'r') as f:
lane_change_planner_param = yaml.safe_load(f)['/**']['ros__parameters']

lane_change_planner_component = ComposableNode(
package='lane_change_planner',
plugin='lane_change_planner::LaneChanger',
name='lane_change_planner',
namespace='',
remappings=[
('~/input/route', LaunchConfiguration('input_route_topic_name')),
('~/input/vector_map', LaunchConfiguration('map_topic_name')),
('~/input/perception', '/perception/object_recognition/objects'),
('~/input/velocity', '/localization/twist'),
('~/input/lane_change_approval',
'/planning/scenario_planning/lane_driving/lane_change_approval'),
('~/input/force_lane_change',
'/planning/scenario_planning/lane_driving/force_lane_change'),
('~/output/lane_change_path', 'path_with_lane_id'),
('~/output/lane_change_ready',
'/planning/scenario_planning/lane_driving/lane_change_ready'),
('~/output/lane_change_avialable',
'/planning/scenario_planning/lane_driving/lane_change_available'),
('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'),
('~/debug/lane_change_candidate_path',
'/planning/scenario_planning/lane_driving/lane_change_candidate_path'),
],
parameters=[
lane_change_planner_param,
{
"enable_abort_lane_change": False,
"enable_collision_check_at_prepare_phase": False,
"use_predicted_path_outside_lanelet": False,
"use_all_predicted_path": False,
"enable_blocked_by_obstacle": False,
}
],
extra_arguments=[
{'use_intra_process_comms': LaunchConfiguration('use_intra_process')}
],
)

# turn signal decider
turn_signal_decider_component = ComposableNode(
package='turn_signal_decider',
plugin='turn_signal_decider::TurnSignalDecider',
name='turn_signal_decider',
namespace='',
remappings=[
('input/path_with_lane_id', 'path_with_lane_id'),
('input/vector_map', LaunchConfiguration('map_topic_name')),
('output/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'),
],
parameters=[
{'lane_change_search_distance': 30.0},
{'intersection_search_distance': 15.0},
],
extra_arguments=[
{'use_intra_process_comms': LaunchConfiguration('use_intra_process')}
],
)

# behavior velocity planner
blind_spot_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'blind_spot.param.yaml',
)
with open(blind_spot_param_path, 'r') as f:
blind_spot_param = yaml.safe_load(f)['/**']['ros__parameters']

crosswalk_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'crosswalk.param.yaml',
)
with open(crosswalk_param_path, 'r') as f:
crosswalk_param = yaml.safe_load(f)['/**']['ros__parameters']

detection_area_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'detection_area.param.yaml',
)
with open(detection_area_param_path, 'r') as f:
detection_area_param = yaml.safe_load(f)['/**']['ros__parameters']

intersection_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'intersection.param.yaml',
)
with open(intersection_param_path, 'r') as f:
intersection_param = yaml.safe_load(f)['/**']['ros__parameters']

stop_line_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'stop_line.param.yaml',
)
with open(stop_line_param_path, 'r') as f:
stop_line_param = yaml.safe_load(f)['/**']['ros__parameters']

traffic_light_param_path = os.path.join(
get_package_share_directory('behavior_velocity_planner'),
'config',
'traffic_light.param.yaml',
)
with open(traffic_light_param_path, 'r') as f:
traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters']

behavior_velocity_planner_component = ComposableNode(
package='behavior_velocity_planner',
plugin='BehaviorVelocityPlannerNode',
name='behavior_velocity_planner',
namespace='',
remappings=[
('~/input/path_with_lane_id', 'path_with_lane_id'),
('~/input/vector_map', '/map/vector_map'),
('~/input/vehicle_velocity', '/localization/twist'),
('~/input/dynamic_objects', '/perception/object_recognition/objects'),
('~/input/no_ground_pointcloud', '/sensing/lidar/no_ground/pointcloud'),
('~/input/traffic_light_states',
'/perception/traffic_light_recognition/traffic_light_states'),
('~/input/external_traffic_light_states',
'/foa/traffic_light_recognition/traffic_light_states'),
('~/output/path', 'path'),
('~/output/stop_reasons',
'/planning/scenario_planning/status/stop_reasons'),
('~/output/traffic_light_state', 'debug/traffic_light_state'),
],
parameters=[
{
'launch_stop_line': True,
'launch_crosswalk': True,
'launch_traffic_light': True,
'launch_intersection': True,
'launch_blind_spot': True,
'launch_detection_area': True,
'forward_path_length': 1000.0,
'backward_path_length': 5.0,
'max_accel': -2.8,
'delay_response_time': 1.3
},
blind_spot_param,
crosswalk_param,
detection_area_param,
intersection_param,
stop_line_param,
traffic_light_param
],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

container = ComposableNodeContainer(
name='behavior_planning_container',
namespace='',
package='rclcpp_components',
executable=LaunchConfiguration('container_executable'),
composable_node_descriptions=[
lane_change_planner_component,
turn_signal_decider_component,
behavior_velocity_planner_component,
],
output='screen',
)

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')),
)

return launch.LaunchDescription([
DeclareLaunchArgument(
'input_route_topic_name',
default_value='/planning/mission_planning/route'),
DeclareLaunchArgument(
'map_topic_name',
default_value='/map/vector_map'
),
DeclareLaunchArgument(
'use_intra_process',
default_value='false'
),
DeclareLaunchArgument(
'use_multithread',
default_value='false'
),
set_container_executable,
set_container_mt_executable,
container,
ExecuteProcess(
cmd=['ros2', 'topic', 'pub',
'/planning/scenario_planning/lane_driving/lane_change_approval',
'autoware_planning_msgs/msg/LaneChangeCommand', '{command: true}',
'-r', '10']),
])
Original file line number Diff line number Diff line change
Expand Up @@ -15,30 +15,11 @@
<remap from="~/output/lane_change_available" to="/planning/scenario_planning/lane_driving/lane_change_available" />
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons" />
<remap from="~/debug/lane_change_candidate_path" to="/planning/scenario_planning/lane_driving/lane_change_candidate_path" />
<param name="min_stop_distance" value="5.0" />
<param name="stop_time" value="2.0" />
<param name="hysteresis_buffer_distance" value="2.0" />
<param name="backward_path_length" value="5.0" />
<param name="forward_path_length" value="200.0" />
<param name="max_accel" value="-5.0" />
<param name="lane_change_prepare_duration" value="4.0" />
<param name="lane_changing_duration" value="8.0" />
<param name="backward_length_buffer_for_end_of_lane" value="5.0" />
<param name="lane_change_finish_judge_buffer" value="3.0" />
<param name="minimum_lane_change_length" value="12.0" />
<param name="minimum_lane_change_velocity" value="5.6" />
<param name="prediction_duration" value="8.0" />
<param name="prediction_time_resolution" value="0.5" />
<param name="drivable_area_resolution" value="0.1" />
<param name="drivable_area_width" value="100.0" />
<param name="drivable_area_height" value="50.0" />
<param name="static_obstacle_velocity_thresh" value="1.5" />
<param name="maximum_deceleration" value="1.0" />
<param from="$(find-pkg-share planning_launch)/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml" />
<param name="enable_abort_lane_change" value="false" />
<param name="enable_collision_check_at_prepare_phase" value="false" />
<param name="use_predicted_path_outside_lanelet" value="false" />
<param name="use_all_predicted_path" value="false" />
<param name="refine_goal_search_radius_range" value="7.5" />
<param name="enable_blocked_by_obstacle" value="false" />
</node>

Expand Down
Loading

0 comments on commit 4ac6374

Please sign in to comment.