Skip to content

Commit

Permalink
fix(crosswalk): don't use vehicle stop checker to remove unnecessary …
Browse files Browse the repository at this point in the history
…callback (autowarefoundation#9234)

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Nov 6, 2024
1 parent c2abb5c commit 200781f
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -197,8 +197,6 @@ CrosswalkModule::CrosswalkModule(

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

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

bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
Expand Down Expand Up @@ -1221,8 +1219,7 @@ void CrosswalkModule::planStop(
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 @@ -436,8 +436,6 @@ class CrosswalkModule : public SceneModuleInterface
// Debug
mutable DebugData debug_data_;

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

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

Expand Down

0 comments on commit 200781f

Please sign in to comment.