Apollo 10.0
自动驾驶开放平台
apollo::dreamview::Dreamview类 参考

#include <dreamview.h>

apollo::dreamview::Dreamview 的协作图:

Public 成员函数

 ~Dreamview ()
 
apollo::common::Status Init ()
 
apollo::common::Status Start ()
 
void Stop ()
 
 ~Dreamview ()
 
apollo::common::Status Init ()
 
apollo::common::Status Start ()
 
void Stop ()
 
void RegisterUpdaters ()
 

详细描述

在文件 dreamview.h46 行定义.

构造及析构函数说明

◆ ~Dreamview() [1/2]

apollo::dreamview::Dreamview::~Dreamview ( )

在文件 dreamview.cc47 行定义.

◆ ~Dreamview() [2/2]

apollo::dreamview::Dreamview::~Dreamview ( )

成员函数说明

◆ Init() [1/2]

Status apollo::dreamview::Dreamview::Init ( )

在文件 dreamview.cc54 行定义.

54 {
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}
A module that collects camera image and localization (by collecting localization & static transforms)...
A module that maintains all dv-related plugin information.
static void Init()
Initialize vehicle configurations with default configuration file pointed by gflags FLAGS_vehicle_con...
#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

◆ Init() [2/2]

apollo::common::Status apollo::dreamview::Dreamview::Init ( )

◆ RegisterUpdaters()

void apollo::dreamview::Dreamview::RegisterUpdaters ( )

在文件 dreamview.cc266 行定义.

266 {
267 updater_manager_->RegisterUpdater("simworld", sim_world_updater_.get());
268 updater_manager_->RegisterUpdater("hmistatus", hmi_.get());
269 updater_manager_->RegisterUpdater("camera", perception_camera_updater_.get());
270 updater_manager_->RegisterUpdater("pointcloud", point_cloud_updater_.get());
271 updater_manager_->RegisterUpdater("map", map_updater_.get());
272 updater_manager_->RegisterUpdater("obstacle", obstacle_updater_.get());
273 updater_manager_->RegisterUpdater("channelsinfo",
274 channels_info_updater_.get());
275}

◆ Start() [1/2]

Status apollo::dreamview::Dreamview::Start ( )

在文件 dreamview.cc124 行定义.

124 {
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}
#define ADEBUG
Definition log.h:41

◆ Start() [2/2]

apollo::common::Status apollo::dreamview::Dreamview::Start ( )

◆ Stop() [1/2]

void apollo::dreamview::Dreamview::Stop ( )

在文件 dreamview.cc149 行定义.

149 {
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}

◆ Stop() [2/2]

void apollo::dreamview::Dreamview::Stop ( )

该类的文档由以下文件生成: