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

chore(intersection): publish decision status string #4456

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ IntersectionModule::IntersectionModule(
before_creep_state_machine_.setState(StateMachine::State::STOP);
stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area);
stuck_private_area_timeout_.setState(StateMachine::State::STOP);
decision_state_pub_ =
node_.create_publisher<std_msgs::msg::String>("~/debug/intersection/decision_state", 1);
}

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

std::string decision_type = "intersection" + std::to_string(module_id_) + " : ";
if (std::get_if<IntersectionModule::Indecisive>(&decision_result)) {
decision_type += "Indecisive";
}
if (std::get_if<IntersectionModule::StuckStop>(&decision_result)) {
decision_type += "StuckStop";
}
if (std::get_if<IntersectionModule::NonOccludedCollisionStop>(&decision_result)) {
decision_type += "NonOccludedCollisionStop";
}
if (std::get_if<IntersectionModule::FirstWaitBeforeOcclusion>(&decision_result)) {
decision_type += "FirstWaitBeforeOcclusion";
}
if (std::get_if<IntersectionModule::PeekingTowardOcclusion>(&decision_result)) {
decision_type += "PeekingTowardOcclusion";
}
if (std::get_if<IntersectionModule::OccludedCollisionStop>(&decision_result)) {
decision_type += "OccludedCollisionStop";
}
if (std::get_if<IntersectionModule::Safe>(&decision_result)) {
decision_type += "Safe";
}
if (std::get_if<IntersectionModule::TrafficLightArrowSolidOn>(&decision_result)) {
decision_type += "TrafficLightArrowSolidOn";
}
std_msgs::msg::String decision_result_msg;
decision_result_msg.data = decision_type;
decision_state_pub_->publish(decision_result_msg);

prepareRTCStatus(decision_result, *path);

const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <std_msgs/msg/string.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>
Expand Down Expand Up @@ -272,6 +273,7 @@ class IntersectionModule : public SceneModuleInterface
*/

util::DebugData debug_data_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr decision_state_pub_;
};

} // namespace behavior_velocity_planner
Expand Down