提交 a51b34d7 编写于 作者: D Dong Li 提交者: Jiaming Tao

remove data_center dp_poly_path optimizer (#147)

上级 3929f2dd
......@@ -51,7 +51,7 @@ cc_library(
"prediction_trajectory.h",
],
deps = [
"//modules/common/proto:path_point_proto",
":discretized_trajectory",
"//modules/common/proto:path_point_proto",
],
)
......@@ -17,11 +17,12 @@ cc_library(
"trajectory_cost.h",
],
deps = [
"//modules/common/configs:vehicle_config_helper",
"//modules/common/math",
"//modules/map/proto:map_proto",
"//modules/planning/common:data_center",
"//modules/planning/common:decision_data",
"//modules/planning/common:obstacle",
"//modules/planning/common:planning_gflags",
"//modules/planning/common/path",
"//modules/planning/common/path:discretized_path",
"//modules/planning/common/path:frenet_frame_path",
......
......@@ -20,33 +20,30 @@
#include "modules/planning/optimizer/dp_poly_path/dp_road_graph.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/log.h"
#include "modules/common/proto/error_code.pb.h"
#include "modules/common/proto/path_point.pb.h"
#include "modules/planning/common/path/frenet_frame_path.h"
#include "modules/planning/math/curve1d/quintic_polynomial_curve1d.h"
#include "modules/planning/math/sl_analytic_transformation.h"
#include "modules/planning/math/double.h"
#include "modules/planning/math/sl_analytic_transformation.h"
#include "modules/planning/math/sl_analytic_transformation.h"
#include "modules/planning/optimizer/dp_poly_path/path_sampler.h"
#include "modules/planning/optimizer/dp_poly_path/trajectory_cost.h"
#include "modules/common/proto/path_point.pb.h"
#include "modules/common/proto/error_code.pb.h"
#include "modules/common/log.h"
#include "modules/planning/math/sl_analytic_transformation.h"
namespace apollo {
namespace planning {
DpRoadGraph::DpRoadGraph(
const DpPolyPathConfig &config,
const ::apollo::common::TrajectoryPoint &init_point,
const SpeedData& speed_data) :
_config(config),
_init_point(init_point),
_heuristic_speed_data(speed_data){
}
DpRoadGraph::DpRoadGraph(const DpPolyPathConfig &config,
const ::apollo::common::TrajectoryPoint &init_point,
const SpeedData &speed_data)
: _config(config),
_init_point(init_point),
_heuristic_speed_data(speed_data) {}
::apollo::common::ErrorCode DpRoadGraph::find_tunnel(
const DataCenter &data_center,
const ReferenceLine &reference_line,
DecisionData *const decision_data,
const ReferenceLine &reference_line, DecisionData *const decision_data,
PathData *const path_data) {
CHECK_NOTNULL(path_data);
::apollo::common::ErrorCode ret = ::apollo::common::ErrorCode::PLANNING_OK;
......@@ -54,12 +51,13 @@ DpRoadGraph::DpRoadGraph(
AERROR << "Fail to init dp road graph!";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
}
if (generate_graph(reference_line) != ::apollo::common::ErrorCode::PLANNING_OK) {
if (generate_graph(reference_line) !=
::apollo::common::ErrorCode::PLANNING_OK) {
AERROR << "Fail to generate graph!";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
}
std::vector<size_t> min_cost_edges;
if (find_best_trajectory(data_center, reference_line, *decision_data, &min_cost_edges) !=
if (find_best_trajectory(reference_line, *decision_data, &min_cost_edges) !=
::apollo::common::ErrorCode::PLANNING_OK) {
AERROR << "Fail to find best trajectory!";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
......@@ -71,7 +69,7 @@ DpRoadGraph::DpRoadGraph(
for (size_t i = 0; i < min_cost_edges.size(); ++i) {
GraphEdge edge = _edges[min_cost_edges[i]];
GraphVertex end_vertex = _vertices[edge.to_vertex()];
double step = 0.1; // TODO: get from config.
double step = 0.1; // TODO: get from config.
double current_s = step;
while (Double::compare(current_s, end_vertex.frame_point().s()) < 0.0) {
current_s += step;
......@@ -101,19 +99,22 @@ DpRoadGraph::DpRoadGraph(
if (!reference_line.get_point_in_Cartesian_frame(sl_point, &xy_point)) {
AERROR << "Fail to convert sl point to xy point";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
}
ReferencePoint ref_point = reference_line.get_reference_point(frenet_point.s());
ReferencePoint ref_point =
reference_line.get_reference_point(frenet_point.s());
double theta = SLAnalyticTransformation::calculate_theta(
ref_point.heading(), ref_point.kappa(), frenet_point.l(), frenet_point.dl());
//TODO comment out unused variable
//double kappa = SLAnalyticTransformation::calculate_kappa(ref_point.kappa(),
ref_point.heading(), ref_point.kappa(), frenet_point.l(),
frenet_point.dl());
// TODO comment out unused variable
// double kappa =
// SLAnalyticTransformation::calculate_kappa(ref_point.kappa(),
// ref_point.dkappa(),
// frenet_point.l(),
// frenet_point.dl(),
// frenet_point.ddl());
::apollo::common::PathPoint path_point;//(xy_point, theta, kappa, 0.0, 0.0, 0.0);
::apollo::common::PathPoint
path_point; //(xy_point, theta, kappa, 0.0, 0.0, 0.0);
path_point.set_x(xy_point[0]);
path_point.set_y(xy_point[1]);
path_point.set_theta(theta);
......@@ -134,25 +135,29 @@ DpRoadGraph::DpRoadGraph(
return ret;
}
::apollo::common::ErrorCode DpRoadGraph::init(const ReferenceLine &reference_line) {
::apollo::common::ErrorCode DpRoadGraph::init(
const ReferenceLine &reference_line) {
_vertices.clear();
_edges.clear();
Eigen::Vector2d xy_point(_init_point.path_point().x(), _init_point.path_point().y());
Eigen::Vector2d xy_point(_init_point.path_point().x(),
_init_point.path_point().y());
if (!reference_line.get_point_in_Frenet_frame(xy_point, &_init_sl_point)) {
AERROR << "Fail to map init point to sl coordinate!";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
}
ReferencePoint reference_point = reference_line.get_reference_point(_init_sl_point.s());
ReferencePoint reference_point =
reference_line.get_reference_point(_init_sl_point.s());
double init_dl = SLAnalyticTransformation().calculate_lateral_derivative(
reference_point.heading(), _init_point.path_point().theta(),
_init_sl_point.l(), reference_point.kappa());
double init_ddl = SLAnalyticTransformation().calculate_second_order_lateral_derivative(
reference_point.heading(), _init_point.path_point().theta(),
reference_point.kappa(), _init_point.path_point().kappa(),
reference_point.dkappa(), _init_sl_point.l());
double init_ddl =
SLAnalyticTransformation().calculate_second_order_lateral_derivative(
reference_point.heading(), _init_point.path_point().theta(),
reference_point.kappa(), _init_point.path_point().kappa(),
reference_point.dkappa(), _init_sl_point.l());
::apollo::common::FrenetFramePoint init_frenet_frame_point;
init_frenet_frame_point.set_s(_init_sl_point.s());
init_frenet_frame_point.set_l(_init_sl_point.l());
......@@ -165,11 +170,13 @@ DpRoadGraph::DpRoadGraph(
return ::apollo::common::ErrorCode::PLANNING_OK;
}
::apollo::common::ErrorCode DpRoadGraph::generate_graph(const ReferenceLine &reference_line) {
::apollo::common::ErrorCode DpRoadGraph::generate_graph(
const ReferenceLine &reference_line) {
::apollo::common::ErrorCode ret = ::apollo::common::ErrorCode::PLANNING_OK;
std::vector<std::vector<::apollo::common::SLPoint>> points;
PathSampler path_sampler(_config);
ret = path_sampler.sample(reference_line, _init_point, _init_sl_point, &points);
ret =
path_sampler.sample(reference_line, _init_point, _init_sl_point, &points);
if (ret != ::apollo::common::ErrorCode::PLANNING_OK) {
AERROR << "Fail to sampling point with path sampler!";
return ::apollo::common::ErrorCode::PLANNING_ERROR_FAILED;
......@@ -180,7 +187,8 @@ DpRoadGraph::DpRoadGraph(
size_t accumulated_index = 0;
for (size_t i = 0; i < points.size(); ++i) {
int vertex_num_current_level = 0;
ReferencePoint reference_point = reference_line.get_reference_point(points[i][0].s());
ReferencePoint reference_point =
reference_line.get_reference_point(points[i][0].s());
for (size_t j = 0; j < points[i].size(); ++j) {
if (!add_vertex(points[i][j], reference_point, i + 1)) {
continue;
......@@ -189,7 +197,8 @@ DpRoadGraph::DpRoadGraph(
for (int n = 0; n < vertex_num_previous_level; ++n) {
const size_t index_start = accumulated_prev_level_size + n;
const size_t index_end = accumulated_prev_level_size +
vertex_num_previous_level + vertex_num_current_level;
vertex_num_previous_level +
vertex_num_current_level;
if (connect_vertex(index_start, index_end)) {
is_connected = true;
}
......@@ -214,9 +223,7 @@ DpRoadGraph::DpRoadGraph(
}
::apollo::common::ErrorCode DpRoadGraph::find_best_trajectory(
const DataCenter &data_center,
const ReferenceLine &reference_line,
const DecisionData &decision_data,
const ReferenceLine &reference_line, const DecisionData &decision_data,
std::vector<size_t> *const min_cost_edges) {
CHECK_NOTNULL(min_cost_edges);
std::unordered_map<size_t, size_t> vertex_connect_table;
......@@ -226,31 +233,35 @@ DpRoadGraph::DpRoadGraph(
double min_trajectory_cost = std::numeric_limits<double>::max();
TrajectoryCost trajectory_cost(_config, _heuristic_speed_data, decision_data);
const auto *vehicle_config = common::config::VehicleConfigHelper::instance();
const double vehicle_length =
vehicle_config->GetConfig().vehicle_param().length();
const double vehicle_width =
vehicle_config->GetConfig().vehicle_param().length();
for (size_t i = 0; i < _vertices.size(); ++i) {
const GraphVertex &vertex = _vertices[i];
const std::vector<size_t> edges = vertex.edges_out();
for (size_t j = 0; j < edges.size(); ++j) {
double start_s = vertex.frame_point().s();
double end_s = _vertices[_edges[j].to_vertex()].frame_point().s();
double cost = trajectory_cost.calculate(
_edges[j].poly_path(), start_s, end_s,
4.933, //TODO length change to vehicle_config
2.11, //TODO width change to vehicle_config
reference_line);
double cost = trajectory_cost.calculate(_edges[j].poly_path(), start_s,
end_s, vehicle_length,
vehicle_width, reference_line);
GraphVertex &vertex_end = _vertices[_edges[j].to_vertex()];
if (vertex_connect_table.find(vertex_end.index()) == vertex_connect_table.end()) {
if (vertex_connect_table.find(vertex_end.index()) ==
vertex_connect_table.end()) {
vertex_end.set_accumulated_cost(vertex.accumulated_cost() + cost);
vertex_connect_table[vertex_end.index()] = vertex.index();
} else {
if (Double::compare(
vertex.accumulated_cost() + cost, vertex_end.accumulated_cost()) < 0) {
if (Double::compare(vertex.accumulated_cost() + cost,
vertex_end.accumulated_cost()) < 0) {
vertex_end.set_accumulated_cost(vertex.accumulated_cost() + cost);
vertex_connect_table[vertex_end.index()] = vertex.index();
}
}
}
if (vertex.is_dead_end()
&& Double::compare(vertex.accumulated_cost(), min_trajectory_cost) <= 0) {
if (vertex.is_dead_end() &&
Double::compare(vertex.accumulated_cost(), min_trajectory_cost) <= 0) {
best_trajectory_end_index = vertex.index();
min_trajectory_cost = vertex.accumulated_cost();
}
......@@ -265,7 +276,8 @@ DpRoadGraph::DpRoadGraph(
}
bool DpRoadGraph::add_vertex(const ::apollo::common::SLPoint &sl_point,
const ReferencePoint &reference_point, const size_t level) {
const ReferencePoint &reference_point,
const size_t level) {
double kappa = reference_point.kappa();
double kappa_range_upper = 0.23;
double kappa_range_lower = -kappa_range_upper;
......@@ -275,7 +287,7 @@ bool DpRoadGraph::add_vertex(const ::apollo::common::SLPoint &sl_point,
} else {
kappa = kappa / (1 - kappa * sl_point.l());
if (kappa < kappa_range_lower || kappa > kappa_range_upper) {
//Invalid sample point
// Invalid sample point
return false;
}
kappa = std::max(kappa_range_lower, kappa);
......@@ -296,8 +308,9 @@ bool DpRoadGraph::connect_vertex(const size_t start, const size_t end) {
GraphVertex &v_start = _vertices[start];
GraphVertex &v_end = _vertices[end];
QuinticPolynomialCurve1d curve(
v_start.frame_point().l(), v_start.frame_point().dl(), v_start.frame_point().ddl(),
v_end.frame_point().l(), v_end.frame_point().dl(), v_end.frame_point().ddl(),
v_start.frame_point().l(), v_start.frame_point().dl(),
v_start.frame_point().ddl(), v_end.frame_point().l(),
v_end.frame_point().dl(), v_end.frame_point().ddl(),
v_end.frame_point().s() - v_start.frame_point().s());
v_start.add_out_vertex(end);
v_start.add_out_edge(_edges.size());
......
......@@ -24,7 +24,6 @@
#include <vector>
#include "modules/common/proto/error_code.pb.h"
#include "modules/common/proto/path_point.pb.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/decision_data.h"
#include "modules/planning/common/path/path_data.h"
#include "modules/planning/common/speed/speed_data.h"
......@@ -44,8 +43,7 @@ class DpRoadGraph {
const ::apollo::common::TrajectoryPoint &init_point,
const SpeedData &speed_data);
~DpRoadGraph() = default;
::apollo::common::ErrorCode find_tunnel(const DataCenter &data_center,
const ReferenceLine &reference_line,
::apollo::common::ErrorCode find_tunnel(const ReferenceLine &reference_line,
DecisionData *const decision_data,
PathData *const path_data);
......@@ -54,8 +52,7 @@ class DpRoadGraph {
::apollo::common::ErrorCode generate_graph(
const ReferenceLine &reference_line);
::apollo::common::ErrorCode find_best_trajectory(
const DataCenter &data_center, const ReferenceLine &reference_line,
const DecisionData &decision_data,
const ReferenceLine &reference_line, const DecisionData &decision_data,
std::vector<size_t> *const min_cost_edges);
bool add_vertex(const ::apollo::common::SLPoint &sl_point,
const ReferencePoint &reference_point, const size_t level);
......
......@@ -23,7 +23,6 @@
#include "modules/common/proto/error_code.pb.h"
#include "modules/common/proto/path_point.pb.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/proto/dp_poly_path_config.pb.h"
#include "modules/planning/reference_line/reference_line.h"
......
......@@ -38,15 +38,13 @@ bool DpPolyPathOptimizer::SetConfig(const std::string &config_file) {
}
::apollo::common::ErrorCode DpPolyPathOptimizer::optimize(
const DataCenter &data_center, const SpeedData &speed_data,
const ReferenceLine &reference_line,
const SpeedData &speed_data, const ReferenceLine &reference_line,
const ::apollo::planning::TrajectoryPoint &init_point,
DecisionData *const decision_data, PathData *const path_data) const {
CHECK_NOTNULL(decision_data);
CHECK_NOTNULL(path_data);
DpRoadGraph dp_road_graph(config_, init_point, speed_data);
dp_road_graph.find_tunnel(data_center, reference_line, decision_data,
path_data);
dp_road_graph.find_tunnel(reference_line, decision_data, path_data);
return ::apollo::common::ErrorCode::PLANNING_OK;
}
......
......@@ -32,8 +32,7 @@ class DpPolyPathOptimizer : public PathOptimizer {
explicit DpPolyPathOptimizer(const std::string &name);
bool SetConfig(const std::string &config_file) override;
virtual ::apollo::common::ErrorCode optimize(
const DataCenter &data_center, const SpeedData &speed_data,
const ReferenceLine &reference_line,
const SpeedData &speed_data, const ReferenceLine &reference_line,
const ::apollo::planning::TrajectoryPoint &init_point,
DecisionData *const decision_data,
PathData *const path_data) const override;
......
......@@ -23,7 +23,6 @@
#include "common/speed/st_point.h"
#include "math/double.h"
#include "util/data_center.h"
namespace apollo {
namespace planning {
......
......@@ -23,10 +23,7 @@
namespace apollo {
namespace planning {
PathOptimizer::PathOptimizer(const std::string &name) : Optimizer(name) {
}
PathOptimizer::PathOptimizer(const std::string &name) : Optimizer(name) {}
} // namespace planning
} // namespace adu
......@@ -25,7 +25,6 @@
#include "modules/common/proto/error_code.pb.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/decision_data.h"
#include "modules/planning/common/path/path_data.h"
#include "modules/planning/common/speed/speed_data.h"
......@@ -39,8 +38,7 @@ class PathOptimizer : public Optimizer {
explicit PathOptimizer(const std::string &name);
virtual ~PathOptimizer() = default;
virtual apollo::common::ErrorCode optimize(
const DataCenter &data_center, const SpeedData &speed_data,
const ReferenceLine &reference_line,
const SpeedData &speed_data, const ReferenceLine &reference_line,
const ::apollo::planning::TrajectoryPoint &init_point,
DecisionData *const decision_data, PathData *const path_data) const = 0;
};
......
......@@ -44,9 +44,9 @@ QpSplineStBoundaryMapper::QpSplineStBoundaryMapper(
: StBoundaryMapper(st_boundary_config, veh_param) {}
ErrorCode QpSplineStBoundaryMapper::get_graph_boundary(
const DataCenter& data_center, const DecisionData& decision_data,
const PathData& path_data, const double planning_distance,
const double planning_time,
const common::TrajectoryPoint& initial_planning_point,
const DecisionData& decision_data, const PathData& path_data,
const double planning_distance, const double planning_time,
std::vector<STGraphBoundary>* const obs_boundary) const {
if (planning_time < 0.0) {
AERROR << "Fail to get params because planning_time < 0.";
......@@ -82,9 +82,10 @@ ErrorCode QpSplineStBoundaryMapper::get_graph_boundary(
if (dynamic_obs_vec[i] == nullptr) {
continue;
}
if (map_obstacle_with_trajectory(
data_center, *dynamic_obs_vec[i], path_data, planning_distance,
planning_time, obs_boundary) != ErrorCode::PLANNING_OK) {
if (map_obstacle_with_trajectory(initial_planning_point,
*dynamic_obs_vec[i], path_data,
planning_distance, planning_time,
obs_boundary) != ErrorCode::PLANNING_OK) {
AERROR << "Fail to map dynamic obstacle with id "
<< dynamic_obs_vec[i]->Id();
return ErrorCode::PLANNING_ERROR_FAILED;
......@@ -95,9 +96,9 @@ ErrorCode QpSplineStBoundaryMapper::get_graph_boundary(
}
ErrorCode QpSplineStBoundaryMapper::map_obstacle_with_trajectory(
const DataCenter& data_center, const Obstacle& obstacle,
const PathData& path_data, const double planning_distance,
const double planning_time,
const common::TrajectoryPoint& init_planning_point,
const Obstacle& obstacle, const PathData& path_data,
const double planning_distance, const double planning_time,
std::vector<STGraphBoundary>* const boundary) const {
std::vector<STPoint> boundary_points;
// lower and upper bound for st boundary
......@@ -233,14 +234,8 @@ ErrorCode QpSplineStBoundaryMapper::map_obstacle_with_trajectory(
double control_throttle_release_time = 0.1;
double control_brake_full_time = 0.2;
double t_delay = compute_delay_time + control_cmd_delay_time;
const double init_acc = data_center.current_frame()
->planning_data()
.init_planning_point()
.a();
const double init_speed = data_center.current_frame()
->planning_data()
.init_planning_point()
.v();
const double init_acc = init_planning_point.a();
const double init_speed = init_planning_point.v();
if (init_acc > 0.3) {
t_delay += control_throttle_release_time;
}
......
......@@ -27,7 +27,6 @@
#include "modules/common/proto/error_code.pb.h"
#include "modules/planning/proto/st_boundary_config.pb.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/decision_data.h"
namespace apollo {
......@@ -41,16 +40,16 @@ class QpSplineStBoundaryMapper : public StBoundaryMapper {
// TODO: combine two interfaces together to provide a st graph data type
virtual common::ErrorCode get_graph_boundary(
const DataCenter& data_center, const DecisionData& decision_data,
const PathData& path_data, const double planning_distance,
const double planning_time,
const common::TrajectoryPoint& initial_planning_point,
const DecisionData& decision_data, const PathData& path_data,
const double planning_distance, const double planning_time,
std::vector<STGraphBoundary>* const boundary) const override;
private:
common::ErrorCode map_obstacle_with_trajectory(
const DataCenter& data_center, const Obstacle& obstacle,
const PathData& path_data, const double planning_distance,
const double planning_time,
const common::TrajectoryPoint& initial_planning_point,
const Obstacle& obstacle, const PathData& path_data,
const double planning_distance, const double planning_time,
std::vector<STGraphBoundary>* const boundary) const;
common::ErrorCode map_obstacle_without_trajectory(
......
......@@ -24,8 +24,6 @@
#include "modules/planning/optimizer/optimizer.h"
#include "modules/common/proto/error_code.pb.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/decision_data.h"
#include "modules/planning/common/path/path_data.h"
#include "modules/planning/common/planning_data.h"
......@@ -38,8 +36,7 @@ class SpeedOptimizer : public Optimizer {
public:
explicit SpeedOptimizer(const std::string& name);
virtual ~SpeedOptimizer() = default;
virtual common::ErrorCode optimize(const DataCenter& data_center,
const PathData& path_data,
virtual common::ErrorCode optimize(const PathData& path_data,
const TrajectoryPoint& init_point,
DecisionData* const decision_data,
SpeedData* const speed_data) const = 0;
......
......@@ -60,12 +60,17 @@ cc_library(
"//modules/common/proto:path_point_proto",
"//modules/map/hdmap",
"//modules/map/proto:map_proto",
"//modules/planning/common:data_center",
"//modules/planning/common:decision_data",
"//modules/planning/common:map_object",
"//modules/planning/common:obstacle",
"//modules/planning/common:planning_gflags",
"//modules/planning/common:planning_object",
"//modules/planning/common:speed_limit",
"//modules/planning/common/path:discretized_path",
"//modules/planning/common/path:frenet_frame_path",
"//modules/planning/common/path:path_data",
"//modules/planning/common/trajectory:discretized_trajectory",
"//modules/planning/common/trajectory:prediction_trajectory",
"//modules/planning/math:double",
"//modules/planning/proto:planning_proto",
"//modules/planning/reference_line",
......
......@@ -24,7 +24,6 @@
#include "modules/common/math/line_segment2d.h"
#include "modules/common/math/vec2d.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/planning_gflags.h"
#include "modules/planning/math/double.h"
......
......@@ -27,7 +27,6 @@
#include "modules/planning/proto/st_boundary_config.pb.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/planning/common/data_center.h"
#include "modules/planning/common/decision_data.h"
#include "modules/planning/common/path/path_data.h"
#include "modules/planning/common/speed_limit.h"
......@@ -46,9 +45,9 @@ class StBoundaryMapper {
virtual ~StBoundaryMapper() = default;
virtual common::ErrorCode get_graph_boundary(
const DataCenter& data_center, const DecisionData& decision_data,
const PathData& path_data, const double planning_distance,
const double planning_time,
const common::TrajectoryPoint& initial_planning_point,
const DecisionData& decision_data, const PathData& path_data,
const double planning_distance, const double planning_time,
std::vector<STGraphBoundary>* const boundary) const = 0;
virtual common::ErrorCode get_speed_limits(
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册