Apollo  6.0
Open source self driving car software
base_cipv.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2021 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 
17 #pragma once
18 
19 #include <memory>
20 #include <string>
21 
22 #include "Eigen/Dense"
23 #include "Eigen/Eigen"
24 #include "Eigen/Geometry"
25 
26 #include "cyber/common/macros.h"
30 
31 namespace apollo {
32 namespace perception {
33 namespace camera {
34 
39  float average_frame_rate = 0.05f;
40  bool image_based_cipv = false;
41  int debug_level = 0;
42 };
43 
44 struct CipvOptions {
45  float velocity = 5.0f;
46  float yaw_rate = 0.0f;
47  float yaw_angle = 0.0f;
48 };
49 
50 class BaseCipv {
51  public:
52  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 
54  // Member functions
55  public:
56  BaseCipv() = default;
57  virtual ~BaseCipv() = default;
58 
59  virtual bool Init(const Eigen::Matrix3d &homography_im2car,
60  const CipvInitOptions &options = CipvInitOptions()) = 0;
61 
62  virtual bool Process(CameraFrame *frame,
63  const CipvOptions &options,
64  const Eigen::Affine3d &world2camera,
65  const base::MotionBufferPtr &motion_buffer) = 0;
66 
67  virtual std::string Name() const = 0;
68 
69  private:
71 }; // class BaseCipv
72 
74 #define PERCEPTION_REGISTER_CIPV(name) \
75  PERCEPTION_REGISTER_CLASS(BaseCipv, name)
76 
77 } // namespace camera
78 } // namespace perception
79 } // namespace apollo
PERCEPTION_REGISTER_REGISTERER(BaseCalibrationService)
Definition: base_init_options.h:24
Definition: camera_frame.h:33
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_cipv.h:50
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition: macros.h:48
int debug_level
Definition: base_cipv.h:41
float max_vehicle_width_in_meter
Definition: base_cipv.h:38
Definition: base_cipv.h:44
bool Init(const char *binary_name)
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:203
float average_frame_rate
Definition: base_cipv.h:39
float average_lane_width_in_meter
Definition: base_cipv.h:37
float min_laneline_length_for_cipv
Definition: base_cipv.h:36
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Eigen::Matrix3d Matrix3d
Definition: base_map_fwd.h:33
bool image_based_cipv
Definition: base_cipv.h:40