@@ -243,7 +243,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
243
243
recordTime (2 );
244
244
245
245
// Calculate stop point with margin
246
- const auto static_stop_pose = getStaticStopPose (*path, first_path_point_on_crosswalk);
246
+ const auto default_stop_pose = getDefaultStopPose (*path, first_path_point_on_crosswalk);
247
247
248
248
// Resample path sparsely for less computation cost
249
249
constexpr double resample_interval = 4.0 ;
@@ -253,12 +253,12 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
253
253
// Decide to stop for crosswalk users
254
254
const auto stop_factor_for_crosswalk_users = checkStopForCrosswalkUsers (
255
255
*path, sparse_resample_path, first_path_point_on_crosswalk, last_path_point_on_crosswalk,
256
- static_stop_pose );
256
+ default_stop_pose );
257
257
258
258
// Decide to stop for stuck vehicle
259
259
const auto stop_factor_for_stuck_vehicles = checkStopForStuckVehicles (
260
260
sparse_resample_path, objects_ptr->objects , first_path_point_on_crosswalk,
261
- last_path_point_on_crosswalk, static_stop_pose );
261
+ last_path_point_on_crosswalk, default_stop_pose );
262
262
263
263
// Get nearest stop factor
264
264
const auto nearest_stop_factor =
@@ -270,13 +270,13 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
270
270
271
271
// Set distance
272
272
// NOTE: If no stop point is inserted, distance to the virtual stop line has to be calculated.
273
- setDistanceToStop (*path, static_stop_pose , nearest_stop_factor);
273
+ setDistanceToStop (*path, default_stop_pose , nearest_stop_factor);
274
274
275
275
// plan Go/Stop
276
276
if (isActivated ()) {
277
277
planGo (*path, nearest_stop_factor);
278
278
} else {
279
- planStop (*path, nearest_stop_factor, static_stop_pose , stop_reason);
279
+ planStop (*path, nearest_stop_factor, default_stop_pose , stop_reason);
280
280
}
281
281
recordTime (4 );
282
282
@@ -288,7 +288,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
288
288
}
289
289
290
290
// NOTE: The stop point will be the returned point with the margin.
291
- std::optional<geometry_msgs::msg::Pose> CrosswalkModule::getStaticStopPose (
291
+ std::optional<geometry_msgs::msg::Pose> CrosswalkModule::getDefaultStopPose (
292
292
const PathWithLaneId & ego_path,
293
293
const geometry_msgs::msg::Point & first_path_point_on_crosswalk) const
294
294
{
@@ -314,7 +314,7 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
314
314
const PathWithLaneId & ego_path, const PathWithLaneId & sparse_resample_path,
315
315
const geometry_msgs::msg::Point & first_path_point_on_crosswalk,
316
316
const geometry_msgs::msg::Point & last_path_point_on_crosswalk,
317
- const std::optional<geometry_msgs::msg::Pose> & static_stop_pose )
317
+ const std::optional<geometry_msgs::msg::Pose> & default_stop_pose )
318
318
{
319
319
const auto & ego_pos = planner_data_->current_odometry ->pose .position ;
320
320
const double ego_vel = planner_data_->current_velocity ->twist .linear .x ;
@@ -324,7 +324,7 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
324
324
findEgoPassageDirectionAlongPath (sparse_resample_path);
325
325
const auto base_link2front = planner_data_->vehicle_info_ .max_longitudinal_offset_m ;
326
326
const auto dist_ego_to_stop =
327
- calcSignedArcLength (ego_path.points , ego_pos, static_stop_pose ->position );
327
+ calcSignedArcLength (ego_path.points , ego_pos, default_stop_pose ->position );
328
328
329
329
// Calculate attention range for crosswalk
330
330
const auto crosswalk_attention_range = getAttentionRange (
@@ -400,8 +400,8 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
400
400
401
401
if (stop_at_stop_line) {
402
402
// Stop at the stop line
403
- if (static_stop_pose ) {
404
- return createStopFactor (*static_stop_pose , stop_factor_points);
403
+ if (default_stop_pose ) {
404
+ return createStopFactor (*default_stop_pose , stop_factor_points);
405
405
}
406
406
} else {
407
407
const auto stop_pose = calcLongitudinalOffsetPose (
@@ -1238,13 +1238,14 @@ geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon(
1238
1238
}
1239
1239
1240
1240
void CrosswalkModule::setDistanceToStop (
1241
- const PathWithLaneId & ego_path, const std::optional<geometry_msgs::msg::Pose> & static_stop_pose,
1241
+ const PathWithLaneId & ego_path,
1242
+ const std::optional<geometry_msgs::msg::Pose> & default_stop_pose,
1242
1243
const std::optional<StopFactor> & stop_factor)
1243
1244
{
1244
1245
// calculate stop position
1245
1246
const auto stop_pos = [&]() -> std::optional<geometry_msgs::msg::Point > {
1246
1247
if (stop_factor) return stop_factor->stop_pose .position ;
1247
- if (static_stop_pose ) return static_stop_pose ->position ;
1248
+ if (default_stop_pose ) return default_stop_pose ->position ;
1248
1249
return std::nullopt;
1249
1250
}();
1250
1251
@@ -1273,11 +1274,11 @@ void CrosswalkModule::planGo(
1273
1274
1274
1275
void CrosswalkModule::planStop (
1275
1276
PathWithLaneId & ego_path, const std::optional<StopFactor> & nearest_stop_factor,
1276
- const std::optional<geometry_msgs::msg::Pose> & static_stop_pose , StopReason * stop_reason)
1277
+ const std::optional<geometry_msgs::msg::Pose> & default_stop_pose , StopReason * stop_reason)
1277
1278
{
1278
1279
const auto stop_factor = [&]() -> std::optional<StopFactor> {
1279
1280
if (nearest_stop_factor) return *nearest_stop_factor;
1280
- if (static_stop_pose ) return createStopFactor (*static_stop_pose );
1281
+ if (default_stop_pose ) return createStopFactor (*default_stop_pose );
1281
1282
return std::nullopt;
1282
1283
}();
1283
1284
0 commit comments