Skip to content

Commit a2ae07f

Browse files
committed
static stop pose -> default stop pose
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent a7cb680 commit a2ae07f

File tree

3 files changed

+17
-16
lines changed

3 files changed

+17
-16
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ group apply slow down
2222
:applySlowDownByOcclusion;
2323
end group
2424
group calculate stop pose
25-
:getStaticStopPose;
25+
:getDefaultStopPose;
2626
:resamplePath;
2727
:checkStopForCrosswalkUsers;
2828
:checkStopForStuckVehicles;

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+15-14
Original file line numberDiff line numberDiff line change
@@ -243,7 +243,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
243243
recordTime(2);
244244

245245
// 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);
247247

248248
// Resample path sparsely for less computation cost
249249
constexpr double resample_interval = 4.0;
@@ -253,12 +253,12 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
253253
// Decide to stop for crosswalk users
254254
const auto stop_factor_for_crosswalk_users = checkStopForCrosswalkUsers(
255255
*path, sparse_resample_path, first_path_point_on_crosswalk, last_path_point_on_crosswalk,
256-
static_stop_pose);
256+
default_stop_pose);
257257

258258
// Decide to stop for stuck vehicle
259259
const auto stop_factor_for_stuck_vehicles = checkStopForStuckVehicles(
260260
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);
262262

263263
// Get nearest stop factor
264264
const auto nearest_stop_factor =
@@ -270,13 +270,13 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
270270

271271
// Set distance
272272
// 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);
274274

275275
// plan Go/Stop
276276
if (isActivated()) {
277277
planGo(*path, nearest_stop_factor);
278278
} else {
279-
planStop(*path, nearest_stop_factor, static_stop_pose, stop_reason);
279+
planStop(*path, nearest_stop_factor, default_stop_pose, stop_reason);
280280
}
281281
recordTime(4);
282282

@@ -288,7 +288,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
288288
}
289289

290290
// 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(
292292
const PathWithLaneId & ego_path,
293293
const geometry_msgs::msg::Point & first_path_point_on_crosswalk) const
294294
{
@@ -314,7 +314,7 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
314314
const PathWithLaneId & ego_path, const PathWithLaneId & sparse_resample_path,
315315
const geometry_msgs::msg::Point & first_path_point_on_crosswalk,
316316
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)
318318
{
319319
const auto & ego_pos = planner_data_->current_odometry->pose.position;
320320
const double ego_vel = planner_data_->current_velocity->twist.linear.x;
@@ -324,7 +324,7 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
324324
findEgoPassageDirectionAlongPath(sparse_resample_path);
325325
const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
326326
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);
328328

329329
// Calculate attention range for crosswalk
330330
const auto crosswalk_attention_range = getAttentionRange(
@@ -400,8 +400,8 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
400400

401401
if (stop_at_stop_line) {
402402
// 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);
405405
}
406406
} else {
407407
const auto stop_pose = calcLongitudinalOffsetPose(
@@ -1238,13 +1238,14 @@ geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon(
12381238
}
12391239

12401240
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,
12421243
const std::optional<StopFactor> & stop_factor)
12431244
{
12441245
// calculate stop position
12451246
const auto stop_pos = [&]() -> std::optional<geometry_msgs::msg::Point> {
12461247
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;
12481249
return std::nullopt;
12491250
}();
12501251

@@ -1273,11 +1274,11 @@ void CrosswalkModule::planGo(
12731274

12741275
void CrosswalkModule::planStop(
12751276
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)
12771278
{
12781279
const auto stop_factor = [&]() -> std::optional<StopFactor> {
12791280
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);
12811282
return std::nullopt;
12821283
}();
12831284

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -344,7 +344,7 @@ class CrosswalkModule : public SceneModuleInterface
344344
PathWithLaneId & output, const geometry_msgs::msg::Point & first_path_point_on_crosswalk,
345345
const geometry_msgs::msg::Point & last_path_point_on_crosswalk);
346346

347-
std::optional<geometry_msgs::msg::Pose> getStaticStopPose(
347+
std::optional<geometry_msgs::msg::Pose> getDefaultStopPose(
348348
const PathWithLaneId & ego_path,
349349
const geometry_msgs::msg::Point & first_path_point_on_crosswalk) const;
350350

0 commit comments

Comments
 (0)