提交 85867d47 编写于 作者: H Hongyi 提交者: Qi Luo

Revert "planning: STBoundaryMapper remove buffer"

This reverts commit 7912ce004e1b4b115e2743eaba9655e2b7b5f51b.
上级 64117b0c
......@@ -48,6 +48,12 @@ using apollo::common::math::Box2d;
using apollo::common::math::Vec2d;
using apollo::common::util::StrCat;
namespace {
// TODO(all): remove them; no buffer should be added here.
constexpr double boundary_t_buffer = 0.1;
constexpr double boundary_s_buffer = 1.0;
} // namespace
StBoundaryMapper::StBoundaryMapper(const SLBoundary& adc_sl_boundary,
const SpeedBoundsDeciderConfig& config,
const ReferenceLine& reference_line,
......@@ -212,7 +218,9 @@ Status StBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
return Status::OK();
}
auto boundary = STBoundary::CreateInstance(lower_points, upper_points);
auto boundary = STBoundary::CreateInstance(lower_points, upper_points)
.ExpandByS(boundary_s_buffer)
.ExpandByT(boundary_t_buffer);
boundary.set_id(obstacle->Id());
const auto& prev_st_boundary = obstacle->st_boundary();
const auto& ref_line_st_boundary = obstacle->reference_line_st_boundary();
......@@ -389,7 +397,9 @@ Status StBoundaryMapper::MapWithDecision(
lower_points.emplace_back(extend_lower_s, planning_time_);
}
auto boundary = STBoundary::CreateInstance(lower_points, upper_points);
auto boundary = STBoundary::CreateInstance(lower_points, upper_points)
.ExpandByS(boundary_s_buffer)
.ExpandByT(boundary_t_buffer);
// get characteristic_length and boundary_type.
STBoundary::BoundaryType b_type = STBoundary::BoundaryType::UNKNOWN;
......@@ -420,7 +430,6 @@ Status StBoundaryMapper::MapWithDecision(
bool StBoundaryMapper::CheckOverlap(const PathPoint& path_point,
const Box2d& obs_box,
const double buffer) const {
/**
// TODO(all): the code makes no sense; remove it.
double left_delta_l = 0.0;
double right_delta_l = 0.0;
......@@ -451,26 +460,6 @@ bool StBoundaryMapper::CheckOverlap(const PathPoint& path_point,
vehicle_param_.length() + 2.0 * buffer,
vehicle_param_.width() + 2.0 * buffer);
return obs_box.HasOverlap(adc_box);
**/
// TODO(all): the code makes no sense; remove it.
Vec2d ego_center_map_frame(
(vehicle_param_.front_edge_to_center() -
vehicle_param_.back_edge_to_center()) *
0.5,
(vehicle_param_.left_edge_to_center() -
vehicle_param_.right_edge_to_center()) *
0.5);
ego_center_map_frame.SelfRotate(path_point.theta());
ego_center_map_frame.set_x(ego_center_map_frame.x() + path_point.x());
ego_center_map_frame.set_y(ego_center_map_frame.y() + path_point.y());
Box2d adc_box(ego_center_map_frame, path_point.theta(),
vehicle_param_.length(),
vehicle_param_.width());
return obs_box.HasOverlap(adc_box);
}
} // namespace planning
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册