提交 e9dbd25d 编写于 作者: Y Yajia Zhang

planning: remove unused parameter for STBoundaryMapper

上级 654f176e
......@@ -72,11 +72,10 @@ Status SpeedBoundsDecider::Process(
}
// 2. Map obstacles into st graph
StBoundaryMapper boundary_mapper(adc_sl_boundary, speed_bounds_config_,
STBoundaryMapper boundary_mapper(adc_sl_boundary, speed_bounds_config_,
reference_line, path_data,
speed_bounds_config_.total_path_length(),
speed_bounds_config_.total_time(),
reference_line_info_->IsChangeLanePath());
speed_bounds_config_.total_time());
path_decision->EraseStBoundaries();
if (boundary_mapper.CreateStBoundary(path_decision).code() ==
......
......@@ -48,23 +48,21 @@ using apollo::common::math::Box2d;
using apollo::common::math::Vec2d;
using apollo::common::util::StrCat;
StBoundaryMapper::StBoundaryMapper(const SLBoundary& adc_sl_boundary,
STBoundaryMapper::STBoundaryMapper(const SLBoundary& adc_sl_boundary,
const SpeedBoundsDeciderConfig& config,
const ReferenceLine& reference_line,
const PathData& path_data,
const double planning_distance,
const double planning_time,
bool is_change_lane)
const double planning_time)
: adc_sl_boundary_(adc_sl_boundary),
speed_bounds_config_(config),
reference_line_(reference_line),
path_data_(path_data),
vehicle_param_(common::VehicleConfigHelper::GetConfig().vehicle_param()),
planning_distance_(planning_distance),
planning_time_(planning_time),
is_change_lane_(is_change_lane) {}
planning_time_(planning_time) {}
Status StBoundaryMapper::CreateStBoundary(PathDecision* path_decision) const {
Status STBoundaryMapper::CreateStBoundary(PathDecision* path_decision) const {
const auto& obstacles = path_decision->obstacles();
if (planning_time_ < 0.0) {
......@@ -155,7 +153,7 @@ Status StBoundaryMapper::CreateStBoundary(PathDecision* path_decision) const {
return Status::OK();
}
bool StBoundaryMapper::MapStopDecision(
bool STBoundaryMapper::MapStopDecision(
Obstacle* stop_obstacle, const ObjectDecisionType& stop_decision) const {
DCHECK(stop_decision.has_stop()) << "Must have stop decision";
......@@ -203,7 +201,7 @@ bool StBoundaryMapper::MapStopDecision(
return true;
}
Status StBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
Status STBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
std::vector<STPoint> lower_points;
std::vector<STPoint> upper_points;
......@@ -227,7 +225,7 @@ Status StBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
return Status::OK();
}
bool StBoundaryMapper::GetOverlapBoundaryPoints(
bool STBoundaryMapper::GetOverlapBoundaryPoints(
const std::vector<PathPoint>& path_points, const Obstacle& obstacle,
std::vector<STPoint>* upper_points,
std::vector<STPoint>* lower_points) const {
......@@ -362,7 +360,7 @@ bool StBoundaryMapper::GetOverlapBoundaryPoints(
return (lower_points->size() > 1 && upper_points->size() > 1);
}
Status StBoundaryMapper::MapWithDecision(
Status STBoundaryMapper::MapWithDecision(
Obstacle* obstacle, const ObjectDecisionType& decision) const {
DCHECK(decision.has_follow() || decision.has_yield() ||
decision.has_overtake())
......@@ -418,7 +416,7 @@ Status StBoundaryMapper::MapWithDecision(
return Status::OK();
}
bool StBoundaryMapper::CheckOverlap(const PathPoint& path_point,
bool STBoundaryMapper::CheckOverlap(const PathPoint& path_point,
const Box2d& obs_box,
const double buffer) const {
Vec2d ego_center_map_frame(
......
......@@ -36,22 +36,22 @@
namespace apollo {
namespace planning {
class StBoundaryMapper {
class STBoundaryMapper {
public:
StBoundaryMapper(const SLBoundary& adc_sl_boundary,
STBoundaryMapper(const SLBoundary& adc_sl_boundary,
const SpeedBoundsDeciderConfig& config,
const ReferenceLine& reference_line,
const PathData& path_data, const double planning_distance,
const double planning_time, const bool is_change_lane);
const double planning_time);
virtual ~StBoundaryMapper() = default;
virtual ~STBoundaryMapper() = default;
apollo::common::Status CreateStBoundary(PathDecision* path_decision) const;
common::Status CreateStBoundary(PathDecision* path_decision) const;
private:
FRIEND_TEST(StBoundaryMapperTest, check_overlap_test);
bool CheckOverlap(const apollo::common::PathPoint& path_point,
const apollo::common::math::Box2d& obs_box,
bool CheckOverlap(const common::PathPoint& path_point,
const common::math::Box2d& obs_box,
const double buffer) const;
/**
......@@ -60,27 +60,26 @@ class StBoundaryMapper {
* upper_points.size() = lower_points.size()
*/
bool GetOverlapBoundaryPoints(
const std::vector<apollo::common::PathPoint>& path_points,
const std::vector<common::PathPoint>& path_points,
const Obstacle& obstacle, std::vector<STPoint>* upper_points,
std::vector<STPoint>* lower_points) const;
apollo::common::Status MapWithoutDecision(Obstacle* obstacle) const;
common::Status MapWithoutDecision(Obstacle* obstacle) const;
bool MapStopDecision(Obstacle* stop_obstacle,
const ObjectDecisionType& decision) const;
apollo::common::Status MapWithDecision(
Obstacle* obstacle, const ObjectDecisionType& decision) const;
common::Status MapWithDecision(Obstacle* obstacle,
const ObjectDecisionType& decision) const;
private:
const SLBoundary& adc_sl_boundary_;
const SpeedBoundsDeciderConfig& speed_bounds_config_;
const ReferenceLine& reference_line_;
const PathData& path_data_;
const apollo::common::VehicleParam& vehicle_param_;
const common::VehicleParam& vehicle_param_;
const double planning_distance_;
const double planning_time_;
bool is_change_lane_ = false;
};
} // namespace planning
......
......@@ -81,8 +81,8 @@ TEST_F(StBoundaryMapperTest, check_overlap_test) {
double planning_distance = 70.0;
double planning_time = 10.0;
SLBoundary adc_sl_boundary;
StBoundaryMapper mapper(adc_sl_boundary, config, *reference_line_, path_data_,
planning_distance, planning_time, false);
STBoundaryMapper mapper(adc_sl_boundary, config, *reference_line_, path_data_,
planning_distance, planning_time);
common::PathPoint path_point;
path_point.set_x(1.0);
path_point.set_y(1.0);
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册