提交 47940ce8 编写于 作者: L lianglia-apollo 提交者: Jiaming Tao

added test for st_graph_boundary, exit when path length is smaller than...

added test for st_graph_boundary, exit when path length is smaller than reference line length. (#395)

* added test for st_graph_boundary

* exit when path length is smaller than reference line length.

* fixed compilation error.
上级 46cef652
......@@ -30,13 +30,13 @@ const std::string& PathObstacle::Id() const { return id_; }
PathObstacle::PathObstacle(const planning::Obstacle* obstacle,
const ReferenceLine* reference_line)
: obstacle_(obstacle) {
CHECK_NOTNULL(obstacle) << "obstacle is null";
CHECK_NOTNULL(obstacle);
id_ = obstacle_->Id();
CHECK(reference_line != nullptr) << "reference line is null";
Init(reference_line);
}
bool PathObstacle::Init(const ReferenceLine* reference_line) {}
bool PathObstacle::Init(const ReferenceLine* reference_line) { return true; }
const planning::Obstacle* PathObstacle::Obstacle() const { return obstacle_; }
......
......@@ -37,7 +37,9 @@ namespace planning {
using common::SpeedPoint;
namespace {
constexpr double kEpsilontol = 1e-6;
}
bool QpFrenetFrame::Init(const ReferenceLine& reference_line,
const DecisionData& decision_data,
......@@ -46,7 +48,7 @@ bool QpFrenetFrame::Init(const ReferenceLine& reference_line,
const double start_s, const double end_s,
const double time_resolution,
const uint32_t num_points) {
clear_data();
Clear();
_vehicle_param =
common::VehicleConfigHelper::instance()->GetConfig().vehicle_param();
_speed_profile = &speed_data;
......@@ -70,7 +72,7 @@ bool QpFrenetFrame::Init(const ReferenceLine& reference_line,
return false;
}
if (!calcualate_discretized_veh_loc()) {
if (!CalculateDiscretizedVehicleLocation()) {
AERROR << "Fail to calculate discretized vehicle location!";
return false;
}
......@@ -86,15 +88,15 @@ bool QpFrenetFrame::Init(const ReferenceLine& reference_line,
}
// initialize calculation here
if (!calculate_hd_map_bound()) {
if (!CalculateHDMapBound()) {
AERROR << "Calculate hd map bound failed!";
return false;
}
if (!calculate_static_obstacle_bound()) {
if (!CalculateStaticObstacleBound()) {
AERROR << "Calculate static obstacle bound failed!";
return false;
}
if (!calculate_dynamic_obstacle_bound()) {
if (!CalculateDynamicObstacleBound()) {
AERROR << "Calculate dynamic obstacle bound failed!";
return false;
}
......@@ -138,21 +140,21 @@ bool QpFrenetFrame::get_overall_bound(
bool QpFrenetFrame::get_map_bound(
const double s, std::pair<double, double>* const bound) const {
return get_bound(s, _hdmap_bound, bound);
return GetBound(s, _hdmap_bound, bound);
}
bool QpFrenetFrame::get_static_obstacle_bound(
const double s, std::pair<double, double>* const bound) const {
return get_bound(s, _static_obstacle_bound, bound);
return GetBound(s, _static_obstacle_bound, bound);
}
bool QpFrenetFrame::get_dynamic_obstacle_bound(
const double s, std::pair<double, double>* const bound) const {
return get_bound(s, _dynamic_obstacle_bound, bound);
return GetBound(s, _dynamic_obstacle_bound, bound);
}
bool QpFrenetFrame::find_longitudinal_distance(const double time,
SpeedPoint* const speed_point) {
bool QpFrenetFrame::FindLongitudinalDistance(const double time,
SpeedPoint* const speed_point) {
if (_speed_profile == nullptr) {
return false;
}
......@@ -164,7 +166,7 @@ bool QpFrenetFrame::find_longitudinal_distance(const double time,
return true;
}
bool QpFrenetFrame::calcualate_discretized_veh_loc() {
bool QpFrenetFrame::CalculateDiscretizedVehicleLocation() {
double relative_time = 0.0;
for (; relative_time < _speed_profile->total_time();
......@@ -181,8 +183,7 @@ bool QpFrenetFrame::calcualate_discretized_veh_loc() {
return true;
}
bool QpFrenetFrame::mapping_dynamic_obstacle_with_decision(
const Obstacle& obstacle) {
bool QpFrenetFrame::MapDynamicObstacleWithDecision(const Obstacle& obstacle) {
const std::vector<ObjectDecisionType>& decision = obstacle.Decisions();
for (uint32_t i = 0; i < decision.size(); ++i) {
......@@ -226,7 +227,7 @@ bool QpFrenetFrame::mapping_dynamic_obstacle_with_decision(
std::swap(sl_first, sl_second);
}
std::pair<double, double> bound = map_lateral_constraint(
std::pair<double, double> bound = MapLateralConstraint(
sl_first, sl_second, nudge_side,
veh_point.s() - _vehicle_param.back_edge_to_center(),
veh_point.s() + _vehicle_param.front_edge_to_center());
......@@ -242,7 +243,7 @@ bool QpFrenetFrame::mapping_dynamic_obstacle_with_decision(
continue;
}
std::pair<uint32_t, uint32_t> update_index_range =
find_interval(update_start_s, update_end_s);
FindInterval(update_start_s, update_end_s);
for (uint32_t j = update_index_range.first;
j < update_index_range.second; ++j) {
......@@ -258,8 +259,7 @@ bool QpFrenetFrame::mapping_dynamic_obstacle_with_decision(
return true;
}
bool QpFrenetFrame::mapping_static_obstacle_with_decision(
const Obstacle& obstacle) {
bool QpFrenetFrame::MapStaticObstacleWithDecision(const Obstacle& obstacle) {
const std::vector<ObjectDecisionType>& object_decisions =
obstacle.Decisions();
......@@ -273,7 +273,7 @@ bool QpFrenetFrame::mapping_static_obstacle_with_decision(
const auto& box = obstacle.PerceptionBoundingBox();
std::vector<common::math::Vec2d> corners;
box.GetAllCorners(&corners);
if (!mapping_polygon(corners, buffer, -1, &_static_obstacle_bound)) {
if (!MapPolygon(corners, buffer, -1, &_static_obstacle_bound)) {
AERROR << "fail to map polygon with id " << obstacle.Id()
<< " in qp frenet frame";
return false;
......@@ -282,7 +282,7 @@ bool QpFrenetFrame::mapping_static_obstacle_with_decision(
const auto& box = obstacle.PerceptionBoundingBox();
std::vector<common::math::Vec2d> corners;
box.GetAllCorners(&corners);
if (!mapping_polygon(corners, buffer, 1, &_static_obstacle_bound)) {
if (!MapPolygon(corners, buffer, 1, &_static_obstacle_bound)) {
AERROR << "fail to map polygon with id " << obstacle.Id()
<< "in qp frenet frame";
return false;
......@@ -293,7 +293,7 @@ bool QpFrenetFrame::mapping_static_obstacle_with_decision(
return true;
}
bool QpFrenetFrame::mapping_polygon(
bool QpFrenetFrame::MapPolygon(
const std::vector<common::math::Vec2d>& corners, const double buffer,
const bool nudge_side,
std::vector<std::pair<double, double>>* const bound_map) {
......@@ -313,10 +313,10 @@ bool QpFrenetFrame::mapping_polygon(
}
for (uint32_t i = 0; i < sl_corners.size(); ++i) {
if (!map_line(sl_corners[i % sl_corners.size()],
sl_corners[(i + 1) % sl_corners.size()], nudge_side,
bound_map)) {
AERROR << "Mapping box line (sl) " << sl_corners[i].DebugString() << "->"
if (!MapLine(sl_corners[i % sl_corners.size()],
sl_corners[(i + 1) % sl_corners.size()], nudge_side,
bound_map)) {
AERROR << "Map box line (sl) " << sl_corners[i].DebugString() << "->"
<< sl_corners[i + 1].DebugString();
return false;
}
......@@ -324,14 +324,14 @@ bool QpFrenetFrame::mapping_polygon(
return true;
}
bool QpFrenetFrame::map_line(
bool QpFrenetFrame::MapLine(
const common::SLPoint& start, const common::SLPoint& end,
const int nudge_side,
std::vector<std::pair<double, double>>* const constraint) {
common::SLPoint near_point = (start.s() < end.s() ? start : end);
common::SLPoint further_point = (start.s() < end.s() ? end : start);
std::pair<uint32_t, uint32_t> impact_index =
find_interval(near_point.s(), further_point.s());
FindInterval(near_point.s(), further_point.s());
if ((near_point.s() < _start_s - _vehicle_param.back_edge_to_center() &&
further_point.s() < _start_s - _vehicle_param.back_edge_to_center()) ||
......@@ -380,7 +380,7 @@ bool QpFrenetFrame::map_line(
return true;
}
std::pair<double, double> QpFrenetFrame::map_lateral_constraint(
std::pair<double, double> QpFrenetFrame::MapLateralConstraint(
const common::SLPoint& start, const common::SLPoint& end,
const int nudge_side, const double s_start, const double s_end) {
double inf = std::numeric_limits<double>::infinity();
......@@ -413,14 +413,14 @@ std::pair<double, double> QpFrenetFrame::map_lateral_constraint(
return result;
}
std::pair<uint32_t, uint32_t> QpFrenetFrame::find_interval(
std::pair<uint32_t, uint32_t> QpFrenetFrame::FindInterval(
const double start, const double end) const {
double new_start = std::max(start - _vehicle_param.front_edge_to_center(),
_evaluated_knots.front());
double new_end = std::min(end + _vehicle_param.back_edge_to_center(),
_evaluated_knots.back());
uint32_t start_index = find_index(new_start);
uint32_t end_index = find_index(new_end);
uint32_t start_index = FindIndex(new_start);
uint32_t end_index = FindIndex(new_end);
if (end > _evaluated_knots[end_index] &&
end_index + 1 != _evaluated_knots.size()) {
......@@ -430,7 +430,7 @@ std::pair<uint32_t, uint32_t> QpFrenetFrame::find_interval(
return std::make_pair(start_index, end_index);
}
bool QpFrenetFrame::calculate_hd_map_bound() {
bool QpFrenetFrame::CalculateHDMapBound() {
for (uint32_t i = 0; i < _hdmap_bound.size(); ++i) {
double left_bound = 0.0;
double right_bound = 0.0;
......@@ -451,13 +451,13 @@ bool QpFrenetFrame::calculate_hd_map_bound() {
return true;
}
bool QpFrenetFrame::calculate_static_obstacle_bound() {
bool QpFrenetFrame::CalculateStaticObstacleBound() {
const std::vector<Obstacle*> static_obs_list =
_decision_data->StaticObstacles();
for (uint32_t i = 0; i < static_obs_list.size(); ++i) {
const Obstacle* cur_obstacle = static_obs_list[i];
if (!mapping_static_obstacle_with_decision(*cur_obstacle)) {
if (!MapStaticObstacleWithDecision(*cur_obstacle)) {
AERROR << "mapping obstacle with id [" << cur_obstacle->Id()
<< "] failed in qp frenet frame.";
return false;
......@@ -466,13 +466,13 @@ bool QpFrenetFrame::calculate_static_obstacle_bound() {
return true;
}
bool QpFrenetFrame::calculate_dynamic_obstacle_bound() {
bool QpFrenetFrame::CalculateDynamicObstacleBound() {
const std::vector<Obstacle*> dynamic_obs_list =
_decision_data->DynamicObstacles();
for (uint32_t i = 0; i < dynamic_obs_list.size(); ++i) {
const Obstacle* cur_obstacle = dynamic_obs_list[i];
if (!mapping_dynamic_obstacle_with_decision(*cur_obstacle)) {
if (!MapDynamicObstacleWithDecision(*cur_obstacle)) {
AERROR << "mapping obstacle with id [" << cur_obstacle->Id()
<< "] failed in qp frenet frame.";
return false;
......@@ -481,7 +481,7 @@ bool QpFrenetFrame::calculate_dynamic_obstacle_bound() {
return true;
}
bool QpFrenetFrame::get_bound(
bool QpFrenetFrame::GetBound(
const double s, const std::vector<std::pair<double, double>>& bound_map,
std::pair<double, double>* const bound) const {
if (Double::compare(s, _start_s, 1e-8) < 0 ||
......@@ -493,7 +493,7 @@ bool QpFrenetFrame::get_bound(
}
// linear bound interpolation
uint32_t lower_index = find_index(s);
uint32_t lower_index = FindIndex(s);
const double s_low = _evaluated_knots[lower_index];
const double s_high = _evaluated_knots[lower_index + 1];
double weight = (Double::compare(s_high, s_low, 1e-8) <= 0
......@@ -526,7 +526,7 @@ bool QpFrenetFrame::get_bound(
return true;
}
uint32_t QpFrenetFrame::find_index(const double s) const {
uint32_t QpFrenetFrame::FindIndex(const double s) const {
auto upper_bound =
std::lower_bound(_evaluated_knots.begin() + 1, _evaluated_knots.end(), s);
return std::min(
......@@ -535,7 +535,7 @@ uint32_t QpFrenetFrame::find_index(const double s) const {
1;
}
void QpFrenetFrame::clear_data() {
void QpFrenetFrame::Clear() {
_reference_line = nullptr;
_speed_profile = nullptr;
_decision_data = nullptr;
......
......@@ -30,6 +30,7 @@
#include "modules/common/configs/proto/vehicle_config.pb.h"
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/planning/common/obstacle.h"
#include "modules/planning/common/planning_data.h"
#include "modules/planning/common/speed/speed_data.h"
......@@ -65,47 +66,47 @@ class QpFrenetFrame {
std::pair<double, double>* const bound) const;
private:
bool find_longitudinal_distance(const double time,
common::SpeedPoint* const speed_point);
bool FindLongitudinalDistance(const double time,
common::SpeedPoint* const speed_point);
bool calcualate_discretized_veh_loc();
bool CalculateDiscretizedVehicleLocation();
bool mapping_dynamic_obstacle_with_decision(const Obstacle& obstacle);
bool MapDynamicObstacleWithDecision(const Obstacle& obstacle);
bool mapping_static_obstacle_with_decision(const Obstacle& obstacle);
bool MapStaticObstacleWithDecision(const Obstacle& obstacle);
bool mapping_polygon(const std::vector<common::math::Vec2d>& corners,
const double buffer, const bool nudge_side,
std::vector<std::pair<double, double>>* const bound_map);
bool MapPolygon(const std::vector<common::math::Vec2d>& corners,
const double buffer, const bool nudge_side,
std::vector<std::pair<double, double>>* const bound_map);
// nudge_side > 0 update upper bound, nudge_side < 0 update lower_bound
// nudge_side == 0 out of bound
bool map_line(const common::SLPoint& start, const common::SLPoint& end,
const int nudge_side,
std::vector<std::pair<double, double>>* const constraint);
bool MapLine(const common::SLPoint& start, const common::SLPoint& end,
const int nudge_side,
std::vector<std::pair<double, double>>* const constraint);
std::pair<double, double> map_lateral_constraint(const common::SLPoint& start,
const common::SLPoint& end,
const int nudge_side,
const double s_start,
const double s_end);
std::pair<double, double> MapLateralConstraint(const common::SLPoint& start,
const common::SLPoint& end,
const int nudge_side,
const double s_start,
const double s_end);
std::pair<uint32_t, uint32_t> find_interval(const double start,
const double end) const;
std::pair<uint32_t, uint32_t> FindInterval(const double start,
const double end) const;
bool calculate_hd_map_bound();
bool CalculateHDMapBound();
bool calculate_static_obstacle_bound();
bool CalculateStaticObstacleBound();
bool calculate_dynamic_obstacle_bound();
bool CalculateDynamicObstacleBound();
bool get_bound(const double s,
const std::vector<std::pair<double, double>>& bound_map,
std::pair<double, double>* const bound) const;
bool GetBound(const double s,
const std::vector<std::pair<double, double>>& bound_map,
std::pair<double, double>* const bound) const;
uint32_t find_index(const double s) const;
uint32_t FindIndex(const double s) const;
void clear_data();
void Clear();
private:
const ReferenceLine* _reference_line = nullptr;
......
......@@ -15,7 +15,7 @@
*****************************************************************************/
/**
* @file qp_spline_path_optimizer.cpp
* @file qp_spline_path_optimizer.cc
**/
#include "modules/planning/optimizer/qp_spline_path/qp_spline_path_optimizer.h"
......
......@@ -18,8 +18,8 @@
* @file qp_path_optimizer.h
**/
#ifndef MODULES_PLANNING_OPTIMIZER_QP_SPLINE_PATH_OPTIMIZER_H_
#define MODULES_PLANNING_OPTIMIZER_QP_SPLINE_PATH_OPTIMIZER_H_
#ifndef MODULES_PLANNING_OPTIMIZER_QP_SPLINE_PATH_QP_SPLINE_PATH_OPTIMIZER_H_
#define MODULES_PLANNING_OPTIMIZER_QP_SPLINE_PATH_QP_SPLINE_PATH_OPTIMIZER_H_
#include <string>
......@@ -49,4 +49,4 @@ class QpSplinePathOptimizer : public PathOptimizer {
} // namespace planning
} // namespace apollo
#endif // MODULES_PLANNING_OPTIMIZER_SPLINE_QP_PATH_OPTIMIZER_H_
#endif // MODULES_PLANNING_OPTIMIZER_QP_SPLINE_PATH_QP_PATH_OPTIMIZER_H_
......@@ -94,4 +94,19 @@ cc_library(
],
)
cc_test(
name = "st_graph_boundary_test",
size = "small",
srcs = [
"st_graph_boundary_test.cc",
],
deps = [
":st_graph_boundary",
"//modules/common:log",
"//modules/common/time",
"//modules/common/util",
"@gtest//:main",
],
)
cpplint()
......@@ -88,6 +88,18 @@ bool StBoundaryMapper::CheckOverlap(const PathPoint& path_point,
Status StBoundaryMapper::GetSpeedLimits(
const ReferenceLine& reference_line, const PathData& path_data,
SpeedLimit* const speed_limit_data) const {
DCHECK_NOTNULL(speed_limit_data);
if (Double::compare(path_data.discretized_path().length(),
reference_line.length()) > 0) {
std::string msg = common::util::StrCat(
"path length [", path_data.discretized_path().length(),
"] should be LESS than reference_line length [",
reference_line.length(), "].");
AERROR << msg;
return Status(ErrorCode::PLANNING_ERROR, msg);
}
std::vector<double> speed_limits;
for (const auto& path_point : path_data.discretized_path().points()) {
// speed limit from reference line
......
......@@ -61,31 +61,31 @@ Vec2d StGraphBoundary::point(const uint32_t index) const {
const std::vector<Vec2d>& StGraphBoundary::points() const { return points_; }
StGraphBoundary::BoundaryType StGraphBoundary::boundary_type() const {
return _boundary_type;
return boundary_type_;
}
void StGraphBoundary::SetBoundaryType(const BoundaryType& boundary_type) {
_boundary_type = boundary_type;
boundary_type_ = boundary_type;
}
const std::string& StGraphBoundary::id() const { return _id; }
const std::string& StGraphBoundary::id() const { return id_; }
void StGraphBoundary::set_id(const std::string& id) { _id = id; }
void StGraphBoundary::set_id(const std::string& id) { id_ = id; }
double StGraphBoundary::characteristic_length() const {
return _characteristic_length;
return characteristic_length_;
}
void StGraphBoundary::SetCharacteristicLength(
const double characteristic_length) {
_characteristic_length = characteristic_length;
characteristic_length_ = characteristic_length;
}
bool StGraphBoundary::GetUnblockSRange(const double curr_time, double* s_upper,
double* s_lower) const {
const common::math::LineSegment2d segment = {Vec2d(curr_time, 0.0),
Vec2d(curr_time, _s_high_limit)};
*s_upper = _s_high_limit;
Vec2d(curr_time, s_high_limit_)};
*s_upper = s_high_limit_;
*s_lower = 0.0;
Vec2d p_s_first;
Vec2d p_s_second;
......@@ -95,17 +95,17 @@ bool StGraphBoundary::GetUnblockSRange(const double curr_time, double* s_upper,
<< "] is out of the coverage scope of the boundary.";
return false;
}
if (_boundary_type == BoundaryType::STOP ||
_boundary_type == BoundaryType::YIELD ||
_boundary_type == BoundaryType::FOLLOW ||
_boundary_type == BoundaryType::UNKNOWN) {
if (boundary_type_ == BoundaryType::STOP ||
boundary_type_ == BoundaryType::YIELD ||
boundary_type_ == BoundaryType::FOLLOW ||
boundary_type_ == BoundaryType::UNKNOWN) {
*s_upper = std::fmin(*s_upper, std::fmin(p_s_first.y(), p_s_second.y()));
} else if (_boundary_type == BoundaryType::OVERTAKE) {
} else if (boundary_type_ == BoundaryType::OVERTAKE) {
// overtake
*s_lower = std::fmax(*s_lower, std::fmax(p_s_first.y(), p_s_second.y()));
} else {
AERROR << "boundary_type is not supported. boundary_type: "
<< static_cast<int>(_boundary_type);
<< static_cast<int>(boundary_type_);
return false;
}
return true;
......@@ -114,8 +114,8 @@ bool StGraphBoundary::GetUnblockSRange(const double curr_time, double* s_upper,
bool StGraphBoundary::GetBoundarySRange(const double curr_time, double* s_upper,
double* s_lower) const {
const common::math::LineSegment2d segment = {Vec2d(curr_time, 0.0),
Vec2d(curr_time, _s_high_limit)};
*s_upper = _s_high_limit;
Vec2d(curr_time, s_high_limit_)};
*s_upper = s_high_limit_;
*s_lower = 0.0;
Vec2d p_s_first;
......
......@@ -44,7 +44,10 @@ class StGraphBoundary : public common::math::Polygon2d {
OVERTAKE,
};
// boundary points go counter clockwise.
explicit StGraphBoundary(const std::vector<STPoint>& points);
// boundary points go counter clockwise.
explicit StGraphBoundary(const std::vector<common::math::Vec2d>& points);
~StGraphBoundary() = default;
......@@ -72,10 +75,10 @@ class StGraphBoundary : public common::math::Polygon2d {
void GetBoundaryTimeScope(double* start_t, double* end_t) const;
private:
BoundaryType _boundary_type = BoundaryType::UNKNOWN;
std::string _id;
double _characteristic_length = 1.0;
double _s_high_limit = 200.0;
BoundaryType boundary_type_ = BoundaryType::UNKNOWN;
std::string id_;
double characteristic_length_ = 1.0;
double s_high_limit_ = 200.0;
};
} // namespace planning
......
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/planning/optimizer/st_graph/st_graph_boundary.h"
#include <algorithm>
#include <cmath>
#include <iostream>
#include "gmock/gmock.h"
#include "gtest/gtest.h"
#include "ros/include/ros/ros.h"
#include "modules/common/log.h"
namespace apollo {
namespace planning {
TEST(StGraphBoundaryTest, basic_test) {
std::vector<STPoint> st_points;
st_points.emplace_back(0.0, 0.0);
st_points.emplace_back(0.0, 10.0);
st_points.emplace_back(5.0, 10.0);
st_points.emplace_back(5.0, 0.0);
StGraphBoundary boundary(st_points);
EXPECT_EQ(boundary.id(), "");
EXPECT_EQ(boundary.boundary_type(), StGraphBoundary::BoundaryType::UNKNOWN);
double left_t = 0.0;
double right_t = 0.0;
boundary.GetBoundaryTimeScope(&left_t, &right_t);
EXPECT_DOUBLE_EQ(left_t, 0.0);
EXPECT_DOUBLE_EQ(right_t, 10.0);
}
} // namespace planning
} // namespace apollo
int main(int argc, char** argv) {
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册