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

A wrapper around WebSocketHandler to keep pushing PointCloud to frontend via websocket while handling the response from frontend. 更多...

#include <point_cloud_updater.h>

类 apollo::dreamview::PointCloudUpdater 继承关系图:
apollo::dreamview::PointCloudUpdater 的协作图:

Public 类型

using DvCallback = std::function< bool(const std::string &string)>
 

Public 成员函数

 PointCloudUpdater (WebSocketHandler *websocket, SimulationWorldUpdater *sim_world_updater)
 Constructor with the websocket handler.
 
 ~PointCloudUpdater ()
 
void Start (DvCallback callback_api)
 Starts to push PointCloud to frontend.
 
void Stop ()
 
 PointCloudUpdater (WebSocketHandler *websocket)
 Constructor with the websocket handler.
 
 ~PointCloudUpdater ()
 
void Stop ()
 Starts to push PointCloud to frontend.
 
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 OnTimer (const std::string &channel_name="")
 
void PublishMessage (const std::string &channel_name="") override
 Publish Message to dreamview frontend.
 
void GetChannelMsg (std::vector< std::string > *channels) override
 GetChannelMsg
 
- Public 成员函数 继承自 apollo::dreamview::UpdaterWithChannelsBase
 UpdaterWithChannelsBase (const std::vector< std::string > &filter_message_types, const std::vector< std::string > &filter_channels)
 
void GetChannelMsgWithFilter (std::vector< std::string > *channels)
 
bool IsChannelInUpdater (const std::string &message_type, const std::string &channel_name)
 Check if the channel belongs to current updater.
 
- Public 成员函数 继承自 apollo::dreamview::UpdaterBase
 UpdaterBase ()
 Updaterbase
 
virtual ~UpdaterBase ()
 

静态 Public 成员函数

static void LoadLidarHeight (const std::string &file_path)
 

静态 Public 属性

static float lidar_height_ = kDefaultLidarHeight
 
static boost::shared_mutex mutex_
 

额外继承的成员函数

- Public 属性 继承自 apollo::dreamview::UpdaterWithChannelsBase
std::vector< std::string > channels_
 
std::vector< std::string > filter_message_types_
 
std::vector< std::string > filter_channels_
 

详细描述

A wrapper around WebSocketHandler to keep pushing PointCloud to frontend via websocket while handling the response from frontend.

在文件 point_cloud_updater.h53 行定义.

成员类型定义说明

◆ DvCallback

using apollo::dreamview::PointCloudUpdater::DvCallback = std::function<bool(const std::string &string)>

在文件 point_cloud_updater.h66 行定义.

构造及析构函数说明

◆ PointCloudUpdater() [1/2]

apollo::dreamview::PointCloudUpdater::PointCloudUpdater ( WebSocketHandler websocket,
SimulationWorldUpdater sim_world_updater 
)

Constructor with the websocket handler.

参数
websocketPointer of the websocket handler that has been attached to the server.
simulationworldupdaterpointer

在文件 point_cloud_updater.cc42 行定义.

44 : node_(cyber::CreateNode("point_cloud")),
45 websocket_(websocket),
46 point_cloud_str_(""),
47 future_ready_(true),
48 simworld_updater_(simworld_updater) {
49 RegisterMessageHandlers();
50}
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space)
Definition cyber.cc:33

◆ ~PointCloudUpdater() [1/2]

apollo::dreamview::PointCloudUpdater::~PointCloudUpdater ( )

◆ PointCloudUpdater() [2/2]

apollo::dreamview::PointCloudUpdater::PointCloudUpdater ( WebSocketHandler websocket)
explicit

Constructor with the websocket handler.

参数
websocketPointer of the websocket handler that has been attached to the server.
simulationworldupdaterpointer

在文件 point_cloud_updater.cc43 行定义.

44 : UpdaterWithChannelsBase({"PointCloud", "PerceptionEdgeInfo"},
45 {"sensor", "edge"}),
46 node_(cyber::CreateNode("point_cloud")),
47 websocket_(websocket) {
48 localization_reader_ = node_->CreateReader<LocalizationEstimate>(
49 FLAGS_localization_topic,
50 [this](const std::shared_ptr<LocalizationEstimate> &msg) {
51 UpdateLocalizationTime(msg);
52 });
53}
UpdaterWithChannelsBase(const std::vector< std::string > &filter_message_types, const std::vector< std::string > &filter_channels)

◆ ~PointCloudUpdater() [2/2]

apollo::dreamview::PointCloudUpdater::~PointCloudUpdater ( )

成员函数说明

◆ GetChannelMsg()

void apollo::dreamview::PointCloudUpdater::GetChannelMsg ( std::vector< std::string > *  channels)
overridevirtual

◆ LoadLidarHeight()

void apollo::dreamview::PointCloudUpdater::LoadLidarHeight ( const std::string &  file_path)
static

在文件 point_cloud_updater.cc54 行定义.

54 {
55 if (!cyber::common::PathExists(file_path)) {
56 AWARN << "No such file: " << FLAGS_lidar_height_yaml
57 << ". Using default lidar height:" << kDefaultLidarHeight;
58 boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
59 lidar_height_ = kDefaultLidarHeight;
60 return;
61 }
62
63 YAML::Node config = YAML::LoadFile(file_path);
64 if (config["vehicle"] && config["vehicle"]["parameters"]) {
65 boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
66 lidar_height_ = config["vehicle"]["parameters"]["height"].as<float>();
67 AINFO << "Lidar height is updated to " << lidar_height_;
68 return;
69 }
70
71 AWARN << "Fail to load the lidar height yaml file: "
72 << FLAGS_lidar_height_yaml
73 << ". Using default lidar height:" << kDefaultLidarHeight;
74 boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
75 lidar_height_ = kDefaultLidarHeight;
76}
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
bool PathExists(const std::string &path)
Check if the path exists.
Definition file.cc:195

◆ OnTimer()

void apollo::dreamview::PointCloudUpdater::OnTimer ( const std::string &  channel_name = "")

在文件 point_cloud_updater.cc109 行定义.

109 {
110 PublishMessage(channel_name);
111}
void PublishMessage(const std::string &channel_name="") override
Publish Message to dreamview frontend.

◆ PublishMessage()

void apollo::dreamview::PointCloudUpdater::PublishMessage ( const std::string &  channel_name = "")
overridevirtual

Publish Message to dreamview frontend.

实现了 apollo::dreamview::UpdaterBase.

在文件 point_cloud_updater.cc126 行定义.

126 {
127 PointCloudChannelUpdater *updater = GetPointCloudChannelUpdater(channel_name);
128 std::string to_send;
129 // the channel has no data input, clear the sending object.
130 if ((updater->point_cloud_reader_ &&
131 !updater->point_cloud_reader_->HasWriter()) ||
132 (updater->perception_edge_reader_ &&
133 !updater->perception_edge_reader_->HasWriter())) {
134 updater->last_point_cloud_time_ = 0.0;
135 updater->point_cloud_str_ = "";
136 to_send = "";
137 } else {
138 if (updater->point_cloud_str_ != "" &&
139 std::fabs(last_localization_time_ - updater->last_point_cloud_time_) >
140 2.0) {
141 boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
142 updater->point_cloud_str_ = "";
143 }
144 {
145 boost::shared_lock<boost::shared_mutex> reader_lock(mutex_);
146 to_send = updater->point_cloud_str_;
147 }
148 }
149 StreamData stream_data;
150 std::string stream_data_string;
151 stream_data.set_action("stream");
152 stream_data.set_data_name("pointcloud");
153 stream_data.set_channel_name(channel_name);
154 std::vector<uint8_t> byte_data(to_send.begin(), to_send.end());
155 stream_data.set_data(&(byte_data[0]), byte_data.size());
156 stream_data.set_type("pointcloud");
157 stream_data.SerializeToString(&stream_data_string);
158 websocket_->BroadcastBinaryData(stream_data_string);
159}
bool BroadcastBinaryData(const std::string &data, bool skippable=false)
Sends the provided binary data to all the connected clients.

◆ Start()

void apollo::dreamview::PointCloudUpdater::Start ( DvCallback  callback_api)

Starts to push PointCloud to frontend.

在文件 point_cloud_updater.cc205 行定义.

205 {
206 callback_api_ = callback_api;
207 localization_reader_ = node_->CreateReader<LocalizationEstimate>(
208 FLAGS_localization_topic,
209 [this](const std::shared_ptr<LocalizationEstimate> &msg) {
210 UpdateLocalizationTime(msg);
211 });
212 LoadLidarHeight(FLAGS_lidar_height_yaml);
213}
static void LoadLidarHeight(const std::string &file_path)

◆ StartStream()

void apollo::dreamview::PointCloudUpdater::StartStream ( const double &  time_interval_ms,
const std::string &  channel_name = "",
nlohmann::json *  subscribe_param = nullptr 
)
overridevirtual

Start data flow.

参数
time_interval_msData stream sending frequency. 0 means single subscribe
subscribe_paramsubscribe some updater may need extra params

实现了 apollo::dreamview::UpdaterBase.

在文件 point_cloud_updater.cc84 行定义.

86 {
87 if (channel_name.empty()) {
88 AERROR << "Failed to subscribe channel for channel is empty!";
89 return;
90 }
91 if (std::find(channels_.begin(), channels_.end(), channel_name) ==
92 channels_.end()) {
93 AERROR << "Failed to subscribe point cloud updater, for channel: "
94 << channel_name << " is invalid.";
95 return;
96 }
97 if (time_interval_ms > 0) {
98 PointCloudChannelUpdater *updater =
99 GetPointCloudChannelUpdater(channel_name);
100 updater->timer_.reset(new cyber::Timer(
101 time_interval_ms,
102 [channel_name, this]() { this->OnTimer(channel_name); }, false));
103 updater->timer_->Start();
104 } else {
105 this->OnTimer(channel_name);
106 }
107}
void OnTimer(const std::string &channel_name="")
#define AERROR
Definition log.h:44

◆ Stop() [1/2]

void apollo::dreamview::PointCloudUpdater::Stop ( )

在文件 point_cloud_updater.cc215 行定义.

215 {
216 if (enabled_) {
217 async_future_.wait();
218 }
219}

◆ Stop() [2/2]

void apollo::dreamview::PointCloudUpdater::Stop ( )

Starts to push PointCloud to frontend.

◆ StopStream()

void apollo::dreamview::PointCloudUpdater::StopStream ( const std::string &  channel_name = "")
overridevirtual

Stop data flow.

实现了 apollo::dreamview::UpdaterBase.

在文件 point_cloud_updater.cc112 行定义.

112 {
113 if (channel_name.empty()) {
114 AERROR << "Failed to unsubscribe channel for channel is empty!";
115 return;
116 }
117 PointCloudChannelUpdater *updater = GetPointCloudChannelUpdater(channel_name);
118 if (updater->timer_) {
119 updater->timer_->Stop();
120 }
121 // 回到初始值
122 updater->last_point_cloud_time_ = 0.0;
123 updater->point_cloud_str_ = "";
124 updater->future_ready_ = true;
125}

类成员变量说明

◆ lidar_height_

static float apollo::dreamview::PointCloudUpdater::lidar_height_ = kDefaultLidarHeight
static

在文件 point_cloud_updater.h75 行定义.

◆ mutex_

static boost::shared_mutex apollo::dreamview::PointCloudUpdater::mutex_
static

在文件 point_cloud_updater.h79 行定义.


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