diff --git a/modules/dreamview/backend/dreamview.cc b/modules/dreamview/backend/dreamview.cc index 0c954f3247b4d497f8e064c1969a3539d083e3ac..88f9ddc1dcc96e4dd6d487db9303e3d14131a771 100644 --- a/modules/dreamview/backend/dreamview.cc +++ b/modules/dreamview/backend/dreamview.cc @@ -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())); diff --git a/modules/dreamview/backend/handlers/websocket_handler.cc b/modules/dreamview/backend/handlers/websocket_handler.cc index 21759d6039cc6d27348f5bd85bd0e6d714f68ced..fba7db26e4189d49c642654b55b6b8e6dd4d1e40 100644 --- a/modules/dreamview/backend/handlers/websocket_handler.cc +++ b/modules/dreamview/backend/handlers/websocket_handler.cc @@ -34,7 +34,8 @@ void WebSocketHandler::handleReadyState(CivetServer *server, Connection *conn) { { std::unique_lock lock(mutex_); connections_.emplace(conn, std::make_shared()); - 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 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 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; } diff --git a/modules/dreamview/backend/handlers/websocket_handler.h b/modules/dreamview/backend/handlers/websocket_handler.h index 7bd26f08c1b7e0ee580ead6f771c94b7e29836a6..286c9333fb19ff6534895e5bff149fabe6469565 100644 --- a/modules/dreamview/backend/handlers/websocket_handler.h +++ b/modules/dreamview/backend/handlers/websocket_handler.h @@ -56,6 +56,8 @@ class WebSocketHandler : public CivetWebSocketHandler { using MessageHandler = std::function; using ConnectionReadyHandler = std::function; + 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 message_handlers_; // New connection ready handlers. diff --git a/modules/dreamview/backend/handlers/websocket_handler_test.cc b/modules/dreamview/backend/handlers/websocket_handler_test.cc index c23b01b7cf96362f22470d2a294660d9dade9ec9..c3a336b3e952f48dcf5215aff35f0238bc259be8 100644 --- a/modules/dreamview/backend/handlers/websocket_handler_test.cc +++ b/modules/dreamview/backend/handlers/websocket_handler_test.cc @@ -53,7 +53,7 @@ class MockClient { }; std::vector 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 diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.cc b/modules/dreamview/backend/simulation_world/simulation_world_service.cc index 197992a1f00be5f47fc37652bfe8793fe1f8baee..fd8000a8fe8e89d692e598d694e946bbfef397e8 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.cc @@ -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()); diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.h b/modules/dreamview/backend/simulation_world/simulation_world_service.h index 259571a16595f74babd6f6d7467ba24f8c6523ec..41f26e13fe4a6b9b093807b64efb8f628d7664a6 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.h +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.h @@ -185,10 +185,12 @@ class SimulationWorldService { */ template 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; } diff --git a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc index 5481aa9553fe6acfa56ffb189b408a53162f3100..b31f4d5a301e809874169c84880bc1b8db25d5e4 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc @@ -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,