Apollo 10.0
自动驾驶开放平台
dreamview.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 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
18
19#include <vector>
20
21#include "cyber/common/file.h"
22#include "cyber/time/clock.h"
26namespace {
27std::map<std::string, int> plugin_function_map = {
28 {"UpdateScenarioSetToStatus", 0},
29 {"UpdateRecordToStatus", 1},
30 {"UpdateDynamicModelToStatus", 2},
31 {"UpdateVehicleToStatus", 3}};
32std::map<std::string, int> hmi_function_map = {
33 {"SimControlRestart", 0}, {"MapServiceReloadMap", 1},
34 {"LoadDynamicModels", 2}, {"ChangeDynamicModel", 3},
35 {"DeleteDynamicModel", 4}, {"AddDynamicModel", 5},
36 {"RestartDynamicModel", 6},
37};
38} // namespace
39
40namespace apollo {
41namespace dreamview {
42
46
48
49void Dreamview::TerminateProfilingMode() {
50 Stop();
51 AWARN << "Profiling timer called shutdown!";
52}
53
56
57 if (FLAGS_dreamview_profiling_mode &&
58 FLAGS_dreamview_profiling_duration > 0.0) {
59 exit_timer_.reset(new cyber::Timer(
60 FLAGS_dreamview_profiling_duration,
61 [this]() { this->TerminateProfilingMode(); }, false));
62
63 exit_timer_->Start();
64 AWARN << "============================================================";
65 AWARN << "| Dreamview running in profiling mode, exit in "
66 << FLAGS_dreamview_profiling_duration << " seconds |";
67 AWARN << "============================================================";
68 }
69
70 // Initialize and run the web server which serves the dreamview htmls and
71 // javascripts and handles websocket requests.
72 std::vector<std::string> options = {
73 "document_root", FLAGS_static_file_dir,
74 "listening_ports", FLAGS_server_ports,
75 "websocket_timeout_ms", FLAGS_websocket_timeout_ms,
76 "request_timeout_ms", FLAGS_request_timeout_ms,
77 "enable_keep_alive", "yes",
78 "tcp_nodelay", "1",
79 "keep_alive_timeout_ms", "500"};
80 if (PathExists(FLAGS_ssl_certificate)) {
81 options.push_back("ssl_certificate");
82 options.push_back(FLAGS_ssl_certificate);
83 } else if (FLAGS_ssl_certificate.size() > 0) {
84 AERROR << "Certificate file " << FLAGS_ssl_certificate
85 << " does not exist!";
86 }
87 server_.reset(new CivetServer(options));
88
89 websocket_.reset(new WebSocketHandler("SimWorld"));
90 map_ws_.reset(new WebSocketHandler("Map"));
91 point_cloud_ws_.reset(new WebSocketHandler("PointCloud"));
92 camera_ws_.reset(new WebSocketHandler("Camera"));
93 plugin_ws_.reset(new WebSocketHandler("Plugin"));
94
95 map_service_.reset(new MapService());
96 image_.reset(new ImageHandler());
97 perception_camera_updater_.reset(
98 new PerceptionCameraUpdater(camera_ws_.get()));
99
100 hmi_.reset(new HMI(websocket_.get(), map_service_.get()));
101 plugin_manager_.reset(new PluginManager(plugin_ws_.get()));
102 sim_world_updater_.reset(new SimulationWorldUpdater(
103 websocket_.get(), map_ws_.get(), camera_ws_.get(),
104 plugin_ws_.get(), map_service_.get(),
105 perception_camera_updater_.get(), plugin_manager_.get(),
106 FLAGS_routing_from_file));
107 point_cloud_updater_.reset(
108 new PointCloudUpdater(point_cloud_ws_.get(), sim_world_updater_.get()));
109
110 server_->addWebSocketHandler("/websocket", *websocket_);
111 server_->addWebSocketHandler("/map", *map_ws_);
112 server_->addWebSocketHandler("/pointcloud", *point_cloud_ws_);
113 server_->addWebSocketHandler("/camera", *camera_ws_);
114 server_->addWebSocketHandler("/plugin", *plugin_ws_);
115 server_->addHandler("/image", *image_);
116#if WITH_TELEOP == 1
117 teleop_ws_.reset(new WebSocketHandler("Teleop"));
118 teleop_.reset(new TeleopService(teleop_ws_.get()));
119 server_->addWebSocketHandler("/teleop", *teleop_ws_);
120#endif
121 return Status::OK();
122}
123
125 sim_world_updater_->Start();
126 point_cloud_updater_->Start([this](const std::string& param_string) -> bool {
127 return PointCloudCallback(param_string);
128 });
129 hmi_->Start([this](const std::string& function_name,
130 const nlohmann::json& param_json) -> nlohmann::json {
131 nlohmann::json ret = HMICallbackSimControl(function_name, param_json);
132 ADEBUG << "ret: " << ret.dump();
133 return ret;
134 });
135 perception_camera_updater_->Start(
136 [this](const std::string& param_string) -> bool {
137 return PerceptionCameraCallback(param_string);
138 });
139 plugin_manager_->Start([this](const std::string& function_name,
140 const nlohmann::json& param_json) -> bool {
141 return PluginCallbackHMI(function_name, param_json);
142 });
143#if WITH_TELEOP == 1
144 teleop_->Start();
145#endif
146 return Status::OK();
147}
148
150 server_->close();
151 SimControlManager::Instance()->Stop();
152 point_cloud_updater_->Stop();
153 hmi_->Stop();
154 perception_camera_updater_->Stop();
155 plugin_manager_->Stop();
156}
157
158nlohmann::json Dreamview::HMICallbackSimControl(
159 const std::string& function_name, const nlohmann::json& param_json) {
160 nlohmann::json callback_res = {};
161 callback_res["result"] = false;
162 if (hmi_function_map.find(function_name) == hmi_function_map.end()) {
163 AERROR << "Donnot support this callback";
164 return callback_res;
165 }
166 switch (hmi_function_map[function_name]) {
167 case 0: {
168 // 解析结果
169 if (param_json.contains("x") && param_json.contains("y")) {
170 const double x = param_json["x"];
171 const double y = param_json["y"];
172 SimControlManager::Instance()->Restart(x, y);
173 callback_res["result"] = true;
174 }
175 } break;
176 case 1: {
177 map_service_->ReloadMap(true);
178 callback_res["result"] = true;
179 break;
180 }
181 case 2: {
182 // loadDynamicModels
183 if (SimControlManager::Instance()->IsEnabled()) {
184 nlohmann::json load_res =
185 SimControlManager::Instance()->LoadDynamicModels();
186 callback_res["loaded_dynamic_models"] =
187 load_res["loaded_dynamic_models"];
188 callback_res["result"] = true;
189 } else {
190 AERROR << "Sim control is not enabled!";
191 }
192 break;
193 }
194 case 3: {
195 // 解析结果
196 if (param_json.contains("dynamic_model_name") &&
197 SimControlManager::Instance()->IsEnabled()) {
198 callback_res["result"] =
199 SimControlManager::Instance()->ChangeDynamicModel(
200 param_json["dynamic_model_name"]);
201 } else {
202 AERROR << "Sim control is not enabled or missing dynamic model name "
203 "param!";
204 }
205 break;
206 }
207 case 4: {
208 // 解析结果
209 if (param_json.contains("dynamic_model_name") &&
210 SimControlManager::Instance()->IsEnabled()) {
211 callback_res["result"] =
212 SimControlManager::Instance()->DeleteDynamicModel(
213 param_json["dynamic_model_name"]);
214 } else {
215 AERROR << "Sim control is not enabled or missing dynamic model name "
216 "param!";
217 }
218 break;
219 }
220 case 5: {
221 // addDynamicModel
222 if (param_json.contains("dynamic_model_name") &&
223 SimControlManager::Instance()->IsEnabled()) {
224 callback_res["result"] = SimControlManager::Instance()->AddDynamicModel(
225 param_json["dynamic_model_name"]);
226 } else {
227 AERROR << "Sim control is not enabled or missing dynamic model name "
228 "param!";
229 }
230 break;
231 }
232 case 6: {
233 // restart dynamic model
234 map_service_->ReloadMap(true);
235 SimControlManager::Instance()->Restart();
236 callback_res["result"] = true;
237 break;
238 }
239 default:
240 break;
241 }
242 return callback_res;
243}
244
245bool Dreamview::PluginCallbackHMI(const std::string& function_name,
246 const nlohmann::json& param_json) {
247 bool callback_res;
248 if (plugin_function_map.find(function_name) == plugin_function_map.end()) {
249 AERROR << "Donnot support this callback";
250 return false;
251 }
252 switch (plugin_function_map[function_name]) {
253 case 0: {
254 // 解析结果
255 if (param_json.contains("data") &&
256 param_json["data"].contains("scenario_set_id") &&
257 param_json["data"].contains("scenario_set_name")) {
258 const std::string scenario_set_id =
259 param_json["data"]["scenario_set_id"];
260 const std::string scenario_set_name =
261 param_json["data"]["scenario_set_name"];
262 if (!scenario_set_id.empty() && !scenario_set_name.empty()) {
263 callback_res = hmi_->UpdateScenarioSetToStatus(scenario_set_id,
264 scenario_set_name);
265 }
266 }
267 } break;
268 case 1: {
269 callback_res = hmi_->UpdateRecordToStatus();
270 } break;
271 case 2: {
272 if (param_json.contains("data") &&
273 param_json["data"].contains("dynamic_model_name")) {
274 const std::string dynamic_model_name =
275 param_json["data"]["dynamic_model_name"];
276 if (!dynamic_model_name.empty()) {
277 callback_res = hmi_->UpdateDynamicModelToStatus(dynamic_model_name);
278 }
279 }
280 } break;
281 case 3: {
282 callback_res = hmi_->UpdateVehicleToStatus();
283 }
284 default:
285 break;
286 }
287 return callback_res;
288}
289
290bool Dreamview::PerceptionCameraCallback(const std::string& param_string) {
291 bool callback_res = false;
292 callback_res = hmi_->UpdateCameraChannelToStatus(param_string);
293 return callback_res;
294}
295
296bool Dreamview::PointCloudCallback(const std::string& param_string) {
297 bool callback_res = false;
298 callback_res = hmi_->UpdatePointChannelToStatus(param_string);
299 return callback_res;
300}
301} // namespace dreamview
302} // namespace apollo
A general class to denote the return status of an API call.
Definition status.h:43
@Brief This is a helper class that can load vehicle configurations.
static void Init()
Initialize vehicle configurations with default configuration file pointed by gflags FLAGS_vehicle_con...
Used to perform oneshot or periodic timing tasks
Definition timer.h:71
apollo::common::Status Init()
Definition dreamview.cc:54
apollo::common::Status Start()
Definition dreamview.cc:124
The ImageHandler, built on top of CivetHandler, converts the received ROS image message to an image s...
A wrapper around WebSocketHandler to keep pushing PointCloud to frontend via websocket while handling...
A wrapper around SimulationWorldService and WebSocketHandler to keep pushing SimulationWorld to front...
The WebSocketHandler, built on top of CivetWebSocketHandler, is a websocket handler that handles diff...
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AWARN
Definition log.h:43
bool PathExists(const std::string &path)
Check if the path exists.
Definition file.cc:195
class register implement
Definition arena_queue.h:37