File tree 2 files changed +1
-7
lines changed
planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src
2 files changed +1
-7
lines changed Original file line number Diff line number Diff line change @@ -199,8 +199,6 @@ CrosswalkModule::CrosswalkModule(
199
199
200
200
collision_info_pub_ =
201
201
node.create_publisher <tier4_debug_msgs::msg::StringStamped>(" ~/debug/collision_info" , 1 );
202
-
203
- vehicle_stop_checker_ = std::make_unique<autoware::motion_utils::VehicleStopChecker>(&node);
204
202
}
205
203
206
204
bool CrosswalkModule::modifyPathVelocity (PathWithLaneId * path, StopReason * stop_reason)
@@ -1389,8 +1387,7 @@ void CrosswalkModule::planStop(
1389
1387
bool CrosswalkModule::checkRestartSuppression (
1390
1388
const PathWithLaneId & ego_path, const std::optional<StopFactor> & stop_factor) const
1391
1389
{
1392
- const auto is_vehicle_stopped = vehicle_stop_checker_->isVehicleStopped ();
1393
- if (!is_vehicle_stopped) {
1390
+ if (!planner_data_->isVehicleStopped ()) {
1394
1391
return false ;
1395
1392
}
1396
1393
Original file line number Diff line number Diff line change 18
18
#include " autoware/behavior_velocity_crosswalk_module/util.hpp"
19
19
20
20
#include < autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
21
- #include < autoware/motion_utils/vehicle/vehicle_state_checker.hpp>
22
21
#include < autoware/universe_utils/geometry/boost_geometry.hpp>
23
22
#include < autoware/universe_utils/system/stop_watch.hpp>
24
23
#include < autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
@@ -466,8 +465,6 @@ class CrosswalkModule : public SceneModuleInterface
466
465
// Debug
467
466
mutable DebugData debug_data_;
468
467
469
- std::unique_ptr<autoware::motion_utils::VehicleStopChecker> vehicle_stop_checker_{nullptr };
470
-
471
468
// Stop watch
472
469
StopWatch<std::chrono::milliseconds> stop_watch_;
473
470
You can’t perform that action at this time.
0 commit comments