Skip to content

Commit f3fb4fa

Browse files
fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (autowarefoundation#9234) (#1630)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com>
1 parent 7d609fa commit f3fb4fa

File tree

2 files changed

+1
-7
lines changed

2 files changed

+1
-7
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -201,8 +201,6 @@ CrosswalkModule::CrosswalkModule(
201201

202202
collision_info_pub_ =
203203
node.create_publisher<tier4_debug_msgs::msg::StringStamped>("~/debug/collision_info", 1);
204-
205-
vehicle_stop_checker_ = std::make_unique<autoware::motion_utils::VehicleStopChecker>(&node);
206204
}
207205

208206
bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
@@ -1389,8 +1387,7 @@ void CrosswalkModule::planStop(
13891387
bool CrosswalkModule::checkRestartSuppression(
13901388
const PathWithLaneId & ego_path, const std::optional<StopFactor> & stop_factor) const
13911389
{
1392-
const auto is_vehicle_stopped = vehicle_stop_checker_->isVehicleStopped();
1393-
if (!is_vehicle_stopped) {
1390+
if (!planner_data_->isVehicleStopped()) {
13941391
return false;
13951392
}
13961393

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
#include "autoware/behavior_velocity_crosswalk_module/util.hpp"
1919

2020
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
21-
#include <autoware/motion_utils/vehicle/vehicle_state_checker.hpp>
2221
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2322
#include <autoware/universe_utils/system/stop_watch.hpp>
2423
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
@@ -466,8 +465,6 @@ class CrosswalkModule : public SceneModuleInterface
466465
// Debug
467466
mutable DebugData debug_data_;
468467

469-
std::unique_ptr<autoware::motion_utils::VehicleStopChecker> vehicle_stop_checker_{nullptr};
470-
471468
// Stop watch
472469
StopWatch<std::chrono::milliseconds> stop_watch_;
473470

0 commit comments

Comments
 (0)