Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(behavior_velocity): occlusion spot generalize detection area polygon #520

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions planning/behavior_velocity_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -220,10 +220,8 @@ target_link_libraries(scene_module_virtual_traffic_light scene_module_lib)
# SceneModule OcclusionSpot
ament_auto_add_library(scene_module_occlusion_spot SHARED
src/scene_module/occlusion_spot/grid_utils.cpp
src/scene_module/occlusion_spot/geometry.cpp
src/scene_module/occlusion_spot/manager.cpp
src/scene_module/occlusion_spot/debug.cpp
src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp
src/scene_module/occlusion_spot/scene_occlusion_spot.cpp
src/scene_module/occlusion_spot/occlusion_spot_utils.cpp
src/scene_module/occlusion_spot/risk_predictive_braking.cpp
Expand Down Expand Up @@ -313,7 +311,6 @@ if(BUILD_TESTING)
ament_add_gtest(occlusion_spot-test
test/src/test_occlusion_spot_utils.cpp
test/src/test_risk_predictive_braking.cpp
test/src/test_geometry.cpp
test/src/test_grid_utils.cpp
)
target_link_libraries(occlusion_spot-test
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
/**:
ros__parameters:
occlusion_spot:
method: "predicted_object" # [-] candidate is "occupancy_grid" or "predicted_object"
detection_method: "predicted_object" # [-] candidate is "occupancy_grid" or "predicted_object"
pass_judge: "current_velocity" # [-] candidate is "current_velocity""
debug: false # [-] whether to publish debug markers. Note Default should be false for performance
use_partition_lanelet: true # [-] whether to use partition lanelet map data
pedestrian_vel: 1.0 # [m/s] assume pedestrian is dashing from occlusion at this velocity
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <grid_map_core/iterators/LineIterator.hpp>
#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <opencv2/opencv.hpp>
#include <utilization/boost_geometry_helper.hpp>

#include <nav_msgs/msg/occupancy_grid.hpp>

Expand Down Expand Up @@ -67,7 +68,7 @@ bool isOcclusionSpotSquare(
//!< @brief Find all occlusion spots inside the given lanelet
void findOcclusionSpots(
std::vector<grid_map::Position> & occlusion_spot_positions, const grid_map::GridMap & grid,
const lanelet::BasicPolygon2d & polygon, const double min_size);
const Polygon2d & polygon, const double min_size);
//!< @brief Return true if the path between the two given points is free of occupied cells
bool isCollisionFree(
const grid_map::GridMap & grid, const grid_map::Position & p1, const grid_map::Position & p2);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <rclcpp/rclcpp.hpp>
#include <scene_module/occlusion_spot/occlusion_spot_utils.hpp>
#include <scene_module/occlusion_spot/scene_occlusion_spot.hpp>
#include <scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp>
#include <scene_module/scene_module_interface.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_object.hpp>
Expand Down Expand Up @@ -49,6 +48,7 @@ class OcclusionSpotModuleManager : public SceneModuleManagerInterface
using PlannerParam = occlusion_spot_utils::PlannerParam;

PlannerParam planner_param_;
int64_t module_id_;

void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <lanelet2_extension/utility/utilities.hpp>
#include <lanelet2_extension/visualization/visualization.hpp>
#include <scene_module/occlusion_spot/grid_utils.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/trajectory/trajectory.hpp>
#include <utilization/util.hpp>

#include <autoware_auto_perception_msgs/msg/object_classification.hpp>
Expand All @@ -42,6 +42,16 @@
#include <utility>
#include <vector>

namespace tier4_autoware_utils
{
template <>
inline geometry_msgs::msg::Pose getPose(
const autoware_auto_planning_msgs::msg::PathPointWithLaneId & p)
{
return p.point.pose;
}
} // namespace tier4_autoware_utils

namespace behavior_velocity_planner
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
Expand All @@ -67,7 +77,8 @@ using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
namespace occlusion_spot_utils
{
enum ROAD_TYPE { PRIVATE, PUBLIC, HIGHWAY, UNKNOWN };
enum METHOD { OCCUPANCY_GRID, PREDICTED_OBJECT };
enum DETECTION_METHOD { OCCUPANCY_GRID, PREDICTED_OBJECT };
enum PASS_JUDGE { SMOOTH_VELOCITY, CURRENT_VELOCITY };

struct DetectionArea
{
Expand Down Expand Up @@ -99,7 +110,8 @@ struct LatLon

struct PlannerParam
{
METHOD method;
DETECTION_METHOD detection_method;
PASS_JUDGE pass_judge;
bool debug; // [-]
bool use_partition_lanelet; // [-]
// parameters in yaml
Expand Down Expand Up @@ -127,22 +139,6 @@ struct SafeMotion
double safe_velocity;
};

// @brief represent the range of a each polygon
struct SliceRange
{
double min_length{};
double max_length{};
double min_distance{};
double max_distance{};
};

// @brief representation of a polygon along a path
struct Slice
{
SliceRange range{};
lanelet::BasicPolygon2d polygon{};
};

struct ObstacleInfo
{
SafeMotion safe_motion; // safe motion of velocity and stop point
Expand Down Expand Up @@ -185,7 +181,7 @@ struct DebugData
double z;
std::string road_type = "";
std::string detection_type = "";
std::vector<Slice> detection_area_polygons;
Polygons2d detection_area_polygons;
std::vector<lanelet::BasicPolygon2d> partition_lanelets;
std::vector<geometry_msgs::msg::Point> parked_vehicle_point;
std::vector<PossibleCollisionInfo> possible_collisions;
Expand All @@ -200,22 +196,26 @@ struct DebugData
occlusion_points.clear();
}
};

// apply current velocity to path
PathWithLaneId applyVelocityToPath(const PathWithLaneId & path, const double v0);
//!< @brief wrapper for detection area polygon generation
void buildDetectionAreaPolygon(
Polygons2d & slices, const PathWithLaneId & path, const double offset,
const PlannerParam & param);
lanelet::ConstLanelet toPathLanelet(const PathWithLaneId & path);
// Note : consider offset_from_start_to_ego and safety margin for collision here
void handleCollisionOffset(std::vector<PossibleCollisionInfo> & possible_collisions, double offset);
void clipPathByLength(
const PathWithLaneId & path, PathWithLaneId & clipped, const double max_length = 100.0);
bool isStuckVehicle(PredictedObject obj, const double min_vel);
double offsetFromStartToEgo(
const PathWithLaneId & path, const Pose & ego_pose, const int closest_idx);
std::vector<PredictedObject> filterDynamicObjectByDetectionArea(
std::vector<PredictedObject> & objs, const std::vector<Slice> & polys);
std::vector<PredictedObject> & objs, const Polygons2d & polys);
std::vector<PredictedObject> getParkedVehicles(
const PredictedObjects & dyn_objects, const PlannerParam & param,
std::vector<Point> & debug_point);
std::vector<PossibleCollisionInfo> generatePossibleCollisionBehindParkedVehicle(
const PathWithLaneId & path, const PlannerParam & param, const double offset_from_start_to_ego,
bool generatePossibleCollisionBehindParkedVehicle(
std::vector<PossibleCollisionInfo> & possible_collisions, const PathWithLaneId & path,
const PlannerParam & param, const double offset_from_start_to_ego,
const std::vector<PredictedObject> & dyn_objects);
ROAD_TYPE getCurrentRoadType(
const lanelet::ConstLanelet & current_lanelet, const LaneletMapPtr & lanelet_map_ptr);
Expand All @@ -236,10 +236,10 @@ void calcSlowDownPointsForPossibleCollision(
//!< @brief convert a set of occlusion spots found on detection_area slice
boost::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
const grid_map::GridMap & grid, const std::vector<grid_map::Position> & occlusion_spot_positions,
const double offset_from_start_to_ego, const BasicPoint2d base_point,
const double offset_from_start_to_ego, const Point2d base_point,
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data);
//!< @brief generate possible collisions coming from occlusion spots on the side of the path
void createPossibleCollisionsInDetectionArea(
bool createPossibleCollisionsInDetectionArea(
std::vector<PossibleCollisionInfo> & possible_collisions, const grid_map::GridMap & grid,
const PathWithLaneId & path, const double offset_from_start_to_ego, const PlannerParam & param,
DebugData & debug_data);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,6 @@ int insertSafeVelocityToPath(
const geometry_msgs::msg::Pose & in_pose, const double safe_vel, const PlannerParam & param,
PathWithLaneId * inout_path);

/**
*
* @param: longitudinal_distance: longitudinal distance to collision
* @param: param: planner param
* @return lateral distance
**/
double calculateLateralDistanceFromTTC(
const double longitudinal_distance, const PlannerParam & param);

/**
* @param: v: ego velocity config
* @param: ttc: time to collision
Expand Down

This file was deleted.

24 changes: 22 additions & 2 deletions planning/behavior_velocity_planner/include/utilization/util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,18 +63,30 @@ struct SearchRangeIndex
size_t min_idx;
size_t max_idx;
};
struct DetectionRange
{
bool use_right = true;
bool use_left = true;
double interval;
double min_longitudinal_distance;
double max_longitudinal_distance;
double min_lateral_distance;
double max_lateral_distance;
};
struct PointWithSearchRangeIndex
{
geometry_msgs::msg::Point point;
SearchRangeIndex index;
};
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using Point2d = boost::geometry::model::d2::point_xy<double>;
using Polygons2d = std::vector<lanelet::BasicPolygon2d>;
using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
using Polygons2d = std::vector<Polygon2d>;
namespace planning_utils
{
using geometry_msgs::msg::Pose;
inline geometry_msgs::msg::Point getPoint(const geometry_msgs::msg::Point & p) { return p; }
inline geometry_msgs::msg::Point getPoint(const geometry_msgs::msg::Pose & p) { return p.position; }
inline geometry_msgs::msg::Point getPoint(const geometry_msgs::msg::PoseStamped & p)
Expand Down Expand Up @@ -110,7 +122,15 @@ inline geometry_msgs::msg::Pose getPose(
{
return traj.points.at(idx).pose;
}
void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, Polygons2d & polys);

// create detection area from given range
void createDetectionAreaPolygons(
Polygons2d & slices, const PathWithLaneId & path, const DetectionRange da_range,
const double obstacle_vel_mps);

Point2d calculateLateralOffsetPoint2d(const Pose & p, const double offset);

void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, BasicPolygons2d & polys);
void setVelocityFrom(const size_t idx, const double vel, PathWithLaneId * input);
void insertVelocity(
PathWithLaneId & path, const PathPointWithLaneId & path_point, const double v,
Expand Down
Loading