Apollo  6.0
Open source self driving car software
camera_perception_viz_message.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 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 <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "cyber/cyber.h"
23 #include "modules/common/proto/error_code.pb.h"
28 #include "modules/perception/proto/perception_obstacle.pb.h"
29 
30 namespace apollo {
31 namespace perception {
32 namespace onboard {
33 
35  public:
36  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37 
38  public:
39  CameraPerceptionVizMessage() { type_name_ = "CameraPerceptionVizMessage"; }
40  ~CameraPerceptionVizMessage() = default;
41 
43  delete;
44 
45  std::string GetTypeName() const { return type_name_; }
46 
48  return new CameraPerceptionVizMessage;
49  }
50 
52  const std::string& camera_name, const double msg_timestamp,
53  const Eigen::Matrix4d& pose_camera_to_world,
54  const std::shared_ptr<base::Blob<uint8_t>>& image_blob,
55  const std::vector<base::ObjectPtr>& camera_objects,
56  const std::vector<base::LaneLine>& lane_objects,
57  const apollo::common::ErrorCode& error_code);
58 
59  public:
60  std::string camera_name_;
61  std::string type_name_;
62  double msg_timestamp_ = 0.0;
63 
65  std::shared_ptr<base::Blob<uint8_t>> image_blob_;
66  std::vector<base::ObjectConstPtr> camera_objects_;
67  std::vector<base::LaneLine> lane_objects_;
68  apollo::common::ErrorCode error_code_ = apollo::common::ErrorCode::OK;
69 };
70 
71 } // namespace onboard
72 } // namespace perception
73 } // namespace apollo
CameraPerceptionVizMessage & operator=(const CameraPerceptionVizMessage &)=delete
Definition: camera_perception_viz_message.h:34
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::vector< base::ObjectConstPtr > camera_objects_
Definition: camera_perception_viz_message.h:66
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
std::string type_name_
Definition: camera_perception_viz_message.h:61
double msg_timestamp_
Definition: camera_perception_viz_message.h:62
std::shared_ptr< base::Blob< uint8_t > > image_blob_
Definition: camera_perception_viz_message.h:65
CameraPerceptionVizMessage * New() const
Definition: camera_perception_viz_message.h:47
std::string camera_name_
Definition: camera_perception_viz_message.h:60
std::vector< base::LaneLine > lane_objects_
Definition: camera_perception_viz_message.h:67
bool OK()
Definition: state.h:44
Eigen::Matrix4d pose_camera_to_world_
Definition: camera_perception_viz_message.h:64
std::string GetTypeName() const
Definition: camera_perception_viz_message.h:45
CameraPerceptionVizMessage()
Definition: camera_perception_viz_message.h:39
apollo::common::ErrorCode error_code_
Definition: camera_perception_viz_message.h:68