Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(mission_planner)!: introduce route_selector node #6363

Original file line number Diff line number Diff line change
@@ -1,19 +1,10 @@
<launch>
<arg name="modified_goal_topic_name" default="/planning/scenario_planning/modified_goal"/>
<arg name="map_topic_name" default="/map/vector_map"/>
<arg name="visualization_topic_name" default="/planning/mission_planning/route_marker"/>
<arg name="mission_planner_param_path" default="$(find-pkg-share mission_planner)/config/mission_planner.param.yaml"/>

<node_container pkg="rclcpp_components" exec="component_container" name="mission_planner_container" namespace="">
<composable_node pkg="mission_planner" plugin="mission_planner::MissionPlanner" name="mission_planner" namespace="">
<param from="$(var mission_planner_param_path)"/>
<remap from="input/modified_goal" to="$(var modified_goal_topic_name)"/>
<remap from="input/vector_map" to="$(var map_topic_name)"/>
<remap from="debug/route_marker" to="$(var visualization_topic_name)"/>
</composable_node>
<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/>
</node_container>

<group>
<include file="$(find-pkg-share mission_planner)/launch/mission_planner.launch.xml">
<arg name="mission_planner_param_path" value="$(var mission_planner_param_path)"/>
</include>
</group>
<group>
<include file="$(find-pkg-share mission_planner)/launch/goal_pose_visualizer.launch.xml"/>
</group>
Expand Down
17 changes: 12 additions & 5 deletions planning/mission_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,20 @@ rclcpp_components_register_node(goal_pose_visualizer_component
)

ament_auto_add_library(${PROJECT_NAME}_component SHARED
src/mission_planner/mission_planner.cpp
src/mission_planner/arrival_checker.cpp
src/mission_planner/service_utils.cpp
src/mission_planner/mission_planner.cpp
src/mission_planner/route_selector.cpp
)

rclcpp_components_register_node(${PROJECT_NAME}_component
PLUGIN "mission_planner::MissionPlanner"
EXECUTABLE ${PROJECT_NAME}
EXECUTABLE mission_planner
)

rclcpp_components_register_node(${PROJECT_NAME}_component
PLUGIN "mission_planner::RouteSelector"
EXECUTABLE route_selector
)

ament_auto_add_library(${PROJECT_NAME}_lanelet2_plugins SHARED
Expand All @@ -30,7 +37,7 @@ ament_auto_add_library(${PROJECT_NAME}_lanelet2_plugins SHARED
pluginlib_export_plugin_description_file(mission_planner plugins/plugin_description.xml)

ament_auto_package(
INSTALL_TO_SHARE
config
launch
INSTALL_TO_SHARE
config
launch
)

This file was deleted.

26 changes: 20 additions & 6 deletions planning/mission_planner/launch/mission_planner.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,24 @@
<arg name="visualization_topic_name" default="/planning/mission_planning/route_marker"/>
<arg name="mission_planner_param_path" default="$(find-pkg-share mission_planner)/config/mission_planner.param.yaml"/>

<node pkg="mission_planner" exec="mission_planner" name="mission_planner" output="screen">
<param from="$(var mission_planner_param_path)"/>
<remap from="input/modified_goal" to="$(var modified_goal_topic_name)"/>
<remap from="input/vector_map" to="$(var map_topic_name)"/>
<remap from="debug/route_marker" to="$(var visualization_topic_name)"/>
</node>
<node_container pkg="rclcpp_components" exec="component_container_mt" name="mission_planner_container" namespace="">
<composable_node pkg="mission_planner" plugin="mission_planner::MissionPlanner" name="mission_planner" namespace="">
<param from="$(var mission_planner_param_path)"/>
<remap from="~/input/modified_goal" to="$(var modified_goal_topic_name)"/>
<remap from="~/input/vector_map" to="$(var map_topic_name)"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/reroute_availability" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/is_reroute_available"/>
<remap from="~/route" to="route"/>
<remap from="~/state" to="state"/>
<remap from="~/debug/route_marker" to="$(var visualization_topic_name)"/>
</composable_node>
<composable_node pkg="mission_planner" plugin="mission_planner::RouteSelector" name="route_selector" namespace="">
<remap from="~/planner/clear_route" to="mission_planner/clear_route"/>
<remap from="~/planner/set_lanelet_route" to="mission_planner/set_lanelet_route"/>
<remap from="~/planner/set_waypoint_route" to="mission_planner/set_waypoint_route"/>
<remap from="~/planner/route" to="route"/>
<remap from="~/planner/state" to="state"/>
</composable_node>
<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/>
</node_container>
</launch>
5 changes: 1 addition & 4 deletions planning/mission_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,15 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>motion_utils</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>route_handler</depend>
<depend>std_srvs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node)

const auto durable_qos = rclcpp::QoS(1).transient_local();
pub_goal_footprint_marker_ =
node_->create_publisher<MarkerArray>("debug/goal_footprint", durable_qos);
node_->create_publisher<MarkerArray>("~/debug/goal_footprint", durable_qos);

vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo();
param_.goal_angle_threshold_deg = node_->declare_parameter<double>("goal_angle_threshold_deg");
Expand All @@ -164,7 +164,7 @@ void DefaultPlanner::initialize(rclcpp::Node * node)
{
initialize_common(node);
map_subscriber_ = node_->create_subscription<HADMapBin>(
"input/vector_map", rclcpp::QoS{10}.transient_local(),
"~/input/vector_map", rclcpp::QoS{10}.transient_local(),
std::bind(&DefaultPlanner::map_callback, this, std::placeholders::_1));
}

Expand Down
Loading
Loading