Skip to content

Commit

Permalink
add param and remove debug svg
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
  • Loading branch information
maxime-clem committed Feb 22, 2024
1 parent fa35de6 commit 595152d
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 27 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
# if false, assume the object moves at constant velocity along *all* lanelets it currently is located in.
predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value.
distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights

overlap:
minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,6 @@
#include <string>
#include <vector>

// for writing the svg file
#include <fstream>
#include <iostream>
// for the geometry types
#include <tier4_autoware_utils/geometry/geometry.hpp>
// for the svg mapper
#include <boost/geometry/io/svg/svg_mapper.hpp>
#include <boost/geometry/io/svg/write.hpp>

namespace behavior_velocity_planner::out_of_lane
{
void cut_predicted_path_beyond_line(
Expand Down Expand Up @@ -98,23 +89,10 @@ std::optional<const lanelet::BasicLineString2d> find_next_stop_line(
/// @param [in] planner_data planner data to get the map and traffic light information
void cut_predicted_path_beyond_red_lights(
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
const PlannerData & planner_data, const double object_front_overhang, int i)
const PlannerData & planner_data, const double object_front_overhang)
{
// Declare a stream and an SVG mapper
std::ofstream svg(
"/home/mclement/Pictures/image" + std::to_string(i) + ".svg"); // /!\ CHANGE PATH
boost::geometry::svg_mapper<tier4_autoware_utils::Point2d> mapper(svg, 400, 400);
const auto stop_line = find_next_stop_line(predicted_path, planner_data);
lanelet::BasicLineString2d path_ls;
for (const auto & p : predicted_path.path) path_ls.emplace_back(p.position.x, p.position.y);
if (stop_line) cut_predicted_path_beyond_line(predicted_path, *stop_line, object_front_overhang);
lanelet::BasicLineString2d cut_path_ls;
for (const auto & p : predicted_path.path) cut_path_ls.emplace_back(p.position.x, p.position.y);
mapper.add(cut_path_ls);
if (stop_line) mapper.add(*stop_line);
mapper.map(path_ls, "opacity:0.3;fill:black;stroke:black;stroke-width:2");
if (stop_line) mapper.map(*stop_line, "opacity:0.5;fill:black;stroke:red;stroke-width:2");
mapper.map(cut_path_ls, "opacity:0.3;fill:red;stroke:red;stroke-width:2");
}

/// @brief filter predicted objects and their predicted paths
Expand Down Expand Up @@ -153,11 +131,10 @@ autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects(
const auto new_end =
std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path);
predicted_paths.erase(new_end, predicted_paths.end());
auto i = 0;
if (true || params.objects_cut_predicted_paths_beyond_red_lights)
if (params.objects_cut_predicted_paths_beyond_red_lights)
for (auto & predicted_path : predicted_paths)
cut_predicted_path_beyond_red_lights(
predicted_path, planner_data, filtered_object.shape.dimensions.x, i++);
predicted_path, planner_data, filtered_object.shape.dimensions.x);
predicted_paths.erase(
std::remove_if(
predicted_paths.begin(), predicted_paths.end(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,10 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node)
pp.objects_min_confidence =
getOrDeclareParameter<double>(node, ns + ".objects.predicted_path_min_confidence");
pp.objects_dist_buffer = getOrDeclareParameter<double>(node, ns + ".objects.distance_buffer");
pp.objects_cut_predicted_paths_beyond_red_lights =
getOrDeclareParameter<bool>(node, ns + ".objects.cut_predicted_paths_beyond_red_lights")

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

pp.skip_if_over_max_decel =
Expand Down

0 comments on commit 595152d

Please sign in to comment.