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

fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback #9234

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
@@ -1,4 +1,4 @@
// Copyright 2020-2023 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1090 to 1088, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -199,8 +199,6 @@

collision_info_pub_ =
node.create_publisher<tier4_debug_msgs::msg::StringStamped>("~/debug/collision_info", 1);

vehicle_stop_checker_ = std::make_unique<autoware::motion_utils::VehicleStopChecker>(&node);
}

bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
Expand Down Expand Up @@ -1389,8 +1387,7 @@
bool CrosswalkModule::checkRestartSuppression(
const PathWithLaneId & ego_path, const std::optional<StopFactor> & stop_factor) const
{
const auto is_vehicle_stopped = vehicle_stop_checker_->isVehicleStopped();
if (!is_vehicle_stopped) {
if (!planner_data_->isVehicleStopped()) {
return false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "autoware/behavior_velocity_crosswalk_module/util.hpp"

#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
#include <autoware/motion_utils/vehicle/vehicle_state_checker.hpp>
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
Expand Down Expand Up @@ -474,8 +473,6 @@ class CrosswalkModule : public SceneModuleInterface
// Debug
mutable DebugData debug_data_;

std::unique_ptr<autoware::motion_utils::VehicleStopChecker> vehicle_stop_checker_{nullptr};

// Stop watch
StopWatch<std::chrono::milliseconds> stop_watch_;

Expand Down
Loading