Skip to content

Commit 470ebba

Browse files
committedJul 1, 2024·
refactor(static_centerline_optimizer): clean up the code (autowarefoundation#7756)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent d1f0430 commit 470ebba

File tree

4 files changed

+12
-19
lines changed

4 files changed

+12
-19
lines changed
 

‎planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz

+1-1
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ Visualization Manager:
122122
Name: Map
123123
- Class: rviz_plugins/PathWithLaneId
124124
Color Border Vel Max: 3
125-
Enabled: true
125+
Enabled: false
126126
Name: Raw Centerline
127127
Topic:
128128
Depth: 5

‎planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py

+4-1
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ def setupUI(self):
6565
centerline_group.setLayout(centerline_vertical_box)
6666
self.grid_layout.addWidget(centerline_group)
6767

68+
"""
6869
# 2. Road Boundary
6970
road_boundary_group = QGroupBox("Road Boundary")
7071
road_boundary_vertical_box = QVBoxLayout(self)
@@ -79,8 +80,8 @@ def setupUI(self):
7980
self.road_boundary_lateral_margin_slider.setMaximum(
8081
5 * self.road_boundary_lateral_margin_ratio
8182
)
82-
8383
road_boundary_vertical_box.addWidget(QPushButton("reset"))
84+
"""
8485

8586
# 3. General
8687
general_group = QGroupBox("General")
@@ -123,9 +124,11 @@ def __init__(self):
123124
self.widget.validate_button.clicked.connect(self.onValidateButtonPushed)
124125
self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged)
125126
self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged)
127+
"""
126128
self.widget.road_boundary_lateral_margin_slider.valueChanged.connect(
127129
self.onRoadBoundaryLateralMargin
128130
)
131+
"""
129132

130133
# ROS
131134
self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1)

‎planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp

+7-16
Original file line numberDiff line numberDiff line change
@@ -251,11 +251,6 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode(
251251
}
252252
save_map();
253253
});
254-
sub_traj_resample_interval_ = create_subscription<std_msgs::msg::Float32>(
255-
"/static_centerline_generator/traj_resample_interval", rclcpp::QoS{1},
256-
[this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) {
257-
// TODO(murooka)
258-
});
259254
sub_validate_ = create_subscription<std_msgs::msg::Empty>(
260255
"/static_centerline_generator/validate", rclcpp::QoS{1},
261256
[this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); });
@@ -325,14 +320,6 @@ void StaticCenterlineGeneratorNode::generate_centerline()
325320
visualize_selected_centerline();
326321
}
327322

328-
void StaticCenterlineGeneratorNode::validate()
329-
{
330-
const auto selected_centerline = centerline_handler_.get_selected_centerline();
331-
const auto road_bounds = update_road_boundary(selected_centerline);
332-
333-
evaluate();
334-
}
335-
336323
CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route()
337324
{
338325
if (!route_handler_ptr_) {
@@ -572,7 +559,7 @@ void StaticCenterlineGeneratorNode::on_plan_path(
572559
CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids});
573560

574561
// publish unsafe_footprints
575-
evaluate();
562+
validate();
576563

577564
// create output data
578565
auto target_traj_point = optimized_traj_points.cbegin();
@@ -714,8 +701,11 @@ RoadBounds StaticCenterlineGeneratorNode::update_road_boundary(
714701
return RoadBounds{ego_left_bound, ego_right_bound};
715702
}
716703

717-
void StaticCenterlineGeneratorNode::evaluate()
704+
void StaticCenterlineGeneratorNode::validate()
718705
{
706+
// const auto selected_centerline = centerline_handler_.get_selected_centerline();
707+
// const auto road_bounds = update_road_boundary(selected_centerline);
708+
719709
std::cerr << std::endl
720710
<< "############################################## Validation Results "
721711
"##############################################"
@@ -730,6 +720,7 @@ void StaticCenterlineGeneratorNode::evaluate()
730720
const double max_steer_angle_margin =
731721
getRosParameter<double>("validation.max_steer_angle_margin");
732722

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

809-
// publish left boundary
800+
// publish road boundaries
810801
const auto left_bound = convertToGeometryPoints(lanelet_left_bound);
811802
const auto right_bound = convertToGeometryPoints(lanelet_right_bound);
812803

‎planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,6 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node
133133

134134
void visualize_selected_centerline();
135135
RoadBounds update_road_boundary(const std::vector<TrajectoryPoint> & centerline);
136-
void evaluate();
137136

138137
// parameter
139138
template <typename T>

0 commit comments

Comments
 (0)