Apollo 10.0
自动驾驶开放平台
simulation_world_updater.h
浏览该文件的文档.
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
21#pragma once
22
23#include <memory>
24#include <string>
25#include <vector>
26
27#include <boost/thread/locks.hpp>
28#include <boost/thread/shared_mutex.hpp>
29
30#include "absl/strings/str_cat.h"
31
32#include "modules/common_msgs/task_manager_msgs/task_manager.pb.h"
33#include "modules/common_msgs/external_command_msgs/lane_follow_command.pb.h"
34#include "modules/common_msgs/external_command_msgs/valet_parking_command.pb.h"
35#include "modules/common_msgs/external_command_msgs/action_command.pb.h"
36#include "modules/dreamview_plus/proto/data_handler.pb.h"
37
38#include "cyber/common/log.h"
39#include "cyber/cyber.h"
44#include "modules/common_msgs/localization_msgs/localization.pb.h"
52namespace apollo {
53namespace dreamview {
54
61class SimulationWorldUpdater : public UpdaterBase {
62 public:
72 SimulationWorldUpdater(WebSocketHandler *websocket, WebSocketHandler *map_ws,
73 WebSocketHandler *plugin_ws,
74 const MapService *map_service,
75 PluginManager *plugin_manager,
76 WebSocketHandler *sim_world_ws, HMI *hmi,
77 bool routing_from_file = false);
78
82 void StartStream(const double &time_interval_ms,
83 const std::string &channel_name = "",
84 nlohmann::json *subscribe_param = nullptr) override;
85 void StopStream(const std::string &channel_name = "") override;
86 void PublishMessage(const std::string &channel_name = "") override;
87 // Time interval, in milliseconds, between pushing SimulationWorld to
88 // frontend.
90
91 double LastAdcTimestampSec() { return last_pushed_adc_timestamp_sec_; }
92
93 private:
98 void OnTimer(const std::string &channel_name = "");
99
106 bool ConstructLaneFollowCommand(
107 const nlohmann::json &json,
109
116 bool ConstructValetParkingCommand(
117 const nlohmann::json &json,
119 const std::string &parking_space_id);
120
126 nlohmann::json GetConstructRoutingRequestJson(const nlohmann::json &start,
127 const nlohmann::json &end);
128
135 bool ConstructLaneWayPoint(const nlohmann::json &point,
136 apollo::routing::LaneWaypoint *laneWayPoint,
137 std::string description);
138
139 bool ValidateCoordinate(const nlohmann::json &json);
140
147 bool CheckRoutingPoint(const nlohmann::json &json, nlohmann::json &result);
148
155 bool LoadPOI();
161 nlohmann::json GetPointJsonFromLaneWaypoint(
162 const apollo::routing::LaneWaypoint &waypoint);
163
169 bool LoadUserDefinedRoutings(const std::string &file_name,
170 google::protobuf::Message *message);
171
178 bool AddDefaultRouting(const nlohmann::json &json);
179
186 bool DeleteDefaultRouting(const std::string &routing_name);
187
188 // /**
189 // * @brief Modify the number of cycles for the default route
190 // * @param routing_name routing name
191 // * @param cycle_number The number of cycles you want to modify
192 // * @return False if failed to delete,
193 // * true otherwise.
194 // */
195 // bool ModifyCycleNumber(const std::string &routing_name,
196 // const int &cycle_number);
197
198 void RegisterMessageHandlers();
199 void RegisterRoutingMessageHandlers();
200
201 SimulationWorldService sim_world_service_;
202 const MapService *map_service_ = nullptr;
203 WebSocketHandler *websocket_ = nullptr;
204 WebSocketHandler *map_ws_ = nullptr;
205 WebSocketHandler *plugin_ws_ = nullptr;
206 std::unique_ptr<PluginManager> plugin_manager_ = nullptr;
207 WebSocketHandler *sim_world_ws_ = nullptr;
208 HMI *hmi_ = nullptr;
209
210 // End point for requesting default route
212
213 // default routings
214 apollo::routing::POI default_routings_;
215 apollo::routing::Landmark *default_routing_;
216
217 // park and go
218 apollo::routing::POI park_go_routings_;
219
220 // The simulation_world in wire format to be pushed to frontend, which is
221 // updated by timer.
222 std::string simulation_world_with_planning_data_;
223
224 // Received relative map data in wire format.
225 std::string relative_map_string_;
226
227 // Mutex to protect concurrent access to simulation_world_json_.
228 // NOTE: Use boost until we have std version of rwlock support.
229 boost::shared_mutex mutex_;
230
231 std::unique_ptr<cyber::Timer> timer_;
232
233 volatile double last_pushed_adc_timestamp_sec_ = 0.0f;
234
235 // std::unique_ptr<PluginManager> plugin_manager_;
236
237 uint64_t command_id_;
238};
239
240} // namespace dreamview
241} // namespace apollo
242
A module that maintains all dv-related plugin information.
This is a major component of the Simulation backend, which maintains a SimulationWorld object and kee...
void StartStream(const double &time_interval_ms, const std::string &channel_name="", nlohmann::json *subscribe_param=nullptr) override
Starts to push simulation_world to frontend.
void PublishMessage(const std::string &channel_name="") override
Publish Message to dreamview frontend.
SimulationWorldUpdater(WebSocketHandler *websocket, WebSocketHandler *map_ws, WebSocketHandler *camera_ws, WebSocketHandler *plugin_ws, const MapService *map_service, PerceptionCameraUpdater *perception_camera_updater, PluginManager *plugin_manager, bool routing_from_file=false)
Constructor with the websocket handler.
void StopStream(const std::string &channel_name="") override
Stop data flow.
The WebSocketHandler, built on top of CivetWebSocketHandler, is a websocket handler that handles diff...
class register implement
Definition arena_queue.h:37
SocketManager to manage all websocket