Apollo 10.0
自动驾驶开放平台
map_updater.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2023 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
21#pragma once
22#include<string>
23#include<memory>
24#include "modules/common_msgs/localization_msgs/localization.pb.h"
25#include "modules/dreamview_plus/proto/data_handler.pb.h"
26#include "modules/common_msgs/dreamview_msgs/simulation_world.pb.h"
27
28#include "cyber/common/log.h"
29#include "cyber/cyber.h"
40namespace apollo {
41namespace dreamview {
42
44
50class MapUpdater : public UpdaterBase {
51 public:
58 MapUpdater(WebSocketHandler *websocket, const MapService *map_service);
59 ~MapUpdater() override {}
60 void StartStream(const double &time_interval_ms,
61 const std::string &channel_name = "",
62 nlohmann::json *subscribe_param = nullptr) override;
63 void StopStream(const std::string& channel_name = "") override;
64 void OnTimer(const std::string& channel_name = "");
65 void PublishMessage(const std::string& channel_name = "") override;
66
67 private:
68 std::unique_ptr<cyber::Node> node_;
69 WebSocketHandler *websocket_ = nullptr;
70 const MapService *map_service_;
71
72 // retrieved map string by map element ids.
73 std::string retrieved_map_string_;
74
79 void UpdateAdcPosition(
80 const std::shared_ptr<apollo::localization::LocalizationEstimate>
81 &localization);
82 std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate>>
83 localization_reader_;
84
90 void GetMapElementIds(double radius, MapElementIds *ids);
91
92 // adc localization position
93 apollo::common::PointENU adc_point_;
94
95 std::unique_ptr<cyber::Timer> timer_;
96 MapElementIds map_element_ids_;
97};
98
99} // namespace dreamview
100} // namespace apollo
A wrapper around WebSocketHandler to keep pushing map to frontend via websocket.
Definition map_updater.h:50
void OnTimer(const std::string &channel_name="")
void StartStream(const double &time_interval_ms, const std::string &channel_name="", nlohmann::json *subscribe_param=nullptr) override
Start data flow.
void StopStream(const std::string &channel_name="") override
Stop data flow.
void PublishMessage(const std::string &channel_name="") override
Publish Message to dreamview frontend.
Base Class for all data updater.
The WebSocketHandler, built on top of CivetWebSocketHandler, is a websocket handler that handles diff...
class register implement
Definition arena_queue.h:37