Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
10239e32
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,体验更适合开发者的 AI 搜索 >>
未验证
提交
10239e32
编写于
4月 17, 2018
作者:
S
siyangy
提交者:
GitHub
4月 17, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Dreamview: improve logging (#3922)
* Dreamview: improve logging * fix lint
上级
c019ba3d
变更
7
隐藏空白更改
内联
并排
Showing
7 changed file
with
27 addition
and
15 deletion
+27
-15
modules/dreamview/backend/dreamview.cc
modules/dreamview/backend/dreamview.cc
+3
-3
modules/dreamview/backend/handlers/websocket_handler.cc
modules/dreamview/backend/handlers/websocket_handler.cc
+12
-7
modules/dreamview/backend/handlers/websocket_handler.h
modules/dreamview/backend/handlers/websocket_handler.h
+4
-0
modules/dreamview/backend/handlers/websocket_handler_test.cc
modules/dreamview/backend/handlers/websocket_handler_test.cc
+1
-1
modules/dreamview/backend/simulation_world/simulation_world_service.cc
...view/backend/simulation_world/simulation_world_service.cc
+1
-1
modules/dreamview/backend/simulation_world/simulation_world_service.h
...mview/backend/simulation_world/simulation_world_service.h
+5
-3
modules/dreamview/backend/simulation_world/simulation_world_updater.cc
...view/backend/simulation_world/simulation_world_updater.cc
+1
-0
未找到文件。
modules/dreamview/backend/dreamview.cc
浏览文件 @
10239e32
...
...
@@ -106,9 +106,9 @@ Status Dreamview::Init() {
server_
.
reset
(
new
CivetServer
(
options
));
image_
.
reset
(
new
ImageHandler
());
websocket_
.
reset
(
new
WebSocketHandler
());
map_ws_
.
reset
(
new
WebSocketHandler
());
point_cloud_ws_
.
reset
(
new
WebSocketHandler
());
websocket_
.
reset
(
new
WebSocketHandler
(
"SimWorld"
));
map_ws_
.
reset
(
new
WebSocketHandler
(
"Map"
));
point_cloud_ws_
.
reset
(
new
WebSocketHandler
(
"PointCloud"
));
map_service_
.
reset
(
new
MapService
());
sim_control_
.
reset
(
new
SimControl
(
map_service_
.
get
()));
...
...
modules/dreamview/backend/handlers/websocket_handler.cc
浏览文件 @
10239e32
...
...
@@ -34,7 +34,8 @@ void WebSocketHandler::handleReadyState(CivetServer *server, Connection *conn) {
{
std
::
unique_lock
<
std
::
mutex
>
lock
(
mutex_
);
connections_
.
emplace
(
conn
,
std
::
make_shared
<
std
::
mutex
>
());
AINFO
<<
"Accepted connection. Total connections: "
<<
connections_
.
size
();
AINFO
<<
name_
<<
": Accepted connection. Total connections: "
<<
connections_
.
size
();
}
// Trigger registered new connection handlers.
...
...
@@ -56,7 +57,8 @@ void WebSocketHandler::handleClose(CivetServer *server,
std
::
unique_lock
<
std
::
mutex
>
lock
(
*
connection_lock
);
connections_
.
erase
(
connection
);
}
AINFO
<<
"Connection closed. Total connections: "
<<
connections_
.
size
();
AINFO
<<
name_
<<
": Connection closed. Total connections: "
<<
connections_
.
size
();
}
}
...
...
@@ -94,7 +96,8 @@ bool WebSocketHandler::SendData(Connection *conn, const std::string &data,
{
std
::
unique_lock
<
std
::
mutex
>
lock
(
mutex_
);
if
(
!
ContainsKey
(
connections_
,
conn
))
{
AERROR
<<
"Trying to send to an uncached connection, skipping."
;
AERROR
<<
name_
<<
": Trying to send to an uncached connection, skipping."
;
return
false
;
}
// Copy the lock so that it still exists if the connection is closed after
...
...
@@ -122,8 +125,9 @@ bool WebSocketHandler::SendData(Connection *conn, const std::string &data,
// Note that while we are holding the connection lock, the connection won't be
// closed and removed.
int
ret
;
PERF_BLOCK
(
StrCat
(
"Writing "
,
data
.
size
(),
" bytes via websocket took"
),
0.1
)
{
PERF_BLOCK
(
StrCat
(
name_
,
": Writing "
,
data
.
size
(),
" bytes via websocket took"
),
0.1
)
{
ret
=
mg_websocket_write
(
conn
,
op_code
,
data
.
c_str
(),
data
.
size
());
}
connection_lock
->
unlock
();
...
...
@@ -144,7 +148,8 @@ bool WebSocketHandler::SendData(Connection *conn, const std::string &data,
msg
=
StrCat
(
"Expect to send "
,
data
.
size
(),
" bytes. But sent "
,
ret
,
" bytes"
);
}
AWARN
<<
"Failed to send data via websocket connection. Reason: "
<<
msg
;
AWARN
<<
name_
<<
": Failed to send data via websocket connection. Reason: "
<<
msg
;
return
false
;
}
...
...
@@ -181,7 +186,7 @@ bool WebSocketHandler::handleData(CivetServer *server, Connection *conn,
result
=
handleBinaryData
(
conn
,
data_
.
str
());
break
;
default:
AERROR
<<
"
Unknown WebSocket bits flag: "
<<
bits
;
AERROR
<<
name_
<<
":
Unknown WebSocket bits flag: "
<<
bits
;
break
;
}
...
...
modules/dreamview/backend/handlers/websocket_handler.h
浏览文件 @
10239e32
...
...
@@ -56,6 +56,8 @@ class WebSocketHandler : public CivetWebSocketHandler {
using
MessageHandler
=
std
::
function
<
void
(
const
Json
&
,
Connection
*
)
>
;
using
ConnectionReadyHandler
=
std
::
function
<
void
(
Connection
*
)
>
;
explicit
WebSocketHandler
(
const
std
::
string
&
name
)
:
name_
(
name
)
{}
/**
* @brief Callback method for when the client intends to establish a websocket
* connection, before websocket handshake.
...
...
@@ -149,6 +151,8 @@ class WebSocketHandler : public CivetWebSocketHandler {
}
private:
const
std
::
string
name_
;
// Message handlers keyed by message type.
std
::
unordered_map
<
std
::
string
,
MessageHandler
>
message_handlers_
;
// New connection ready handlers.
...
...
modules/dreamview/backend/handlers/websocket_handler_test.cc
浏览文件 @
10239e32
...
...
@@ -53,7 +53,7 @@ class MockClient {
};
std
::
vector
<
std
::
string
>
MockClient
::
received_messages_
;
static
WebSocketHandler
handler
;
static
WebSocketHandler
handler
(
"Test"
)
;
TEST
(
WebSocketTest
,
IntegrationTest
)
{
// NOTE: Here a magic number is picked up as the port, which is not ideal but
...
...
modules/dreamview/backend/simulation_world/simulation_world_service.cc
浏览文件 @
10239e32
...
...
@@ -272,7 +272,7 @@ void SimulationWorldService::Update() {
UpdateWithLatestObserved
(
"PerceptionObstacles"
,
AdapterManager
::
GetPerceptionObstacles
());
UpdateWithLatestObserved
(
"PerceptionTrafficLight"
,
AdapterManager
::
GetTrafficLightDetection
());
AdapterManager
::
GetTrafficLightDetection
()
,
false
);
UpdateWithLatestObserved
(
"PredictionObstacles"
,
AdapterManager
::
GetPrediction
());
UpdateWithLatestObserved
(
"Planning"
,
AdapterManager
::
GetPlanning
());
...
...
modules/dreamview/backend/simulation_world/simulation_world_service.h
浏览文件 @
10239e32
...
...
@@ -185,10 +185,12 @@ class SimulationWorldService {
*/
template
<
typename
AdapterType
>
void
UpdateWithLatestObserved
(
const
std
::
string
&
adapter_name
,
AdapterType
*
adapter
)
{
AdapterType
*
adapter
,
bool
logging
=
true
)
{
if
(
adapter
->
Empty
())
{
AINFO_EVERY
(
100
)
<<
adapter_name
<<
" adapter has not received any data yet."
;
if
(
logging
)
{
AINFO_EVERY
(
100
)
<<
adapter_name
<<
" adapter has not received any data yet."
;
}
return
;
}
...
...
modules/dreamview/backend/simulation_world/simulation_world_updater.cc
浏览文件 @
10239e32
...
...
@@ -92,6 +92,7 @@ void SimulationWorldUpdater::RegisterMessageHandlers() {
websocket_
->
RegisterMessageHandler
(
"Binary"
,
[
this
](
const
std
::
string
&
data
,
WebSocketHandler
::
Connection
*
conn
)
{
// Navigation info in binary format
apollo
::
relative_map
::
NavigationInfo
navigation_info
;
if
(
navigation_info
.
ParseFromString
(
data
))
{
AdapterManager
::
FillNavigationHeader
(
FLAGS_dreamview_module_name
,
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录