Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(behavior_velocity_planner): output path's interval can be designated by yaml #6023

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
ros__parameters:
forward_path_length: 1000.0
backward_path_length: 5.0
behavior_output_path_interval: 1.0
stop_line_extend_length: 5.0
max_accel: -2.8
max_jerk: -5.0
Expand Down
4 changes: 3 additions & 1 deletion planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@
// Parameters
forward_path_length_ = declare_parameter<double>("forward_path_length");
backward_path_length_ = declare_parameter<double>("backward_path_length");
behavior_output_path_interval_ = declare_parameter<double>("behavior_output_path_interval");

Check warning on line 141 in planning/behavior_velocity_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode increases from 71 to 72 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
planner_data_.stop_line_extend_length = declare_parameter<double>("stop_line_extend_length");

// nearest search
Expand Down Expand Up @@ -409,7 +410,8 @@
const auto filtered_path = filterLitterPathPoint(to_path(velocity_planned_path));

// interpolation
const auto interpolated_path_msg = interpolatePath(filtered_path, forward_path_length_);
const auto interpolated_path_msg =
interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_);

// check stop point
output_path_msg = filterStopPathPoint(interpolated_path_msg);
Expand Down
1 change: 1 addition & 0 deletions planning/behavior_velocity_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
// parameter
double forward_path_length_;
double backward_path_length_;
double behavior_output_path_interval_;

// member
PlannerData planner_data_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,7 @@ bool splineInterpolate(
const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval,
autoware_auto_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger logger);
autoware_auto_planning_msgs::msg::Path interpolatePath(
const autoware_auto_planning_msgs::msg::Path & path, const double length,
const double interval = 1.0);
const autoware_auto_planning_msgs::msg::Path & path, const double length, const double interval);
autoware_auto_planning_msgs::msg::Path filterLitterPathPoint(
const autoware_auto_planning_msgs::msg::Path & path);
autoware_auto_planning_msgs::msg::Path filterStopPathPoint(
Expand Down
Loading