Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
8097baaa
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
8097baaa
编写于
9月 12, 2018
作者:
L
Liangliang Zhang
提交者:
Jiaming Tao
9月 12, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Planning: removed adapter in frame. (#74)
上级
ccdc6f9d
变更
10
隐藏空白更改
内联
并排
Showing
10 changed file
with
153 addition
and
113 deletion
+153
-113
modules/planning/common/BUILD
modules/planning/common/BUILD
+61
-47
modules/planning/common/frame.cc
modules/planning/common/frame.cc
+23
-29
modules/planning/common/frame.h
modules/planning/common/frame.h
+5
-2
modules/planning/common/frame_open_space.cc
modules/planning/common/frame_open_space.cc
+9
-9
modules/planning/common/frame_open_space.h
modules/planning/common/frame_open_space.h
+1
-1
modules/planning/common/planning_context.cc
modules/planning/common/planning_context.cc
+4
-7
modules/planning/common/planning_context.h
modules/planning/common/planning_context.h
+2
-2
modules/planning/common/planning_data.h
modules/planning/common/planning_data.h
+46
-0
modules/planning/common/reference_line_info.cc
modules/planning/common/reference_line_info.cc
+1
-2
modules/planning/planning_base.h
modules/planning/planning_base.h
+1
-14
未找到文件。
modules/planning/common/BUILD
浏览文件 @
8097baaa
...
...
@@ -136,6 +136,7 @@ cc_library(
],
deps
=
[
":planning_gflags"
,
"//modules/common:macro"
,
"//modules/common:log"
,
"//modules/planning/proto:planning_proto"
,
"//modules/planning/proto:planning_status_proto"
,
...
...
@@ -271,49 +272,35 @@ cc_library(
)
cc_library
(
name
=
"frame"
,
srcs
=
[
"frame.cc"
,
],
name
=
"planning_data"
,
hdrs
=
[
"
frame
.h"
,
"
planning_data
.h"
,
],
deps
=
[
":change_lane_decider"
,
":indexed_queue"
,
":lag_prediction"
,
":obstacle"
,
":reference_line_info"
,
"//modules/common:log"
,
"//modules/common/configs:vehicle_config_helper"
,
"//modules/common/monitor_log"
,
"//modules/common/vehicle_state:vehicle_state_provider"
,
"//modules/map/hdmap:hdmap_util"
,
"//modules/map/pnc_map"
,
"//modules/planning/common/trajectory:discretized_trajectory"
,
"//modules/planning/common/trajectory:publishable_trajectory"
,
"//modules/planning/proto:planning_config_proto"
,
"//modules/localization/proto:localization_proto"
,
"//modules/perception/proto:perception_proto"
,
"//modules/planning/proto:planning_proto"
,
"//modules/p
lanning/reference_line:reference_line_provider
"
,
"//modules/p
rediction/proto:prediction_proto
"
,
],
)
cc_library
(
name
=
"frame
_open_space
"
,
name
=
"frame"
,
srcs
=
[
"frame
_open_space
.cc"
,
"frame.cc"
,
],
hdrs
=
[
"frame
_open_space
.h"
,
"frame.h"
,
],
deps
=
[
":planning_data"
,
":change_lane_decider"
,
":indexed_queue"
,
":lag_prediction"
,
":obstacle"
,
"
//modules/common/configs:vehicle_config_helper
"
,
"
:reference_line_info
"
,
"//modules/common:log"
,
"//modules/common/
monitor_log
"
,
"//modules/common/
configs:vehicle_config_helper
"
,
"//modules/common/vehicle_state:vehicle_state_provider"
,
"//modules/map/hdmap:hdmap_util"
,
"//modules/map/pnc_map"
,
...
...
@@ -321,11 +308,38 @@ cc_library(
"//modules/planning/common/trajectory:publishable_trajectory"
,
"//modules/planning/proto:planning_config_proto"
,
"//modules/planning/proto:planning_proto"
,
"//modules/common/math:geometry"
,
"@eigen"
,
"//modules/planning/reference_line:reference_line_provider"
,
],
)
# cc_library(
# name = "frame_open_space",
# srcs = [
# "frame_open_space.cc",
# ],
# hdrs = [
# "frame_open_space.h",
# ],
# deps = [
# ":change_lane_decider",
# ":indexed_queue",
# ":lag_prediction",
# ":obstacle",
# "//modules/common/configs:vehicle_config_helper",
# "//modules/common:log",
# #"//modules/common/monitor_log",
# "//modules/common/vehicle_state:vehicle_state_provider",
# "//modules/map/hdmap:hdmap_util",
# "//modules/map/pnc_map",
# "//modules/planning/common/trajectory:discretized_trajectory",
# "//modules/planning/common/trajectory:publishable_trajectory",
# "//modules/planning/proto:planning_config_proto",
# "//modules/planning/proto:planning_proto",
# "//modules/common/math:geometry",
# "@eigen",
# ],
# )
cc_test
(
name
=
"frame_test"
,
size
=
"small"
,
...
...
@@ -344,25 +358,25 @@ cc_test(
],
)
cc_test
(
name
=
"frame_open_space_test"
,
size
=
"small"
,
srcs
=
[
"frame_open_space_test.cc"
,
],
data
=
[
"//modules/planning/common:common_testdata"
,
],
deps
=
[
":frame_open_space"
,
"//modules/common/proto:pnc_point_proto"
,
"//modules/common/util"
,
"//modules/common/vehicle_state/proto:vehicle_state_proto"
,
"//modules/planning/proto:planning_config_proto"
,
"@eigen"
,
"@gtest//:main"
,
],
)
#
cc_test(
#
name = "frame_open_space_test",
#
size = "small",
#
srcs = [
#
"frame_open_space_test.cc",
#
],
#
data = [
#
"//modules/planning/common:common_testdata",
#
],
#
deps = [
#
":frame_open_space",
#
"//modules/common/proto:pnc_point_proto",
#
"//modules/common/util",
#
"//modules/common/vehicle_state/proto:vehicle_state_proto",
#
"//modules/planning/proto:planning_config_proto",
#
"@eigen",
#
"@gtest//:main",
#
],
#
)
cc_library
(
name
=
"speed_limit"
,
...
...
@@ -428,7 +442,7 @@ cc_library(
deps
=
[
":ego_info"
,
":frame"
,
":frame_open_space"
,
#
":frame_open_space",
":planning_gflags"
,
":speed_limit"
,
"//modules/common:log"
,
...
...
modules/planning/common/frame.cc
浏览文件 @
8097baaa
...
...
@@ -29,7 +29,6 @@
#include "modules/routing/proto/routing.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/log.h"
#include "modules/common/math/vec2d.h"
...
...
@@ -45,10 +44,9 @@ namespace planning {
using
apollo
::
common
::
ErrorCode
;
using
apollo
::
common
::
Status
;
using
apollo
::
common
::
VehicleStateProvider
;
using
apollo
::
common
::
adapter
::
AdapterManager
;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
monitor
::
MonitorLogBuffer
;
//
using apollo::common::monitor::MonitorLogBuffer;
using
apollo
::
prediction
::
PredictionObstacles
;
constexpr
double
kMathEpsilon
=
1e-8
;
...
...
@@ -56,16 +54,17 @@ constexpr double kMathEpsilon = 1e-8;
FrameHistory
::
FrameHistory
()
:
IndexedQueue
<
uint32_t
,
Frame
>
(
FLAGS_max_history_frame_num
)
{}
Frame
::
Frame
(
uint32_t
sequence_num
,
Frame
::
Frame
(
uint32_t
sequence_num
,
const
PlanningData
&
planning_data
,
const
common
::
TrajectoryPoint
&
planning_start_point
,
const
double
start_time
,
const
common
::
VehicleState
&
vehicle_state
,
ReferenceLineProvider
*
reference_line_provider
)
:
sequence_num_
(
sequence_num
),
planning_data_
(
planning_data
),
planning_start_point_
(
planning_start_point
),
start_time_
(
start_time
),
vehicle_state_
(
vehicle_state
),
reference_line_provider_
(
reference_line_provider
)
,
monitor_logger_
(
common
::
monitor
::
MonitorMessageItem
::
PLANNING
)
{
reference_line_provider_
(
reference_line_provider
)
{
// monitor_logger_(common::monitor::MonitorMessageItem::PLANNING)
if
(
FLAGS_enable_lag_prediction
)
{
lag_predictor_
.
reset
(
new
LagPrediction
(
FLAGS_lag_prediction_min_appear_num
,
...
...
@@ -86,8 +85,7 @@ bool Frame::Rerouting() {
AERROR
<<
"Rerouting not supported in navigation mode"
;
return
false
;
}
auto
adapter_manager
=
AdapterManager
::
Instance
();
if
(
adapter_manager
->
GetRoutingResponse
()
->
Empty
())
{
if
(
planning_data_
.
routing
==
nullptr
)
{
AERROR
<<
"No previous routing available"
;
return
false
;
}
...
...
@@ -95,11 +93,10 @@ bool Frame::Rerouting() {
AERROR
<<
"Invalid HD Map."
;
return
false
;
}
auto
request
=
adapter_manager
->
GetRoutingResponse
()
->
GetLatestObserved
()
.
routing_request
();
auto
request
=
planning_data_
.
routing
->
routing_request
();
request
.
clear_header
();
AdapterManager
::
FillRoutingRequestHeader
(
"planning"
,
&
request
);
// AdapterManager::FillRoutingRequestHeader("planning", &request);
auto
point
=
common
::
util
::
MakePointENU
(
vehicle_state_
.
x
(),
vehicle_state_
.
y
(),
vehicle_state_
.
z
());
double
s
=
0.0
;
...
...
@@ -124,9 +121,9 @@ bool Frame::Rerouting() {
AERROR
<<
"Failed to find future waypoints"
;
return
false
;
}
AdapterManager
::
PublishRoutingRequest
(
request
);
apollo
::
common
::
monitor
::
MonitorLogBuffer
buffer
(
&
monitor_logger_
);
buffer
.
INFO
(
"Planning send Rerouting request"
);
//
AdapterManager::PublishRoutingRequest(request);
//
apollo::common::monitor::MonitorLogBuffer buffer(&monitor_logger_);
//
buffer.INFO("Planning send Rerouting request");
return
true
;
}
...
...
@@ -360,13 +357,12 @@ Status Frame::Init() {
<<
FLAGS_align_prediction_time
;
// prediction
if
(
AdapterManager
::
GetPrediction
()
&&
!
AdapterManager
::
GetPrediction
()
->
Empty
())
{
if
(
planning_data_
.
prediction_obstacles
==
nullptr
)
{
if
(
FLAGS_enable_lag_prediction
&&
lag_predictor_
)
{
lag_predictor_
->
GetLaggedPrediction
(
&
prediction_
);
lag_predictor_
->
GetLaggedPrediction
(
planning_data_
.
prediction_obstacles
.
get
());
}
else
{
prediction_
.
CopyFrom
(
AdapterManager
::
GetPrediction
()
->
GetLatestObserved
());
prediction_
.
CopyFrom
(
*
planning_data_
.
prediction_obstacles
);
}
if
(
FLAGS_align_prediction_time
)
{
AlignPredictionTime
(
vehicle_state_
.
timestamp
(),
&
prediction_
);
...
...
@@ -380,8 +376,8 @@ Status Frame::Init() {
if
(
collision_obstacle
)
{
std
::
string
err_str
=
"Found collision with obstacle: "
+
collision_obstacle
->
Id
();
apollo
::
common
::
monitor
::
MonitorLogBuffer
buffer
(
&
monitor_logger_
);
buffer
.
ERROR
(
err_str
);
//
apollo::common::monitor::MonitorLogBuffer buffer(&monitor_logger_);
//
buffer.ERROR(err_str);
return
Status
(
ErrorCode
::
PLANNING_ERROR
,
err_str
);
}
}
...
...
@@ -456,28 +452,26 @@ void Frame::RecordInputDebug(planning_internal::Debug *debug) {
}
auto
*
planning_debug_data
=
debug
->
mutable_planning_data
();
auto
*
adc_position
=
planning_debug_data
->
mutable_adc_position
();
const
auto
&
localization
=
AdapterManager
::
GetLocalization
()
->
GetLatestObserved
();
adc_position
->
CopyFrom
(
localization
);
adc_position
->
CopyFrom
(
*
planning_data_
.
localization_estimate
);
const
auto
&
chassis
=
AdapterManager
::
GetChassis
()
->
GetLatestObserved
();
auto
debug_chassis
=
planning_debug_data
->
mutable_chassis
();
debug_chassis
->
CopyFrom
(
chassis
);
debug_chassis
->
CopyFrom
(
*
planning_data_
.
chassis
);
if
(
!
FLAGS_use_navigation_mode
)
{
auto
debug_routing
=
planning_debug_data
->
mutable_routing
();
debug_routing
->
CopyFrom
(
AdapterManager
::
GetRoutingResponse
()
->
GetLatestObserved
());
debug_routing
->
CopyFrom
(
*
planning_data_
.
routing
);
}
planning_debug_data
->
mutable_prediction_header
()
->
CopyFrom
(
prediction_
.
header
());
/*
auto relative_map = AdapterManager::GetRelativeMap();
if (!relative_map->Empty()) {
planning_debug_data->mutable_relative_map()->mutable_header()->CopyFrom(
relative_map->GetLatestObserved().header());
}
*/
}
void
Frame
::
AlignPredictionTime
(
const
double
planning_start_time
,
...
...
modules/planning/common/frame.h
浏览文件 @
8097baaa
...
...
@@ -43,6 +43,7 @@
#include "modules/planning/common/indexed_queue.h"
#include "modules/planning/common/lag_prediction.h"
#include "modules/planning/common/obstacle.h"
#include "modules/planning/common/planning_data.h"
#include "modules/planning/common/reference_line_info.h"
#include "modules/planning/common/trajectory/publishable_trajectory.h"
#include "modules/planning/reference_line/reference_line_provider.h"
...
...
@@ -58,7 +59,7 @@ namespace planning {
class
Frame
{
public:
explicit
Frame
(
uint32_t
sequence_num
,
explicit
Frame
(
uint32_t
sequence_num
,
const
PlanningData
&
planning_data
,
const
common
::
TrajectoryPoint
&
planning_start_point
,
const
double
start_time
,
const
common
::
VehicleState
&
vehicle_state
,
...
...
@@ -140,6 +141,7 @@ class Frame {
private:
uint32_t
sequence_num_
=
0
;
const
PlanningData
planning_data_
;
const
hdmap
::
HDMap
*
hdmap_
=
nullptr
;
common
::
TrajectoryPoint
planning_start_point_
;
const
double
start_time_
=
0.0
;
...
...
@@ -158,7 +160,8 @@ class Frame {
ADCTrajectory
trajectory_
;
// last published trajectory
std
::
unique_ptr
<
LagPrediction
>
lag_predictor_
;
ReferenceLineProvider
*
reference_line_provider_
=
nullptr
;
apollo
::
common
::
monitor
::
MonitorLogger
monitor_logger_
;
// apollo::common::monitor::MonitorLogger monitor_logger_;
};
class
FrameHistory
:
public
IndexedQueue
<
uint32_t
,
Frame
>
{
...
...
modules/planning/common/frame_open_space.cc
浏览文件 @
8097baaa
...
...
@@ -45,7 +45,7 @@ using apollo::common::VehicleStateProvider;
using
apollo
::
common
::
adapter
::
AdapterManager
;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
monitor
::
MonitorLogBuffer
;
//
using apollo::common::monitor::MonitorLogBuffer;
using
apollo
::
prediction
::
PredictionObstacles
;
constexpr
double
kMathEpsilon
=
1e-8
;
...
...
@@ -60,12 +60,12 @@ FrameOpenSpace::FrameOpenSpace(
planning_start_point_
(
planning_start_point
),
start_time_
(
start_time
),
vehicle_state_
(
vehicle_state
),
monitor_logger_
(
common
::
monitor
::
MonitorMessageItem
::
PLANNING
)
{
if
(
FLAGS_enable_lag_prediction
)
{
lag_predictor_
.
reset
(
new
LagPrediction
(
FLAGS_lag_prediction_min_appear_num
,
FLAGS_lag_prediction_max_disappear_num
));
}
//
monitor_logger_(common::monitor::MonitorMessageItem::PLANNING) {
if
(
FLAGS_enable_lag_prediction
)
{
lag_predictor_
.
reset
(
new
LagPrediction
(
FLAGS_lag_prediction_min_appear_num
,
FLAGS_lag_prediction_max_disappear_num
));
}
}
const
common
::
TrajectoryPoint
&
FrameOpenSpace
::
PlanningStartPoint
()
const
{
...
...
@@ -111,8 +111,8 @@ Status FrameOpenSpace::Init() {
if
(
collision_obstacle
)
{
std
::
string
err_str
=
"Found collision with obstacle: "
+
collision_obstacle
->
Id
();
apollo
::
common
::
monitor
::
MonitorLogBuffer
buffer
(
&
monitor_logger_
);
buffer
.
ERROR
(
err_str
);
//
apollo::common::monitor::MonitorLogBuffer buffer(&monitor_logger_);
//
buffer.ERROR(err_str);
return
Status
(
ErrorCode
::
PLANNING_ERROR
,
err_str
);
}
}
...
...
modules/planning/common/frame_open_space.h
浏览文件 @
8097baaa
...
...
@@ -144,7 +144,7 @@ class FrameOpenSpace {
ChangeLaneDecider
change_lane_decider_
;
ADCTrajectory
trajectory_
;
// last published trajectory
std
::
unique_ptr
<
LagPrediction
>
lag_predictor_
;
apollo
::
common
::
monitor
::
MonitorLogger
monitor_logger_
;
//
apollo::common::monitor::MonitorLogger monitor_logger_;
std
::
size_t
obstacles_num_
=
0
;
Eigen
::
MatrixXd
obstacles_vertices_num_
;
...
...
modules/planning/common/planning_context.cc
浏览文件 @
8097baaa
...
...
@@ -16,21 +16,18 @@
#include "modules/planning/common/planning_context.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/planning/common/planning_gflags.h"
namespace
apollo
{
namespace
planning
{
using
common
::
adapter
::
AdapterManager
;
PlanningContext
::
PlanningContext
()
{}
void
DumpPlanningContext
()
{
AdapterManager
::
GetLocalization
()
->
DumpLatestMessage
();
AdapterManager
::
GetChassis
()
->
DumpLatestMessage
();
AdapterManager
::
GetRoutingResponse
()
->
DumpLatestMessage
();
AdapterManager
::
GetPrediction
()
->
DumpLatestMessage
();
//
AdapterManager::GetLocalization()->DumpLatestMessage();
//
AdapterManager::GetChassis()->DumpLatestMessage();
//
AdapterManager::GetRoutingResponse()->DumpLatestMessage();
//
AdapterManager::GetPrediction()->DumpLatestMessage();
}
void
PlanningContext
::
Clear
()
{
planning_status_
.
Clear
();
}
...
...
modules/planning/common/planning_context.h
浏览文件 @
8097baaa
...
...
@@ -23,12 +23,12 @@
#include <string>
#include "modules/common/macro.h"
#include "modules/common/proto/drive_state.pb.h"
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/planning/proto/planning_status.pb.h"
#include "modules/common/macro.h"
/**
* @brief PlanningContext is the runtime context in planning. It is
* persistant across multiple frames.
...
...
modules/planning/common/planning_data.h
0 → 100644
浏览文件 @
8097baaa
/******************************************************************************
* Copyright 2018 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.
*****************************************************************************/
#ifndef MODULES_PLANNING_COMMON_PLANNING_DATA_H_
#define MODULES_PLANNING_COMMON_PLANNING_DATA_H_
#include "modules/canbus/proto/chassis.pb.h"
#include "modules/localization/proto/localization.pb.h"
#include "modules/perception/proto/traffic_light_detection.pb.h"
#include "modules/prediction/proto/prediction_obstacle.pb.h"
#include "modules/routing/proto/routing.pb.h"
#
namespace
apollo
{
namespace
planning
{
/**
* @struct planning_data
* @brief PlanningData contains all necessary data as planning input
*/
struct
PlanningData
{
std
::
shared_ptr
<
prediction
::
PredictionObstacles
>
prediction_obstacles
;
std
::
shared_ptr
<
canbus
::
Chassis
>
chassis
;
std
::
shared_ptr
<
localization
::
LocalizationEstimate
>
localization_estimate
;
std
::
shared_ptr
<
perception
::
TrafficLightDetection
>
traffic_light
;
std
::
shared_ptr
<
routing
::
RoutingResponse
>
routing
;
};
}
// namespace planning
}
// namespace apollo
#endif // MODULES_PLANNING_COMMON_PLANNING_DATA_H_
modules/planning/common/reference_line_info.cc
浏览文件 @
8097baaa
...
...
@@ -26,7 +26,6 @@
#include "modules/planning/proto/sl_boundary.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/util/string_util.h"
#include "modules/common/util/thread_pool.h"
...
...
@@ -45,7 +44,7 @@ using apollo::common::SLPoint;
using
apollo
::
common
::
TrajectoryPoint
;
using
apollo
::
common
::
VehicleConfigHelper
;
using
apollo
::
common
::
VehicleSignal
;
using
apollo
::
common
::
adapter
::
AdapterManager
;
//
using apollo::common::adapter::AdapterManager;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
util
::
ThreadPool
;
...
...
modules/planning/planning_base.h
浏览文件 @
8097baaa
...
...
@@ -35,6 +35,7 @@
#include "modules/common/status/status.h"
#include "modules/common/vehicle_state/vehicle_state_provider.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/planning/common/planning_data.h"
#include "modules/planning/common/trajectory/publishable_trajectory.h"
#include "modules/planning/planner/planner.h"
#include "modules/planning/planner/planner_dispatcher.h"
...
...
@@ -45,20 +46,6 @@
*/
namespace
apollo
{
namespace
planning
{
/**
* @class planning_data
*
* @brief PlanningData contains all necessary data as planning input
*/
struct
PlanningData
{
std
::
shared_ptr
<
prediction
::
PredictionObstacles
>
prediction_obstacles
;
std
::
shared_ptr
<
canbus
::
Chassis
>
chassis
;
std
::
shared_ptr
<
localization
::
LocalizationEstimate
>
localization_estimate
;
std
::
shared_ptr
<
perception
::
TrafficLightDetection
>
traffic_light
;
std
::
shared_ptr
<
routing
::
RoutingResponse
>
routing
;
};
/**
* @class planning
*
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录