Apollo 10.0
自动驾驶开放平台
obstacle_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#pragma once
17
18#include <map>
19#include <memory>
20#include <string>
21#include <unordered_map>
22#include <vector>
23
24#include "modules/common_msgs/localization_msgs/localization.pb.h"
25#include "modules/common_msgs/localization_msgs/pose.pb.h"
26#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
27#include "modules/dreamview_plus/proto/obstacle.pb.h"
28
29#include "cyber/cyber.h"
34namespace apollo {
35namespace dreamview {
36
41
43 std::string curr_channel_name_;
44 std::shared_ptr<cyber::Reader<PerceptionObstacles>>
46 std::unordered_map<std::string, Object> obj_map_;
47 std::unique_ptr<cyber::Timer> timer_;
48 std::vector<PerceptionObstacle> obstacles_;
50 explicit ObstacleChannelUpdater(std::string channel_name)
51 : curr_channel_name_(channel_name),
53};
60 public:
61 explicit ObstacleUpdater(WebSocketHandler* websocket);
62 void StartStream(const double& time_interval_ms,
63 const std::string& channel_name = "",
64 nlohmann::json* subscribe_param = nullptr) override;
65 void StopStream(const std::string& channel_name) override;
66 void OnTimer(const std::string& channel_name = "");
67 void PublishMessage(const std::string& channel_name = "") override;
68 void GetChannelMsg(std::vector<std::string>* channels);
69 void Stop();
70 void Init();
71
72 private:
73 bool enabled_ = false;
74 WebSocketHandler* websocket_;
75 std::unique_ptr<cyber::Node> node_;
76 std::map<std::string, ObstacleChannelUpdater*> obstacle_channel_updater_map_;
77 std::mutex channel_updater_map_mutex_;
78 std::mutex updater_publish_mutex_;
79 std::shared_ptr<cyber::Reader<LocalizationEstimate>> localization_reader_;
80 Pose adc_pose_;
81 ObstacleChannelUpdater* GetObstacleChannelUpdater(
82 const std::string& channel_name);
83 void SetObstacleSource(const PerceptionObstacle& obstacle, Object* obj);
84 void SetObstacleType(const PerceptionObstacle::Type obstacle_type,
85 const PerceptionObstacle::SubType obstalce_sub_type,
86 Object* obj);
87 void SetObstaclePolygon(const PerceptionObstacle& obstalce, Object* obj);
88 void SetObstacleInfo(const PerceptionObstacle& obstalce, Object* obj);
89 void SetObstacleSensorMeasurements(const PerceptionObstacle& obstacle,
90 Object* obj,
91 ObstacleChannelUpdater* channel_updater);
92 void SetADCPosition(Object* auto_driving_car);
93 void OnObstacles(const std::shared_ptr<PerceptionObstacles>& obstacles,
94 const std::string& channel_name);
95 void GetObjects(std::string* to_send, std::string channel_name);
96 void OnLocalization(
97 const std::shared_ptr<LocalizationEstimate>& localization);
98};
99
100} // namespace dreamview
101} // namespace apollo
A wrapper around WebSocketHandler to keep pushing obstalcles to frontend via websocket.
void PublishMessage(const std::string &channel_name="") override
Publish Message to dreamview frontend.
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 GetChannelMsg(std::vector< std::string > *channels)
GetChannelMsg
Base Class for data updater with multiply channels.
The WebSocketHandler, built on top of CivetWebSocketHandler, is a websocket handler that handles diff...
class register implement
Definition arena_queue.h:37
std::vector< PerceptionObstacle > obstacles_
std::shared_ptr< cyber::Reader< PerceptionObstacles > > perception_obstacle_reader_
std::unique_ptr< cyber::Timer > timer_
ObstacleChannelUpdater(std::string channel_name)
std::unordered_map< std::string, Object > obj_map_