@@ -86,6 +86,8 @@ IntersectionModule::IntersectionModule(
86
86
before_creep_state_machine_.setState (StateMachine::State::STOP);
87
87
stuck_private_area_timeout_.setMarginTime (planner_param_.stuck_vehicle .timeout_private_area );
88
88
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 );
89
91
}
90
92
91
93
void IntersectionModule::initializeRTCStatus ()
@@ -648,6 +650,35 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
648
650
// calculate the
649
651
const auto decision_result = modifyPathVelocityDetail (path, stop_reason);
650
652
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
+
651
682
prepareRTCStatus (decision_result, *path);
652
683
653
684
const double baselink2front = planner_data_->vehicle_info_ .max_longitudinal_offset_m ;
0 commit comments