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): display intersection marker only when stopped #3150

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 @@ -48,8 +48,6 @@ class IntersectionModule : public SceneModuleInterface
public:
struct DebugData
{
bool stop_required;

geometry_msgs::msg::Pose stop_wall_pose;
geometry_msgs::msg::Polygon stuck_vehicle_detect_area;
geometry_msgs::msg::Polygon candidate_collision_ego_lane_polygon;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,10 +176,12 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createVirtualWallMarker

const auto now = this->clock_->now();

appendMarkerArray(
virtual_wall_marker_creator_->createStopVirtualWallMarker(
{debug_data_.stop_wall_pose}, "intersection", now, module_id_),
&wall_marker, now);
if (state_machine_.getState() == StateMachine::State::STOP) {
appendMarkerArray(
virtual_wall_marker_creator_->createStopVirtualWallMarker(
{debug_data_.stop_wall_pose}, "intersection", now, module_id_),
&wall_marker, now);
}
return wall_marker;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,6 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *

constexpr double v = 0.0;
planning_utils::setVelocityFromIndex(stop_line_idx.value(), v, path);
debug_data_.stop_required = true;
const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
debug_data_.stop_wall_pose =
planning_utils::getAheadPose(stop_line_idx.value(), base_link2front, *path);
Expand Down