Skip to content

Commit 3f68fd9

Browse files
committed
add param and remove debug svg
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent a168cc3 commit 3f68fd9

File tree

3 files changed

+7
-27
lines changed

3 files changed

+7
-27
lines changed

planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
# if false, assume the object moves at constant velocity along *all* lanelets it currently is located in.
1919
predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value.
2020
distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
21+
cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights
2122

2223
overlap:
2324
minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered

planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp

+3-26
Original file line numberDiff line numberDiff line change
@@ -30,15 +30,6 @@
3030
#include <string>
3131
#include <vector>
3232

33-
// for writing the svg file
34-
#include <fstream>
35-
#include <iostream>
36-
// for the geometry types
37-
#include <tier4_autoware_utils/geometry/geometry.hpp>
38-
// for the svg mapper
39-
#include <boost/geometry/io/svg/svg_mapper.hpp>
40-
#include <boost/geometry/io/svg/write.hpp>
41-
4233
namespace behavior_velocity_planner::out_of_lane
4334
{
4435
void cut_predicted_path_beyond_line(
@@ -98,23 +89,10 @@ std::optional<const lanelet::BasicLineString2d> find_next_stop_line(
9889
/// @param [in] planner_data planner data to get the map and traffic light information
9990
void cut_predicted_path_beyond_red_lights(
10091
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
101-
const PlannerData & planner_data, const double object_front_overhang, int i)
92+
const PlannerData & planner_data, const double object_front_overhang)
10293
{
103-
// Declare a stream and an SVG mapper
104-
std::ofstream svg(
105-
"/home/mclement/Pictures/image" + std::to_string(i) + ".svg"); // /!\ CHANGE PATH
106-
boost::geometry::svg_mapper<tier4_autoware_utils::Point2d> mapper(svg, 400, 400);
10794
const auto stop_line = find_next_stop_line(predicted_path, planner_data);
108-
lanelet::BasicLineString2d path_ls;
109-
for (const auto & p : predicted_path.path) path_ls.emplace_back(p.position.x, p.position.y);
11095
if (stop_line) cut_predicted_path_beyond_line(predicted_path, *stop_line, object_front_overhang);
111-
lanelet::BasicLineString2d cut_path_ls;
112-
for (const auto & p : predicted_path.path) cut_path_ls.emplace_back(p.position.x, p.position.y);
113-
mapper.add(cut_path_ls);
114-
if (stop_line) mapper.add(*stop_line);
115-
mapper.map(path_ls, "opacity:0.3;fill:black;stroke:black;stroke-width:2");
116-
if (stop_line) mapper.map(*stop_line, "opacity:0.5;fill:black;stroke:red;stroke-width:2");
117-
mapper.map(cut_path_ls, "opacity:0.3;fill:red;stroke:red;stroke-width:2");
11896
}
11997

12098
/// @brief filter predicted objects and their predicted paths
@@ -153,11 +131,10 @@ autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects(
153131
const auto new_end =
154132
std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path);
155133
predicted_paths.erase(new_end, predicted_paths.end());
156-
auto i = 0;
157-
if (true || params.objects_cut_predicted_paths_beyond_red_lights)
134+
if (params.objects_cut_predicted_paths_beyond_red_lights)
158135
for (auto & predicted_path : predicted_paths)
159136
cut_predicted_path_beyond_red_lights(
160-
predicted_path, planner_data, filtered_object.shape.dimensions.x, i++);
137+
predicted_path, planner_data, filtered_object.shape.dimensions.x);
161138
predicted_paths.erase(
162139
std::remove_if(
163140
predicted_paths.begin(), predicted_paths.end(),

planning/behavior_velocity_out_of_lane_module/src/manager.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,10 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node)
5151
pp.objects_min_confidence =
5252
getOrDeclareParameter<double>(node, ns + ".objects.predicted_path_min_confidence");
5353
pp.objects_dist_buffer = getOrDeclareParameter<double>(node, ns + ".objects.distance_buffer");
54+
pp.objects_cut_predicted_paths_beyond_red_lights =
55+
getOrDeclareParameter<bool>(node, ns + ".objects.cut_predicted_paths_beyond_red_lights")
5456

55-
pp.overlap_min_dist = getOrDeclareParameter<double>(node, ns + ".overlap.minimum_distance");
57+
pp.overlap_min_dist = getOrDeclareParameter<double>(node, ns + ".overlap.minimum_distance");
5658
pp.overlap_extra_length = getOrDeclareParameter<double>(node, ns + ".overlap.extra_length");
5759

5860
pp.skip_if_over_max_decel =

0 commit comments

Comments
 (0)