23#include "opencv2/opencv.hpp"
25#include "modules/common_msgs/basic_msgs/geometry.pb.h"
26#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
27#include "modules/dreamview/proto/camera_update.pb.h"
41void ConvertMatrixToArray(
const Eigen::Matrix4d &matrix,
42 std::vector<double> *array) {
43 const double *pointer = matrix.data();
44 for (
int i = 0; i < matrix.size(); ++i) {
45 array->push_back(pointer[i]);
49template <
typename Po
int>
50void ConstructTransformationMatrix(
const Quaternion &quaternion,
51 const Point &translation,
52 Eigen::Matrix4d *matrix) {
53 matrix->setConstant(0);
55 q.x() = quaternion.qx();
56 q.
y() = quaternion.qy();
57 q.
z() = quaternion.qz();
58 q.
w() = quaternion.qw();
59 matrix->block<3, 3>(0, 0) = q.normalized().toRotationMatrix();
60 (*matrix)(0, 3) = translation.
x();
61 (*matrix)(1, 3) = translation.y();
62 (*matrix)(2, 3) = translation.z();
68 : UpdaterWithChannelsBase({
"drivers.Image"}, {
""}),
69 websocket_(websocket),
70 node_(cyber::CreateNode(
"perception_camera_updater")) {
74void PerceptionCameraUpdater::StartStream(
const double &time_interval_ms,
75 const std::string &channel_name,
76 nlohmann::json *subscribe_param) {
77 if (channel_name.empty()) {
78 AERROR <<
"Failed to subscribe channel for channel is empty!";
81 if (std::find(channels_.begin(), channels_.end(), channel_name) ==
83 AERROR <<
"Failed to subscribe channel: " << channel_name
84 <<
" for channels_ not registered!";
87 if (time_interval_ms > 0) {
92 [channel_name,
this]() { this->OnTimer(channel_name); },
false));
95 this->OnTimer(channel_name);
100 const std::string &channel_name) {
101 std::lock_guard<std::mutex> lck(channel_updater_map_mutex_);
102 if (channel_updaters_.find(channel_name) == channel_updaters_.end()) {
104 channel_updaters_[channel_name]->perception_camera_reader_ =
107 [channel_name,
this](
const std::shared_ptr<drivers::Image> &image) {
108 OnImage(image, channel_name);
111 channel_updaters_[channel_name]->perception_obstacle_reader_ =
112 GetObstacleReader(channel_name);
114 return channel_updaters_[channel_name];
117void PerceptionCameraUpdater::Stop() {
118 channel_updaters_.clear();
121void PerceptionCameraUpdater::StopStream(
const std::string &channel_name) {
122 if (channel_name.empty()) {
123 AERROR <<
"Failed to unsubscribe channel for channel is empty!";
139void PerceptionCameraUpdater::OnTimer(
const std::string &channel_name) {
140 PublishMessage(channel_name);
143void PerceptionCameraUpdater::PublishMessage(
const std::string &channel_name) {
146 if (!channel_updaters_[channel_name]
147 ->perception_camera_reader_->HasWriter()) {
154 GetUpdate(&to_send, channel_name);
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);
168void PerceptionCameraUpdater::GetImageLocalization(
169 std::vector<double> *localization,
const std::string &channel_name) {
178 double timestamp_diff = std::numeric_limits<double>::max();
181 const double tmp_diff =
185 timestamp_diff = tmp_diff;
195 if (tmp_diff < std::fabs(timestamp_diff)) {
202 Eigen::Matrix4d localization_matrix;
203 ConstructTransformationMatrix(image_pos.orientation(), image_pos.position(),
204 &localization_matrix);
205 ConvertMatrixToArray(localization_matrix, localization);
208bool PerceptionCameraUpdater::QueryStaticTF(
const std::string &frame_id,
209 const std::string &child_frame_id,
210 Eigen::Matrix4d *matrix) {
211 TransformStamped transform;
212 if (tf_buffer_->GetLatestStaticTF(frame_id, child_frame_id, &transform)) {
213 ConstructTransformationMatrix(transform.transform().rotation(),
214 transform.transform().translation(), matrix);
220void PerceptionCameraUpdater::GetLocalization2CameraTF(
221 std::vector<double> *localization2camera_tf) {
222 Eigen::Matrix4d localization2camera_mat = Eigen::Matrix4d::Identity();
228 Eigen::Matrix4d loc2novatel_mat;
229 if (QueryStaticTF(
"localization",
"novatel", &loc2novatel_mat)) {
230 localization2camera_mat *= loc2novatel_mat;
233 Eigen::Matrix4d novatel2lidar_mat;
234 if (QueryStaticTF(
"novatel",
"velodyne128", &novatel2lidar_mat)) {
235 localization2camera_mat *= novatel2lidar_mat;
238 Eigen::Matrix4d lidar2camera_mat;
239 if (QueryStaticTF(
"velodyne128",
"front_6mm", &lidar2camera_mat)) {
240 localization2camera_mat *= lidar2camera_mat;
243 ConvertMatrixToArray(localization2camera_mat, localization2camera_tf);
287void PerceptionCameraUpdater::OnImage(
288 const std::shared_ptr<apollo::drivers::Image> &image,
289 const std::string& channel_name) {
290 CameraChannelUpdater* updater = GetCameraChannelUpdater(channel_name);
291 if (!updater->enabled_) {
294 cv::Mat mat(image->height(), image->width(), CV_8UC3,
295 const_cast<char *
>(image->data().data()), image->step());
296 cv::cvtColor(mat, mat, cv::COLOR_RGB2BGR);
298 cv::Size(
static_cast<int>(image->width() * kImageScale),
299 static_cast<int>(image->height() * kImageScale)),
300 0, 0, cv::INTER_LINEAR);
301 cv::imencode(
".jpg", mat, updater->image_buffer_, std::vector<int>());
302 double next_image_timestamp;
303 if (image->has_measurement_time()) {
304 next_image_timestamp = image->measurement_time();
306 next_image_timestamp = image->header().timestamp_sec();
308 std::lock_guard<std::mutex> lock(updater->image_mutex_);
309 if (next_image_timestamp < updater->current_image_timestamp_) {
310 updater->localization_queue_.clear();
312 updater->current_image_timestamp_ = next_image_timestamp;
313 updater->camera_update_.set_image(&(updater->image_buffer_[0]),
314 updater->image_buffer_.size());
315 updater->camera_update_.set_k_image_scale(kImageScale);
318void PerceptionCameraUpdater::OnLocalization(
319 const std::shared_ptr<LocalizationEstimate> &localization) {
320 for (
auto iter = channel_updaters_.begin(); iter != channel_updaters_.end();
322 if (iter->second->enabled_) {
323 std::lock_guard<std::mutex> lock(iter->second->localization_mutex_);
324 iter->second->localization_queue_.push_back(localization);
329void PerceptionCameraUpdater::OnObstacles(
330 const std::shared_ptr<apollo::perception::PerceptionObstacles> &obstacles,
331 const std::string &channel_name) {
332 CameraChannelUpdater *updater = GetCameraChannelUpdater(channel_name);
333 perception_obstacle_enable_ =
true;
334 std::lock_guard<std::mutex> lock(updater->obstacle_mutex_);
335 updater->bbox2ds.clear();
336 updater->obstacle_id.clear();
337 updater->obstacle_sub_type.clear();
338 for (
const auto &obstacle : obstacles->perception_obstacle()) {
339 updater->bbox2ds.push_back(obstacle.bbox2d());
340 updater->obstacle_id.push_back(obstacle.id());
341 updater->obstacle_sub_type.push_back(obstacle.sub_type());
345void PerceptionCameraUpdater::InitReaders() {
346 node_->CreateReader<LocalizationEstimate>(
347 FLAGS_localization_topic,
348 [
this](
const std::shared_ptr<LocalizationEstimate> &localization) {
349 OnLocalization(localization);
353void PerceptionCameraUpdater::GetUpdate(std::string *camera_update,
354 const std::string &channel_name) {
356 std::vector<double> localization;
357 GetImageLocalization(&localization, channel_name);
361 std::lock_guard<std::mutex> lock1(updater->
image_mutex_, std::adopt_lock);
366 *(updater->
camera_update_).mutable_localization() = {localization.begin(),
368 std::vector<double> localization2camera_tf;
369 GetLocalization2CameraTF(&localization2camera_tf);
371 localization2camera_tf.begin(), localization2camera_tf.end()};
374 if (perception_obstacle_enable_) {
385void PerceptionCameraUpdater::GetChannelMsg(
386 std::vector<std::string> *channels) {
387 GetChannelMsgWithFilter(channels);
390std::shared_ptr<cyber::Reader<apollo::perception::PerceptionObstacles>>
391PerceptionCameraUpdater::GetObstacleReader(
const std::string &channel_name) {
395 size_t camera_string_end_pos = channel_name.find_last_of(
"/");
396 size_t camera_string_start_pos =
397 channel_name.find_last_of(
"/", camera_string_end_pos - 1);
398 std::string camera_name =
399 channel_name.substr(camera_string_start_pos + 1,
400 camera_string_end_pos - camera_string_start_pos - 1);
401 std::string perception_obstacle_channel =
402 "/apollo/prediction/perception_obstacles_" + camera_name;
403 auto channel_manager =
404 apollo::cyber::service_discovery::TopologyManager::Instance()
406 std::shared_ptr<cyber::Reader<apollo::perception::PerceptionObstacles>>
407 perception_obstacle_reader;
409 if (!channel_manager->HasWriter(perception_obstacle_channel)) {
410 perception_obstacle_reader =
412 FLAGS_perception_obstacle_topic,
413 [channel_name,
this](
414 const std::shared_ptr<apollo::perception::PerceptionObstacles>
415 &obstacles) { OnObstacles(obstacles, channel_name); });
418 perception_obstacle_reader =
420 perception_obstacle_channel,
421 [channel_name,
this](
422 const std::shared_ptr<apollo::perception::PerceptionObstacles>
423 &obstacles) { OnObstacles(obstacles, channel_name); });
425 return perception_obstacle_reader;
Used to perform oneshot or periodic timing tasks
PerceptionCameraUpdater(WebSocketHandler *websocket)
std::vector< apollo::perception::BBox2D > bbox2ds
CameraUpdate camera_update_
std::vector< uint8_t > image_buffer_
std::mutex localization_mutex_
std::deque< std::shared_ptr< apollo::localization::LocalizationEstimate > > localization_queue_
std::vector< int32_t > obstacle_sub_type
std::unique_ptr< cyber::Timer > timer_
std::mutex obstacle_mutex_
std::vector< int32_t > obstacle_id
double current_image_timestamp_