From 3e2b342a6da2205e3aa31e01a74af942ca9427e8 Mon Sep 17 00:00:00 2001 From: YajiaZhang Date: Thu, 15 Feb 2018 13:15:44 -0800 Subject: [PATCH] planning: renamed PathTimeNeighborhood to PathTimeGraph --- .../planning/lattice/behavior_decider/BUILD | 14 +++++----- .../behavior_decider/behavior_decider.cc | 2 +- .../behavior_decider/behavior_decider.h | 6 ++--- .../behavior_decider/condition_filter.cc | 2 +- .../behavior_decider/condition_filter.h | 6 ++--- ...ime_neighborhood.cc => path_time_graph.cc} | 26 +++++++++---------- ..._time_neighborhood.h => path_time_graph.h} | 13 ++++++---- .../lattice/trajectory_generator/BUILD | 2 +- .../trajectory_evaluator.cc | 2 +- .../trajectory_evaluator.h | 6 ++--- modules/planning/planner/lattice/BUILD | 2 +- .../planner/lattice/lattice_planner.cc | 6 ++--- 12 files changed, 45 insertions(+), 42 deletions(-) rename modules/planning/lattice/behavior_decider/{path_time_neighborhood.cc => path_time_graph.cc} (93%) rename modules/planning/lattice/behavior_decider/{path_time_neighborhood.h => path_time_graph.h} (88%) diff --git a/modules/planning/lattice/behavior_decider/BUILD b/modules/planning/lattice/behavior_decider/BUILD index 4c9d885ec0..e411e4757b 100644 --- a/modules/planning/lattice/behavior_decider/BUILD +++ b/modules/planning/lattice/behavior_decider/BUILD @@ -18,8 +18,8 @@ cc_library( "//modules/planning/common:frame", "//modules/planning/common:planning_gflags", "//modules/planning/common/trajectory:discretized_trajectory", + "//modules/planning/lattice/behavior_decider:path_time_graph", "//modules/planning/lattice/behavior_decider:condition_filter", - "//modules/planning/lattice/behavior_decider:path_time_neighborhood", "//modules/planning/lattice/behavior_decider:scenario_manager", "//modules/planning/proto:lattice_sampling_config_proto", "//modules/planning/proto:planning_proto", @@ -86,12 +86,12 @@ cc_library( ) cc_library( - name = "path_time_neighborhood", - srcs = [ - "path_time_neighborhood.cc", - ], + name = "path_time_graph", hdrs = [ - "path_time_neighborhood.h", + "path_time_graph.h", + ], + srcs = [ + "path_time_graph.cc", ], deps = [ "//modules/common", @@ -117,8 +117,8 @@ cc_library( ], deps = [ "//modules/common/math:linear_interpolation", + "//modules/planning/lattice/behavior_decider:path_time_graph", "//modules/planning/lattice/behavior_decider:feasible_region", - "//modules/planning/lattice/behavior_decider:path_time_neighborhood", "//modules/planning/proto:lattice_structure_proto", "//modules/planning/proto:planning_proto", ], diff --git a/modules/planning/lattice/behavior_decider/behavior_decider.cc b/modules/planning/lattice/behavior_decider/behavior_decider.cc index 671669708f..0fc37a2440 100644 --- a/modules/planning/lattice/behavior_decider/behavior_decider.cc +++ b/modules/planning/lattice/behavior_decider/behavior_decider.cc @@ -35,7 +35,7 @@ using apollo::common::PointENU; BehaviorDecider::BehaviorDecider() {} void BehaviorDecider::UpdatePathTimeNeighborhood( - std::shared_ptr p) { + std::shared_ptr p) { path_time_neighborhood_ = p; } diff --git a/modules/planning/lattice/behavior_decider/behavior_decider.h b/modules/planning/lattice/behavior_decider/behavior_decider.h index a0098d3126..055d557255 100644 --- a/modules/planning/lattice/behavior_decider/behavior_decider.h +++ b/modules/planning/lattice/behavior_decider/behavior_decider.h @@ -29,7 +29,7 @@ #include "modules/planning/common/frame.h" #include "modules/planning/common/reference_line_info.h" #include "modules/planning/common/trajectory/discretized_trajectory.h" -#include "modules/planning/lattice/behavior_decider/path_time_neighborhood.h" +#include "modules/planning/lattice/behavior_decider/path_time_graph.h" #include "modules/planning/proto/lattice_structure.pb.h" #include "modules/planning/proto/planning.pb.h" @@ -40,7 +40,7 @@ class BehaviorDecider { public: BehaviorDecider(); - void UpdatePathTimeNeighborhood(std::shared_ptr p); + void UpdatePathTimeNeighborhood(std::shared_ptr p); virtual ~BehaviorDecider() = default; @@ -51,7 +51,7 @@ class BehaviorDecider { const std::vector& discretized_reference_line); private: - std::shared_ptr path_time_neighborhood_; + std::shared_ptr path_time_neighborhood_; }; } // namespace planning diff --git a/modules/planning/lattice/behavior_decider/condition_filter.cc b/modules/planning/lattice/behavior_decider/condition_filter.cc index f7911a1eaa..b8262c56b1 100644 --- a/modules/planning/lattice/behavior_decider/condition_filter.cc +++ b/modules/planning/lattice/behavior_decider/condition_filter.cc @@ -36,7 +36,7 @@ using PathTimePointPair = std::pair; ConditionFilter::ConditionFilter( const std::array& init_s, const double speed_limit, - std::shared_ptr path_time_neighborhood) + std::shared_ptr path_time_neighborhood) : feasible_region_(init_s, speed_limit), ptr_path_time_neighborhood_(path_time_neighborhood) {} diff --git a/modules/planning/lattice/behavior_decider/condition_filter.h b/modules/planning/lattice/behavior_decider/condition_filter.h index c41634598b..1d424c0ee9 100644 --- a/modules/planning/lattice/behavior_decider/condition_filter.h +++ b/modules/planning/lattice/behavior_decider/condition_filter.h @@ -29,7 +29,7 @@ #include #include "modules/planning/lattice/behavior_decider/feasible_region.h" -#include "modules/planning/lattice/behavior_decider/path_time_neighborhood.h" +#include "modules/planning/lattice/behavior_decider/path_time_graph.h" #include "modules/planning/proto/lattice_structure.pb.h" #include "modules/planning/proto/planning_internal.pb.h" @@ -39,7 +39,7 @@ namespace planning { class ConditionFilter { public: ConditionFilter(const std::array& init_s, const double speed_limit, - std::shared_ptr path_time_neighborhood); + std::shared_ptr path_time_neighborhood); std::vector QuerySampleBounds(const double t) const; @@ -68,7 +68,7 @@ class ConditionFilter { private: FeasibleRegion feasible_region_; - std::shared_ptr ptr_path_time_neighborhood_; + std::shared_ptr ptr_path_time_neighborhood_; }; } // namespace planning diff --git a/modules/planning/lattice/behavior_decider/path_time_neighborhood.cc b/modules/planning/lattice/behavior_decider/path_time_graph.cc similarity index 93% rename from modules/planning/lattice/behavior_decider/path_time_neighborhood.cc rename to modules/planning/lattice/behavior_decider/path_time_graph.cc index 0bd8f44395..3640960f4a 100644 --- a/modules/planning/lattice/behavior_decider/path_time_neighborhood.cc +++ b/modules/planning/lattice/behavior_decider/path_time_graph.cc @@ -18,7 +18,7 @@ * @file **/ -#include "modules/planning/lattice/behavior_decider/path_time_neighborhood.h" +#include "modules/planning/lattice/behavior_decider/path_time_graph.h" #include #include @@ -68,7 +68,7 @@ int LastIndexBefore(const prediction::Trajectory& trajectory, const double t) { } // namespace -PathTimeNeighborhood::PathTimeNeighborhood( +PathTimeGraph::PathTimeGraph( const std::vector& obstacles, const double ego_s, const std::vector& discretized_ref_points) { path_range_.first = ego_s; @@ -81,7 +81,7 @@ PathTimeNeighborhood::PathTimeNeighborhood( SetupObstacles(obstacles, discretized_ref_points); } -SLBoundary PathTimeNeighborhood::ComputeObstacleBoundary( +SLBoundary PathTimeGraph::ComputeObstacleBoundary( const Box2d& box, const std::vector& discretized_ref_points) const { double start_s(std::numeric_limits::max()); @@ -109,7 +109,7 @@ SLBoundary PathTimeNeighborhood::ComputeObstacleBoundary( return sl_boundary; } -void PathTimeNeighborhood::SetupObstacles( +void PathTimeGraph::SetupObstacles( const std::vector& obstacles, const std::vector& discretized_ref_points) { @@ -200,7 +200,7 @@ void PathTimeNeighborhood::SetupObstacles( } } -void PathTimeNeighborhood::SetStaticPathTimeObstacle( +void PathTimeGraph::SetStaticPathTimeObstacle( const Obstacle* obstacle, const std::vector& discretized_ref_points) { TrajectoryPoint start_point = obstacle->GetPointAtTime(0.0); @@ -222,7 +222,7 @@ void PathTimeNeighborhood::SetStaticPathTimeObstacle( FLAGS_trajectory_time_length)); } -double PathTimeNeighborhood::SpeedAtT(const std::string& obstacle_id, +double PathTimeGraph::SpeedAtT(const std::string& obstacle_id, const double s, const double t) const { bool found = prediction_traj_map_.find(obstacle_id) != prediction_traj_map_.end(); @@ -267,7 +267,7 @@ double PathTimeNeighborhood::SpeedAtT(const std::string& obstacle_id, return std::cos(ref_theta) * v_x + std::sin(ref_theta) * v_y; } -PathTimePoint PathTimeNeighborhood::SetPathTimePoint( +PathTimePoint PathTimeGraph::SetPathTimePoint( const std::string& obstacle_id, const double s, const double t) const { PathTimePoint path_time_point; path_time_point.set_s(s); @@ -278,11 +278,11 @@ PathTimePoint PathTimeNeighborhood::SetPathTimePoint( } const std::vector& -PathTimeNeighborhood::GetPathTimeObstacles() const { +PathTimeGraph::GetPathTimeObstacles() const { return path_time_obstacles_; } -bool PathTimeNeighborhood::GetPathTimeObstacle( +bool PathTimeGraph::GetPathTimeObstacle( const std::string& obstacle_id, PathTimeObstacle* path_time_obstacle) { if (path_time_obstacle_map_.find(obstacle_id) == path_time_obstacle_map_.end()) { @@ -293,7 +293,7 @@ bool PathTimeNeighborhood::GetPathTimeObstacle( } std::vector> -PathTimeNeighborhood::GetPathBlockingIntervals(const double t) const { +PathTimeGraph::GetPathBlockingIntervals(const double t) const { CHECK(time_range_.first <= t && t <= time_range_.second); std::vector> intervals; for (const auto& pt_obstacle : path_time_obstacles_) { @@ -314,7 +314,7 @@ PathTimeNeighborhood::GetPathBlockingIntervals(const double t) const { } std::vector>> -PathTimeNeighborhood::GetPathBlockingIntervals(const double t_start, +PathTimeGraph::GetPathBlockingIntervals(const double t_start, const double t_end, const double t_resolution) { std::vector>> intervals; @@ -324,11 +324,11 @@ PathTimeNeighborhood::GetPathBlockingIntervals(const double t_start, return intervals; } -std::pair PathTimeNeighborhood::get_path_range() const { +std::pair PathTimeGraph::get_path_range() const { return path_range_; } -std::pair PathTimeNeighborhood::get_time_range() const { +std::pair PathTimeGraph::get_time_range() const { return time_range_; } diff --git a/modules/planning/lattice/behavior_decider/path_time_neighborhood.h b/modules/planning/lattice/behavior_decider/path_time_graph.h similarity index 88% rename from modules/planning/lattice/behavior_decider/path_time_neighborhood.h rename to modules/planning/lattice/behavior_decider/path_time_graph.h index a3f4414cf2..392dd037cb 100644 --- a/modules/planning/lattice/behavior_decider/path_time_neighborhood.h +++ b/modules/planning/lattice/behavior_decider/path_time_graph.h @@ -18,8 +18,8 @@ * @file **/ -#ifndef MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_NEIGHBORHOOD_H_ -#define MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_NEIGHBORHOOD_H_ +#ifndef MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_GRAPH_H_ +#define MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_GRAPH_H_ #include #include @@ -37,9 +37,9 @@ namespace apollo { namespace planning { -class PathTimeNeighborhood { +class PathTimeGraph { public: - PathTimeNeighborhood( + PathTimeGraph( const std::vector& obstacles, const double ego_s, const std::vector& discretized_ref_points); @@ -61,6 +61,9 @@ class PathTimeNeighborhood { std::pair get_time_range() const; + std::vector> GetPathTimeNeighborhoodPoints( + const double s_dist, const double t_density) const; + private: void SetupObstacles( const std::vector& obstacles, @@ -95,4 +98,4 @@ class PathTimeNeighborhood { } // namespace planning } // namespace apollo -#endif // MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_NEIGHBORHOOD_H_ +#endif // MODULES_PLANNING_LATTICE_BEHAVIOR_DECIDER_PATH_TIME_GRAPH_H_ diff --git a/modules/planning/lattice/trajectory_generator/BUILD b/modules/planning/lattice/trajectory_generator/BUILD index 3b07e206e9..9cfa73b504 100644 --- a/modules/planning/lattice/trajectory_generator/BUILD +++ b/modules/planning/lattice/trajectory_generator/BUILD @@ -51,9 +51,9 @@ cc_library( "//modules/common", "//modules/planning/common:planning_gflags", "//modules/planning/constraint_checker:constraint_checker1d", - "//modules/planning/lattice/behavior_decider:path_time_neighborhood", "//modules/planning/math/curve1d", "//modules/planning/proto:lattice_sampling_config_proto", + "//modules/planning/lattice/behavior_decider:path_time_graph", ], ) diff --git a/modules/planning/lattice/trajectory_generator/trajectory_evaluator.cc b/modules/planning/lattice/trajectory_generator/trajectory_evaluator.cc index 23256196d9..2ee8737a03 100644 --- a/modules/planning/lattice/trajectory_generator/trajectory_evaluator.cc +++ b/modules/planning/lattice/trajectory_generator/trajectory_evaluator.cc @@ -39,7 +39,7 @@ TrajectoryEvaluator::TrajectoryEvaluator( const std::vector>& lon_trajectories, const std::vector>& lat_trajectories, bool is_auto_tuning, - std::shared_ptr pathtime_neighborhood) + std::shared_ptr pathtime_neighborhood) : is_auto_tuning_(is_auto_tuning), pathtime_neighborhood_(pathtime_neighborhood) { diff --git a/modules/planning/lattice/trajectory_generator/trajectory_evaluator.h b/modules/planning/lattice/trajectory_generator/trajectory_evaluator.h index 53919b07b8..7c829743ad 100644 --- a/modules/planning/lattice/trajectory_generator/trajectory_evaluator.h +++ b/modules/planning/lattice/trajectory_generator/trajectory_evaluator.h @@ -27,7 +27,7 @@ #include #include -#include "modules/planning/lattice/behavior_decider/path_time_neighborhood.h" +#include "../behavior_decider/path_time_graph.h" #include "modules/planning/math/curve1d/curve1d.h" #include "modules/planning/proto/lattice_structure.pb.h" #include "modules/planning/proto/planning_config.pb.h" @@ -53,7 +53,7 @@ class TrajectoryEvaluator { const std::vector>& lon_trajectories, const std::vector>& lat_trajectories, bool is_auto_tuning, - std::shared_ptr pathtime_neighborhood); + std::shared_ptr pathtime_neighborhood); virtual ~TrajectoryEvaluator() = default; @@ -118,7 +118,7 @@ class TrajectoryEvaluator { bool is_auto_tuning_ = false; - std::shared_ptr pathtime_neighborhood_; + std::shared_ptr pathtime_neighborhood_; std::vector>> path_time_intervals_; }; diff --git a/modules/planning/planner/lattice/BUILD b/modules/planning/planner/lattice/BUILD index 2a4802e157..377d2895b9 100644 --- a/modules/planning/planner/lattice/BUILD +++ b/modules/planning/planner/lattice/BUILD @@ -18,7 +18,7 @@ cc_library( "//modules/planning/constraint_checker", "//modules/planning/constraint_checker:collision_checker", "//modules/planning/lattice/behavior_decider", - "//modules/planning/lattice/behavior_decider:path_time_neighborhood", + "//modules/planning/lattice/behavior_decider:path_time_graph", "//modules/planning/lattice/trajectory_generator:backup_trajectory_generator", "//modules/planning/lattice/trajectory_generator:trajectory1d_generator", "//modules/planning/lattice/trajectory_generator:trajectory_combiner", diff --git a/modules/planning/planner/lattice/lattice_planner.cc b/modules/planning/planner/lattice/lattice_planner.cc index f8fdb273e3..87d8e0d3de 100644 --- a/modules/planning/planner/lattice/lattice_planner.cc +++ b/modules/planning/planner/lattice/lattice_planner.cc @@ -26,6 +26,7 @@ #include #include +#include "../../lattice/behavior_decider/path_time_graph.h" #include "modules/common/adapters/adapter_manager.h" #include "modules/common/log.h" #include "modules/common/macro.h" @@ -33,7 +34,6 @@ #include "modules/planning/common/planning_gflags.h" #include "modules/planning/constraint_checker/collision_checker.h" #include "modules/planning/constraint_checker/constraint_checker.h" -#include "modules/planning/lattice/behavior_decider/path_time_neighborhood.h" #include "modules/planning/lattice/trajectory_generator/backup_trajectory_generator.h" #include "modules/planning/lattice/trajectory_generator/trajectory1d_generator.h" #include "modules/planning/lattice/trajectory_generator/trajectory_combiner.h" @@ -159,8 +159,8 @@ Status LatticePlanner::PlanOnReferenceLine( current_time = Clock::NowInSeconds(); // 4. parse the decision and get the planning target. - std::shared_ptr path_time_neighborhood_ptr( - new PathTimeNeighborhood(frame->obstacles(), init_s[0], + std::shared_ptr path_time_neighborhood_ptr( + new PathTimeGraph(frame->obstacles(), init_s[0], discretized_reference_line)); decider_.UpdatePathTimeNeighborhood(path_time_neighborhood_ptr); -- GitLab