Skip to content

Commit

Permalink
fix(behavior_path_planner): remove unnecessary publisher and subscrib…
Browse files Browse the repository at this point in the history
…er (#1371)

* fix(behavior_path_planner): remove unnecessary publisher and subscriber

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

* fix(tier4_planning_launch): fix launch file

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

* fix(tier4_planning_launch): fix xml file

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 authored and 1222-takeshi committed Oct 14, 2022
1 parent c3e47c7 commit 87c2bb0
Show file tree
Hide file tree
Showing 4 changed files with 0 additions and 71 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import ExecuteProcess
from launch.actions import GroupAction
from launch.actions import IncludeLaunchDescription
from launch.actions import OpaqueFunction
Expand Down Expand Up @@ -142,32 +141,7 @@ def launch_setup(context, *args, **kwargs):
("~/input/perception", "/perception/object_recognition/objects"),
("~/input/odometry", "/localization/kinematic_state"),
("~/input/scenario", "/planning/scenario_planning/scenario"),
(
"~/input/external_approval",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/path_change_approval",
),
(
"~/input/force_approval",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/path_change_force",
),
("~/output/path", "path_with_lane_id"),
(
"~/output/ready",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/ready_module",
),
(
"~/output/running",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/running_modules",
),
(
"~/output/force_available",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/force_available",
),
("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"),
("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"),
],
Expand Down Expand Up @@ -465,19 +439,6 @@ def launch_setup(context, *args, **kwargs):
[
container,
load_compare_map,
ExecuteProcess(
cmd=[
"ros2",
"topic",
"pub",
"/planning/scenario_planning/lane_driving/behavior_planning/"
"behavior_path_planner/path_change_approval",
"tier4_planning_msgs/msg/Approval",
"{approval: true}",
"-r",
"10",
]
),
]
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,12 @@
<arg name="map_topic_name" default="/map/vector_map"/>
<arg name="vehicle_info_param_file"/>

<executable
cmd="ros2 topic pub /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/path_change_approval
tier4_planning_msgs/msg/Approval 'approval: true' -r 10"
/>

<node pkg="behavior_path_planner" exec="behavior_path_planner" name="behavior_path_planner" output="screen">
<remap from="~/input/route" to="$(var input_route_topic_name)"/>
<remap from="~/input/vector_map" to="$(var map_topic_name)"/>
<remap from="~/input/perception" to="/perception/object_recognition/objects"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/external_approval" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/path_change_approval"/>
<remap from="~/input/force_approval" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/path_change_force"/>
<remap from="~/output/path" to="path_with_lane_id"/>
<remap from="~/output/ready" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/ready_module"/>
<remap from="~/output/running" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/running_modules"/>
<remap from="~/output/force_available" to="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/force_available"/>
<remap from="~/output/turn_indicators_cmd" to="/planning/turn_signal_cmd"/>
<remap from="~/output/hazard_lights_cmd" to="/planning/hazard_signal_cmd"/>
<param from="$(find-pkg-share tier4_planning_launch)/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,13 +76,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
rclcpp::Subscription<Scenario>::SharedPtr scenario_subscriber_;
rclcpp::Subscription<PredictedObjects>::SharedPtr perception_subscriber_;
rclcpp::Subscription<OccupancyGrid>::SharedPtr occupancy_grid_subscriber_;
rclcpp::Subscription<ApprovalMsg>::SharedPtr external_approval_subscriber_;
rclcpp::Subscription<PathChangeModule>::SharedPtr force_approval_subscriber_;
rclcpp::Publisher<PathWithLaneId>::SharedPtr path_publisher_;
rclcpp::Publisher<Path>::SharedPtr path_candidate_publisher_;
rclcpp::Publisher<PathChangeModuleArray>::SharedPtr force_available_publisher_;
rclcpp::Publisher<PathChangeModule>::SharedPtr plan_ready_publisher_;
rclcpp::Publisher<PathChangeModuleArray>::SharedPtr plan_running_publisher_;
rclcpp::Publisher<TurnIndicatorsCommand>::SharedPtr turn_signal_publisher_;
rclcpp::Publisher<HazardLightsCommand>::SharedPtr hazard_signal_publisher_;
rclcpp::TimerBase::SharedPtr timer_;
Expand All @@ -92,10 +87,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node
tier4_autoware_utils::SelfPoseListener self_pose_listener_{this};
Scenario::SharedPtr current_scenario_{nullptr};

std::string prev_ready_module_name_ = "NONE";
PathChangeModule ready_module_{};
PathChangeModuleArray running_modules_{};

TurnSignalDecider turn_signal_decider_;

std::mutex mutex_pd_; // mutex for planner_data_
Expand Down
13 changes: 0 additions & 13 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,12 +70,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
debug_avoidance_msg_array_publisher_ =
create_publisher<AvoidanceDebugMsgArray>("~/debug/avoidance_debug_message_array", 1);

// For remote operation
plan_ready_publisher_ = create_publisher<PathChangeModule>("~/output/ready", 1);
plan_running_publisher_ = create_publisher<PathChangeModuleArray>("~/output/running", 1);
force_available_publisher_ =
create_publisher<PathChangeModuleArray>("~/output/force_available", 1);

// Debug
debug_marker_publisher_ = create_publisher<MarkerArray>("~/debug/markers", 1);

Expand All @@ -102,13 +96,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
current_scenario_ = std::make_shared<Scenario>(*msg);
},
createSubscriptionOptions(this));
external_approval_subscriber_ = create_subscription<ApprovalMsg>(
"~/input/external_approval", 1,
std::bind(&BehaviorPathPlannerNode::onExternalApproval, this, _1),
createSubscriptionOptions(this));
force_approval_subscriber_ = create_subscription<PathChangeModule>(
"~/input/force_approval", 1, std::bind(&BehaviorPathPlannerNode::onForceApproval, this, _1),
createSubscriptionOptions(this));

// route_handler
auto qos_transient_local = rclcpp::QoS{1}.transient_local();
Expand Down

0 comments on commit 87c2bb0

Please sign in to comment.