@@ -251,11 +251,6 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode(
251
251
}
252
252
save_map ();
253
253
});
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
- });
259
254
sub_validate_ = create_subscription<std_msgs::msg::Empty>(
260
255
" /static_centerline_generator/validate" , rclcpp::QoS{1 },
261
256
[this ]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate (); });
@@ -325,14 +320,6 @@ void StaticCenterlineGeneratorNode::generate_centerline()
325
320
visualize_selected_centerline ();
326
321
}
327
322
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
-
336
323
CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route ()
337
324
{
338
325
if (!route_handler_ptr_) {
@@ -572,7 +559,7 @@ void StaticCenterlineGeneratorNode::on_plan_path(
572
559
CenterlineHandler (CenterlineWithRoute{optimized_traj_points, route_lane_ids});
573
560
574
561
// publish unsafe_footprints
575
- evaluate ();
562
+ validate ();
576
563
577
564
// create output data
578
565
auto target_traj_point = optimized_traj_points.cbegin ();
@@ -714,8 +701,11 @@ RoadBounds StaticCenterlineGeneratorNode::update_road_boundary(
714
701
return RoadBounds{ego_left_bound, ego_right_bound};
715
702
}
716
703
717
- void StaticCenterlineGeneratorNode::evaluate ()
704
+ void StaticCenterlineGeneratorNode::validate ()
718
705
{
706
+ // const auto selected_centerline = centerline_handler_.get_selected_centerline();
707
+ // const auto road_bounds = update_road_boundary(selected_centerline);
708
+
719
709
std::cerr << std::endl
720
710
<< " ############################################## Validation Results "
721
711
" ##############################################"
@@ -730,6 +720,7 @@ void StaticCenterlineGeneratorNode::evaluate()
730
720
const double max_steer_angle_margin =
731
721
getRosParameter<double >(" validation.max_steer_angle_margin" );
732
722
723
+ // calculate color for distance to road border
733
724
const auto dist_thresh_vec = getRosParameter<std::vector<double >>(" marker_color_dist_thresh" );
734
725
const auto marker_color_vec = getRosParameter<std::vector<std::string>>(" marker_color" );
735
726
const auto get_marker_color = [&](const double dist) -> boost::optional<std::array<double , 3 >> {
@@ -806,7 +797,7 @@ void StaticCenterlineGeneratorNode::evaluate()
806
797
}
807
798
}
808
799
809
- // publish left boundary
800
+ // publish road boundaries
810
801
const auto left_bound = convertToGeometryPoints (lanelet_left_bound);
811
802
const auto right_bound = convertToGeometryPoints (lanelet_right_bound);
812
803
0 commit comments