Apollo  6.0
Open source self driving car software
multi_camera_projection.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 <map>
19 #include <string>
20 #include <vector>
21 
26 
27 namespace apollo {
28 namespace perception {
29 namespace camera {
30 
31 struct ProjectOption {
32  explicit ProjectOption(const std::string& name) : camera_name(name) {}
33  std::string camera_name;
34 };
35 
37  std::vector<std::string> camera_names;
38 };
39 
40 // @brief Camera Projection project the Light into the image.
42  public:
44 
45  ~MultiCamerasProjection() = default;
46  bool Init(const MultiCamerasInitOption& options);
47  bool Project(const CarPose& pose, const ProjectOption& option,
48  base::TrafficLight* light) const;
49  bool HasCamera(const std::string& camera_name) const;
50 
51  int getImageWidth(const std::string& camera_name) const;
52  int getImageHeight(const std::string& camera_name) const;
53 
54  const std::vector<std::string>& getCameraNamesByDescendingFocalLen() const {
55  return camera_names_;
56  }
57 
58  private:
59  bool BoundaryBasedProject(
60  const base::BrownCameraDistortionModelPtr camera_model,
61  const Eigen::Matrix4d& c2w_pose,
62  const std::vector<base::PointXYZID>& point,
63  base::TrafficLight* light) const;
64 
65  private:
66  // sorted by focal length in descending order
67  std::vector<std::string> camera_names_;
68  // camera_name -> camera_model
69  std::map<std::string, base::BrownCameraDistortionModelPtr> camera_models_;
70 };
71 
72 } // namespace camera
73 } // namespace perception
74 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::shared_ptr< BrownCameraDistortionModel > BrownCameraDistortionModelPtr
Definition: distortion_model.h:89
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
Definition: traffic_light.h:79
Definition: multi_camera_projection.h:41
std::string camera_name
Definition: multi_camera_projection.h:33
const std::vector< std::string > & getCameraNamesByDescendingFocalLen() const
Definition: multi_camera_projection.h:54
ProjectOption(const std::string &name)
Definition: multi_camera_projection.h:32
Definition: multi_camera_projection.h:31
Definition: multi_camera_projection.h:36
std::vector< std::string > camera_names
Definition: multi_camera_projection.h:37
MultiCamerasProjection()
Definition: multi_camera_projection.h:43
bool Init(const char *binary_name)