Skip to content

Commit

Permalink
refactor(static_centerline_optimizer): clean up the code (autowarefou…
Browse files Browse the repository at this point in the history
…ndation#7756)

Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 committed Jul 1, 2024
1 parent d1f0430 commit 470ebba
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ Visualization Manager:
Name: Map
- Class: rviz_plugins/PathWithLaneId
Color Border Vel Max: 3
Enabled: true
Enabled: false
Name: Raw Centerline
Topic:
Depth: 5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ def setupUI(self):
centerline_group.setLayout(centerline_vertical_box)
self.grid_layout.addWidget(centerline_group)

"""
# 2. Road Boundary
road_boundary_group = QGroupBox("Road Boundary")
road_boundary_vertical_box = QVBoxLayout(self)
Expand All @@ -79,8 +80,8 @@ def setupUI(self):
self.road_boundary_lateral_margin_slider.setMaximum(
5 * self.road_boundary_lateral_margin_ratio
)

road_boundary_vertical_box.addWidget(QPushButton("reset"))
"""

# 3. General
general_group = QGroupBox("General")
Expand Down Expand Up @@ -123,9 +124,11 @@ def __init__(self):
self.widget.validate_button.clicked.connect(self.onValidateButtonPushed)
self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged)
self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged)
"""
self.widget.road_boundary_lateral_margin_slider.valueChanged.connect(
self.onRoadBoundaryLateralMargin
)
"""

# ROS
self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -251,11 +251,6 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode(
}
save_map();
});
sub_traj_resample_interval_ = create_subscription<std_msgs::msg::Float32>(
"/static_centerline_generator/traj_resample_interval", rclcpp::QoS{1},
[this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) {
// TODO(murooka)
});
sub_validate_ = create_subscription<std_msgs::msg::Empty>(
"/static_centerline_generator/validate", rclcpp::QoS{1},
[this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); });
Expand Down Expand Up @@ -325,14 +320,6 @@ void StaticCenterlineGeneratorNode::generate_centerline()
visualize_selected_centerline();
}

void StaticCenterlineGeneratorNode::validate()
{
const auto selected_centerline = centerline_handler_.get_selected_centerline();
const auto road_bounds = update_road_boundary(selected_centerline);

evaluate();
}

CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route()
{
if (!route_handler_ptr_) {
Expand Down Expand Up @@ -572,7 +559,7 @@ void StaticCenterlineGeneratorNode::on_plan_path(
CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids});

// publish unsafe_footprints
evaluate();
validate();

// create output data
auto target_traj_point = optimized_traj_points.cbegin();
Expand Down Expand Up @@ -714,8 +701,11 @@ RoadBounds StaticCenterlineGeneratorNode::update_road_boundary(
return RoadBounds{ego_left_bound, ego_right_bound};
}

void StaticCenterlineGeneratorNode::evaluate()
void StaticCenterlineGeneratorNode::validate()
{
// const auto selected_centerline = centerline_handler_.get_selected_centerline();
// const auto road_bounds = update_road_boundary(selected_centerline);

std::cerr << std::endl
<< "############################################## Validation Results "
"##############################################"
Expand All @@ -730,6 +720,7 @@ void StaticCenterlineGeneratorNode::evaluate()
const double max_steer_angle_margin =
getRosParameter<double>("validation.max_steer_angle_margin");

// calculate color for distance to road border
const auto dist_thresh_vec = getRosParameter<std::vector<double>>("marker_color_dist_thresh");
const auto marker_color_vec = getRosParameter<std::vector<std::string>>("marker_color");
const auto get_marker_color = [&](const double dist) -> boost::optional<std::array<double, 3>> {
Expand Down Expand Up @@ -806,7 +797,7 @@ void StaticCenterlineGeneratorNode::evaluate()
}
}

// publish left boundary
// publish road boundaries
const auto left_bound = convertToGeometryPoints(lanelet_left_bound);
const auto right_bound = convertToGeometryPoints(lanelet_right_bound);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,6 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node

void visualize_selected_centerline();
RoadBounds update_road_boundary(const std::vector<TrajectoryPoint> & centerline);
void evaluate();

// parameter
template <typename T>
Expand Down

0 comments on commit 470ebba

Please sign in to comment.