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

#include <perception_camera_updater.h>

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

Public 类型

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

Public 成员函数

 PerceptionCameraUpdater (WebSocketHandler *websocket)
 
void Start (DvCallback callback_api)
 
void Stop ()
 
bool IsEnabled () const
 
void GetUpdate (std::string *camera_update)
 
void GetChannelMsg (std::vector< std::string > *channels)
 GetChannelMsg
 
bool ChangeChannel (std::string channel)
 
 PerceptionCameraUpdater (WebSocketHandler *websocket)
 
void Stop ()
 
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 GetUpdate (std::string *camera_update, const std::string &channel_name)
 
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 属性 继承自 apollo::dreamview::UpdaterWithChannelsBase
std::vector< std::string > channels_
 
std::vector< std::string > filter_message_types_
 
std::vector< std::string > filter_channels_
 

详细描述

在文件 perception_camera_updater.h41 行定义.

成员类型定义说明

◆ DvCallback

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

在文件 perception_camera_updater.h51 行定义.

构造及析构函数说明

◆ PerceptionCameraUpdater() [1/2]

PerceptionCameraUpdater::PerceptionCameraUpdater ( WebSocketHandler websocket)
explicit

在文件 perception_camera_updater.cc67 行定义.

68 : websocket_(websocket),
69 node_(cyber::CreateNode("perception_camera_updater")) {
70 InitReaders();
71}
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space)
Definition cyber.cc:33

◆ PerceptionCameraUpdater() [2/2]

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

成员函数说明

◆ ChangeChannel()

bool PerceptionCameraUpdater::ChangeChannel ( std::string  channel)

在文件 perception_camera_updater.cc313 行定义.

313 {
314 if (curr_channel_name != "") node_->DeleteReader(curr_channel_name);
315 perception_camera_reader_.reset();
316 perception_camera_reader_ = node_->CreateReader<drivers::Image>(
317 channel,
318 [this](const std::shared_ptr<drivers::Image> &image) { OnImage(image); });
319 if (perception_camera_reader_ == nullptr) {
320 return false;
321 }
322 curr_channel_name = channel;
323 bool update_res = false;
324 update_res = callback_api_(channel);
325 if (!update_res) {
326 AERROR << "update current camera channel fail";
327 return false;
328 }
329 return true;
330}
#define AERROR
Definition log.h:44

◆ GetChannelMsg() [1/2]

void PerceptionCameraUpdater::GetChannelMsg ( std::vector< std::string > *  channels)
virtual

GetChannelMsg

实现了 apollo::dreamview::UpdaterWithChannelsBase.

在文件 perception_camera_updater.cc294 行定义.

295 {
296 enabled_ = true;
297 auto channelManager =
298 apollo::cyber::service_discovery::TopologyManager::Instance()
299 ->channel_manager();
300 std::vector<apollo::cyber::proto::RoleAttributes> role_attr_vec;
301 channelManager->GetWriters(&role_attr_vec);
302 for (auto &role_attr : role_attr_vec) {
303 std::string messageType;
304 messageType = role_attr.message_type();
305 int index = messageType.rfind("drivers.Image");
306 if (index != -1) {
307 channels->push_back(role_attr.channel_name());
308 }
309 }
310 channels_.clear();
311 channels_ = {channels->begin(), channels->end()};
312}

◆ GetChannelMsg() [2/2]

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

◆ GetUpdate() [1/2]

void PerceptionCameraUpdater::GetUpdate ( std::string *  camera_update)

在文件 perception_camera_updater.cc268 行定义.

268 {
269 {
270 std::lock(image_mutex_, localization_mutex_, obstacle_mutex_);
271 std::lock_guard<std::mutex> lock1(image_mutex_, std::adopt_lock);
272 std::lock_guard<std::mutex> lock2(localization_mutex_, std::adopt_lock);
273 std::lock_guard<std::mutex> lock3(obstacle_mutex_, std::adopt_lock);
274 std::vector<double> localization;
275 GetImageLocalization(&localization);
276 *camera_update_.mutable_localization() = {localization.begin(),
277 localization.end()};
278 std::vector<double> localization2camera_tf;
279 GetLocalization2CameraTF(&localization2camera_tf);
280 *camera_update_.mutable_localization2camera_tf() = {
281 localization2camera_tf.begin(), localization2camera_tf.end()};
282 // Concurrently modify protobuf msg can cause ByteSizeConsistencyError
283 // when serializing, so we need lock.
284 if (perception_obstacle_enable_) {
285 *camera_update_.mutable_bbox2d() = {bbox2ds.begin(), bbox2ds.end()};
286 *camera_update_.mutable_obstacles_id() = {obstacle_id.begin(),
287 obstacle_id.end()};
288 *camera_update_.mutable_obstacles_sub_type() = {obstacle_sub_type.begin(),
289 obstacle_sub_type.end()};
290 }
291 camera_update_.SerializeToString(camera_update);
292 }
293}

◆ GetUpdate() [2/2]

void PerceptionCameraUpdater::GetUpdate ( std::string *  camera_update,
const std::string &  channel_name 
)

在文件 perception_camera_updater.cc353 行定义.

354 {
355 {
356 std::vector<double> localization;
357 GetImageLocalization(&localization, channel_name);
358 CameraChannelUpdater *updater = GetCameraChannelUpdater(channel_name);
359 std::lock(updater->image_mutex_, updater->localization_mutex_,
360 updater->obstacle_mutex_);
361 std::lock_guard<std::mutex> lock1(updater->image_mutex_, std::adopt_lock);
362 std::lock_guard<std::mutex> lock2(updater->localization_mutex_,
363 std::adopt_lock);
364 std::lock_guard<std::mutex> lock3(updater->obstacle_mutex_,
365 std::adopt_lock);
366 *(updater->camera_update_).mutable_localization() = {localization.begin(),
367 localization.end()};
368 std::vector<double> localization2camera_tf;
369 GetLocalization2CameraTF(&localization2camera_tf);
370 *(updater->camera_update_).mutable_localization2camera_tf() = {
371 localization2camera_tf.begin(), localization2camera_tf.end()};
372 // Concurrently modify protobuf msg can cause ByteSizeConsistencyError
373 // when serializing, so we need lock.
374 if (perception_obstacle_enable_) {
375 *(updater->camera_update_).mutable_bbox2d() = {updater->bbox2ds.begin(),
376 updater->bbox2ds.end()};
377 *(updater->camera_update_).mutable_obstacles_id() = {
378 updater->obstacle_id.begin(), updater->obstacle_id.end()};
379 *(updater->camera_update_).mutable_obstacles_sub_type() = {
380 updater->obstacle_sub_type.begin(), updater->obstacle_sub_type.end()};
381 }
382 updater->camera_update_.SerializeToString(camera_update);
383 }
384}

◆ IsEnabled()

bool apollo::dreamview::PerceptionCameraUpdater::IsEnabled ( ) const
inline

在文件 perception_camera_updater.h56 行定义.

56{ return enabled_; }

◆ OnTimer()

void PerceptionCameraUpdater::OnTimer ( const std::string &  channel_name = "")

在文件 perception_camera_updater.cc139 行定义.

139 {
140 PublishMessage(channel_name);
141}
void PublishMessage(const std::string &channel_name="") override
Publish Message to dreamview frontend.

◆ PublishMessage()

void PerceptionCameraUpdater::PublishMessage ( const std::string &  channel_name = "")
overridevirtual

Publish Message to dreamview frontend.

实现了 apollo::dreamview::UpdaterBase.

在文件 perception_camera_updater.cc143 行定义.

143 {
144 std::string to_send;
145 // the channel has no data input, clear the sending object.
146 if (!channel_updaters_[channel_name]
147 ->perception_camera_reader_->HasWriter()) {
148 CameraChannelUpdater *updater = GetCameraChannelUpdater(channel_name);
149 updater->image_buffer_.clear();
150 updater->current_image_timestamp_ = 0.0;
151 updater->camera_update_.Clear();
152 to_send = "";
153 } else {
154 GetUpdate(&to_send, channel_name);
155 }
156 StreamData stream_data;
157 std::string stream_data_string;
158 stream_data.set_action("stream");
159 stream_data.set_data_name("camera");
160 stream_data.set_channel_name(channel_name);
161 std::vector<uint8_t> byte_data(to_send.begin(), to_send.end());
162 stream_data.set_data(&(byte_data[0]), byte_data.size());
163 stream_data.set_type("camera");
164 stream_data.SerializeToString(&stream_data_string);
165 websocket_->BroadcastBinaryData(stream_data_string);
166}
bool BroadcastBinaryData(const std::string &data, bool skippable=false)
Sends the provided binary data to all the connected clients.

◆ Start()

void PerceptionCameraUpdater::Start ( DvCallback  callback_api)

在文件 perception_camera_updater.cc73 行定义.

73 {
74 callback_api_ = callback_api;
75 enabled_ = true;
76 camera_update_.set_k_image_scale(kImageScale);
77}

◆ StartStream()

void PerceptionCameraUpdater::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.

在文件 perception_camera_updater.cc74 行定义.

76 {
77 if (channel_name.empty()) {
78 AERROR << "Failed to subscribe channel for channel is empty!";
79 return;
80 }
81 if (std::find(channels_.begin(), channels_.end(), channel_name) ==
82 channels_.end()) {
83 AERROR << "Failed to subscribe channel: " << channel_name
84 << " for channels_ not registered!";
85 return;
86 }
87 if (time_interval_ms > 0) {
88 CameraChannelUpdater *updater = GetCameraChannelUpdater(channel_name);
89 updater->enabled_ = true;
90 updater->timer_.reset(new cyber::Timer(
91 time_interval_ms,
92 [channel_name, this]() { this->OnTimer(channel_name); }, false));
93 updater->timer_->Start();
94 } else {
95 this->OnTimer(channel_name);
96 }
97}
void OnTimer(const std::string &channel_name="")

◆ Stop() [1/2]

void PerceptionCameraUpdater::Stop ( )

在文件 perception_camera_updater.cc79 行定义.

79 {
80 if (enabled_) {
81 localization_queue_.clear();
82 image_buffer_.clear();
83 tf_static_.clear();
84 current_image_timestamp_ = 0.0;
85 }
86 enabled_ = false;
87}

◆ Stop() [2/2]

void apollo::dreamview::PerceptionCameraUpdater::Stop ( )

◆ StopStream()

void PerceptionCameraUpdater::StopStream ( const std::string &  channel_name = "")
overridevirtual

Stop data flow.

实现了 apollo::dreamview::UpdaterBase.

在文件 perception_camera_updater.cc121 行定义.

121 {
122 if (channel_name.empty()) {
123 AERROR << "Failed to unsubscribe channel for channel is empty!";
124 return;
125 }
126 CameraChannelUpdater *updater = GetCameraChannelUpdater(channel_name);
127 if (updater->enabled_) {
128 if (updater->timer_) {
129 updater->timer_->Stop();
130 }
131 updater->localization_queue_.clear();
132 updater->image_buffer_.clear();
133 updater->current_image_timestamp_ = 0.0;
134 updater->camera_update_.Clear();
135 updater->enabled_ = false;
136 }
137}

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