Skip to content

Commit

Permalink
po
Browse files Browse the repository at this point in the history
Signed-off-by: yuki-takagi-66 <[email protected]>
  • Loading branch information
yuki-takagi-66 committed Jan 20, 2025
1 parent 225121a commit 7c9c094
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -336,13 +336,13 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(

// Check pedestrian for stop
// NOTE: first stop point and its minimum distance from ego to stop
auto isVehicleType = [](const uint8_t label) {
return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE;
};
// auto isVehicleType = [](const uint8_t label) {
// return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE;
// };
std::optional<double> dist_nearest_cp;
std::vector<geometry_msgs::msg::Point> stop_factor_points;
const std::optional<double> ego_crosswalk_passage_direction =
findEgoPassageDirectionAlongPath(sparse_resample_path);
// const std::optional<double> ego_crosswalk_passage_direction =
// findEgoPassageDirectionAlongPath(sparse_resample_path);
for (const auto & object : object_info_manager_.getObject()) {
const auto & collision_point_opt = object.collision_point;
if (collision_point_opt) {
Expand All @@ -352,18 +352,18 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
continue;
}

if (
isVehicleType(object.classification) && ego_crosswalk_passage_direction &&
collision_point.crosswalk_passage_direction) {
double direction_diff = std::abs(std::fmod(
collision_point.crosswalk_passage_direction.value() -
ego_crosswalk_passage_direction.value(),
M_PI_2));
direction_diff = std::min(direction_diff, M_PI_2 - direction_diff);
if (direction_diff < planner_param_.vehicle_object_cross_angle_threshold) {
continue;
}
}
// if (
// isVehicleType(object.classification) && ego_crosswalk_passage_direction &&

Check notice on line 356 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Conditional

CrosswalkModule::checkStopForCrosswalkUsers no longer has a complex conditional. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
// collision_point.crosswalk_passage_direction) {
// double direction_diff = std::abs(std::fmod(
// collision_point.crosswalk_passage_direction.value() -
// ego_crosswalk_passage_direction.value(),
// M_PI_2));
// direction_diff = std::min(direction_diff, M_PI_2 - direction_diff);
// if (direction_diff < planner_param_.vehicle_object_cross_angle_threshold) {
// continue;
// }
// }

Check notice on line 366 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

CrosswalkModule::checkStopForCrosswalkUsers decreases in cyclomatic complexity from 16 to 10, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 366 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

CrosswalkModule::checkStopForCrosswalkUsers is no longer above the threshold for logical blocks with deeply nested code. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check notice on line 366 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Deep, Nested Complexity

CrosswalkModule::checkStopForCrosswalkUsers is no longer above the threshold for nested complexity depth. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

stop_factor_points.push_back(object.position);

Expand Down Expand Up @@ -1166,10 +1166,12 @@ void CrosswalkModule::updateObjectState(

const auto collision_point =
getCollisionPoint(sparse_resample_path, object, crosswalk_attention_range, attention_area);
const std::optional<double> ego_crosswalk_passage_direction =
findEgoPassageDirectionAlongPath(sparse_resample_path);
object_info_manager_.update(
obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding,
has_traffic_light, collision_point, object.classification.front().label, planner_param_,
crosswalk_.polygon2d().basicPolygon(), attention_area);
crosswalk_.polygon2d().basicPolygon(), attention_area, ego_crosswalk_passage_direction);

const auto collision_state = object_info_manager_.getCollisionState(obj_uuid);
if (collision_point) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,8 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC
const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel,
const bool is_ego_yielding, const std::optional<CollisionPoint> & collision_point,
const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon,
const bool is_object_away_from_path)
const bool is_object_away_from_path,
const std::optional<double> & ego_crosswalk_passage_direction)
{
const bool is_stopped = vel < planner_param.stop_object_velocity;

Expand Down Expand Up @@ -224,6 +225,24 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC

// Compare time to collision and vehicle
if (collision_point) {
auto isVehicleType = [](const uint8_t label) {
return label == ObjectClassification::MOTORCYCLE ||
label == ObjectClassification::BICYCLE;
};
if (
isVehicleType(classification) && ego_crosswalk_passage_direction &&
collision_point->crosswalk_passage_direction) {
double direction_diff = std::abs(std::fmod(
collision_point->crosswalk_passage_direction.value() -
ego_crosswalk_passage_direction.value(),
M_PI_2));
direction_diff = std::min(direction_diff, M_PI_2 - direction_diff);
if (direction_diff < planner_param.vehicle_object_cross_angle_threshold) {
collision_state = CollisionState::IGNORE;
return;
}
}

// Check if ego will pass first
const double ego_pass_first_additional_margin =
collision_state == CollisionState::EGO_PASS_FIRST
Expand Down Expand Up @@ -268,7 +287,8 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC
const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light,
const std::optional<CollisionPoint> & collision_point, const uint8_t classification,
const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon,
const Polygon2d & attention_area)
const Polygon2d & attention_area,
const std::optional<double> & ego_crosswalk_passage_direction)
{
// update current uuids
current_uuids_.push_back(uuid);
Expand All @@ -292,7 +312,7 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC
// update object state
objects.at(uuid).transitState(
now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon,
is_object_away_from_path);
is_object_away_from_path, ego_crosswalk_passage_direction);
objects.at(uuid).collision_point = collision_point;
objects.at(uuid).position = position;
objects.at(uuid).classification = classification;
Expand Down

0 comments on commit 7c9c094

Please sign in to comment.