Skip to content

Commit 2212b00

Browse files
authoredJul 31, 2023
chore(intersection): publish decision status string (#4456)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 48870ea commit 2212b00

File tree

2 files changed

+33
-0
lines changed

2 files changed

+33
-0
lines changed
 

‎planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+31
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,8 @@ IntersectionModule::IntersectionModule(
8686
before_creep_state_machine_.setState(StateMachine::State::STOP);
8787
stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area);
8888
stuck_private_area_timeout_.setState(StateMachine::State::STOP);
89+
decision_state_pub_ =
90+
node_.create_publisher<std_msgs::msg::String>("~/debug/intersection/decision_state", 1);
8991
}
9092

9193
void IntersectionModule::initializeRTCStatus()
@@ -648,6 +650,35 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
648650
// calculate the
649651
const auto decision_result = modifyPathVelocityDetail(path, stop_reason);
650652

653+
std::string decision_type = "intersection" + std::to_string(module_id_) + " : ";
654+
if (std::get_if<IntersectionModule::Indecisive>(&decision_result)) {
655+
decision_type += "Indecisive";
656+
}
657+
if (std::get_if<IntersectionModule::StuckStop>(&decision_result)) {
658+
decision_type += "StuckStop";
659+
}
660+
if (std::get_if<IntersectionModule::NonOccludedCollisionStop>(&decision_result)) {
661+
decision_type += "NonOccludedCollisionStop";
662+
}
663+
if (std::get_if<IntersectionModule::FirstWaitBeforeOcclusion>(&decision_result)) {
664+
decision_type += "FirstWaitBeforeOcclusion";
665+
}
666+
if (std::get_if<IntersectionModule::PeekingTowardOcclusion>(&decision_result)) {
667+
decision_type += "PeekingTowardOcclusion";
668+
}
669+
if (std::get_if<IntersectionModule::OccludedCollisionStop>(&decision_result)) {
670+
decision_type += "OccludedCollisionStop";
671+
}
672+
if (std::get_if<IntersectionModule::Safe>(&decision_result)) {
673+
decision_type += "Safe";
674+
}
675+
if (std::get_if<IntersectionModule::TrafficLightArrowSolidOn>(&decision_result)) {
676+
decision_type += "TrafficLightArrowSolidOn";
677+
}
678+
std_msgs::msg::String decision_result_msg;
679+
decision_result_msg.data = decision_type;
680+
decision_state_pub_->publish(decision_result_msg);
681+
651682
prepareRTCStatus(decision_result, *path);
652683

653684
const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;

‎planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>
2626

2727
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
28+
#include <std_msgs/msg/string.hpp>
2829

2930
#include <lanelet2_core/LaneletMap.h>
3031
#include <lanelet2_routing/RoutingGraph.h>
@@ -272,6 +273,7 @@ class IntersectionModule : public SceneModuleInterface
272273
*/
273274

274275
util::DebugData debug_data_;
276+
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr decision_state_pub_;
275277
};
276278

277279
} // namespace behavior_velocity_planner

0 commit comments

Comments
 (0)
Please sign in to comment.