Skip to content

Commit

Permalink
reduce diff
Browse files Browse the repository at this point in the history
  • Loading branch information
mitukou1109 committed Jun 27, 2024
1 parent 3b336d7 commit eec09a7
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,6 @@ class ObstacleCruisePlannerNode : public rclcpp::Node

bool enable_debug_info_;
bool enable_calculation_time_info_;
bool enable_slow_down_planning_{false};
bool use_pointcloud_for_stop_;
bool use_pointcloud_for_slow_down_;
double min_behavior_stop_margin_;
Expand Down Expand Up @@ -292,6 +291,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
EgoNearestParam ego_nearest_param_;

bool is_driving_forward_{true};
bool enable_slow_down_planning_{false};
bool use_pointcloud_{false};

std::vector<StopObstacle> prev_closest_stop_obstacles_{};
Expand Down
15 changes: 6 additions & 9 deletions planning/autoware_obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -558,8 +558,8 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
}

const auto & ego_odom = *ego_odom_ptr;
const auto & acc = *acc_ptr;
const auto & objects = objects_ptr ? std::make_optional(*objects_ptr) : std::nullopt;
const auto & acc = *acc_ptr;

const auto traj_points = autoware::motion_utils::convertToTrajectoryPointArray(*msg);
// check if subscribed variables are ready
Expand Down Expand Up @@ -1073,9 +1073,8 @@ std::optional<CruiseObstacle> ObstacleCruisePlannerNode::createCruiseObstacle(
return std::nullopt;
}

const auto & p = behavior_determination_param_;

const auto & object_id = obstacle.uuid.substr(0, 4);
const auto & p = behavior_determination_param_;

// NOTE: When driving backward, Stop will be planned instead of cruise.
// When the obstacle is crossing the ego's trajectory, cruise can be ignored.
Expand Down Expand Up @@ -1121,11 +1120,10 @@ std::optional<CruiseObstacle> ObstacleCruisePlannerNode::createYieldCruiseObstac
return std::nullopt;
}

Check warning on line 1122 in planning/autoware_obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ObstacleCruisePlannerNode::createYieldCruiseObstacle has a cyclomatic complexity of 9, 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.
const auto & p = behavior_determination_param_;

if (traj_points.empty()) return std::nullopt;
// check label
const auto & object_id = obstacle.uuid.substr(0, 4);
const auto & p = behavior_determination_param_;

if (!isOutsideCruiseObstacle(obstacle.classification.label)) {
RCLCPP_INFO_EXPRESSION(
Expand Down Expand Up @@ -1409,10 +1407,9 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
std::optional<std::pair<geometry_msgs::msg::Point, double>> collision_point = std::nullopt;
if (obstacle.source_type == Obstacle::SourceType::POINTCLOUD) {
if (obstacle.stop_collision_point) {
const auto dist_to_collide_on_traj = autoware::motion_utils::calcSignedArcLength(
traj_points, 0, obstacle.stop_collision_point.value());
collision_point =
std::make_pair(obstacle.stop_collision_point.value(), dist_to_collide_on_traj);
const auto dist_to_collide_on_traj =
autoware::motion_utils::calcSignedArcLength(traj_points, 0, *obstacle.stop_collision_point);
collision_point = std::make_pair(*obstacle.stop_collision_point, dist_to_collide_on_traj);
}
} else if (obstacle.source_type == Obstacle::SourceType::PREDICTED_OBJECT) {
const auto & object_id = obstacle.uuid.substr(0, 4);
Expand Down

0 comments on commit eec09a7

Please sign in to comment.