Apollo  6.0
Open source self driving car software
cipv_camera.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2019 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 <array>
20 #include <map>
21 #include <memory>
22 #include <string>
23 #include <utility>
24 #include <vector>
25 
26 #include "Eigen/Dense"
27 #include "Eigen/Eigen"
28 #include "Eigen/Geometry"
29 
35 
36 namespace apollo {
37 namespace perception {
38 namespace camera {
39 
40 constexpr float kMinVelocity = 10.0f; // in m/s
41 constexpr float kMaxDistObjectToLaneInMeter = 70.0f;
42 constexpr float kMaxDistObjectToVirtualLaneInMeter = 10.0f;
43 constexpr float kMaxDistObjectToLaneInPixel = 10.0f;
44 const std::size_t kDropsHistorySize = 20;
45 const std::size_t kMaxObjectNum = 100;
46 const std::size_t kMaxAllowedSkipObject = 10;
47 
48 static constexpr uint32_t kMaxNumVirtualLanePoint = 25;
49 // TODO(All) average image frame rate should come from other header file.
50 static constexpr float kAverageFrameRate = 0.05f;
51 
52 class Cipv : public BaseCipv {
53  public:
54  Cipv() = default;
55  ~Cipv() = default;
56 
57  bool Init(const Eigen::Matrix3d &homography_im2car,
58  const CipvInitOptions &options = CipvInitOptions()) override;
59 
60  bool Process(CameraFrame *frame,
61  const CipvOptions &options,
62  const Eigen::Affine3d &world2camera,
63  const base::MotionBufferPtr &motion_buffer) override;
64 
65  std::string Name() const override;
66 
67  // Determine CIPV among multiple objects
68  bool DetermineCipv(const std::vector<base::LaneLine> &lane_objects,
69  const CipvOptions &options,
70  const Eigen::Affine3d &world2camera,
71  std::vector<std::shared_ptr<base::Object>> *objects);
72 
73  // Collect drops for tailgating
74  bool CollectDrops(const base::MotionBufferPtr &motion_buffer,
75  const Eigen::Affine3d &world2camera,
76  std::vector<std::shared_ptr<base::Object>> *objects);
77 
78  static float VehicleDynamics(const uint32_t tick, const float yaw_rate,
79  const float velocity, const float time_unit,
80  float *x, float *y);
81  static float VehicleDynamics(const uint32_t tick, const float yaw_rate,
82  const float velocity, const float time_unit,
83  const float vehicle_half_width, float *center_x,
84  float *ceneter_y, float *left_x, float *left_y,
85  float *right_x, float *right_y);
86  // Make a virtual lane line using a yaw_rate
87  static bool MakeVirtualEgoLaneFromYawRate(const float yaw_rate,
88  const float velocity,
89  const float offset_distance,
90  LaneLineSimple *left_lane_line,
91  LaneLineSimple *right_lane_line);
92 
93  private:
94  // Distance from a point to a line segment
95  bool DistanceFromPointToLineSegment(const Point2Df &point,
96  const Point2Df &line_seg_start_point,
97  const Point2Df &line_seg_end_point,
98  float *distance);
99 
100  // Determine CIPV among multiple objects
101  bool GetEgoLane(const std::vector<base::LaneLine> &lane_objects,
102  EgoLane *egolane_image, EgoLane *egolane_ground,
103  bool *b_left_valid, bool *b_right_valid);
104 
105  // Elongate lane line
106  bool ElongateEgoLane(const std::vector<base::LaneLine> &lane_objects,
107  const bool b_left_valid, const bool b_right_valid,
108  const float yaw_rate, const float velocity,
109  EgoLane *egolane_image, EgoLane *egolane_ground);
110  bool CreateVirtualEgoLane(const float yaw_rate, const float velocity,
111  EgoLane *egolane_ground);
112 
113  // Get closest edge of an object in image coordinate
114  bool FindClosestObjectImage(const std::shared_ptr<base::Object> &object,
115  const EgoLane &egolane_image,
116  LineSegment2Df *closted_object_edge,
117  float *distance);
118 
119  // Get closest edge of an object in ground coordinate
120  bool FindClosestObjectGround(const std::shared_ptr<base::Object> &object,
121  const EgoLane &egolane_ground,
122  const Eigen::Affine3d world2camera,
123  LineSegment2Df *closted_object_edge,
124  float *distance);
125 
126  // Check if the distance between lane and object are OK
127  bool AreDistancesSane(const float distance_start_point_to_right_lane,
128  const float distance_start_point_to_left_lane,
129  const float distance_end_point_to_right_lane,
130  const float distance_end_point_to_left_lane);
131 
132  // Check if the object is in the lane in image space
133  bool IsObjectInTheLaneImage(const std::shared_ptr<base::Object> &object,
134  const EgoLane &egolane_image, float *distance);
135  // Check if the object is in the lane in ego-ground space
136  // | |
137  // | *------* |
138  // | *-+-----*
139  // | | *--------* <- closest edge of object
140  // *+------* |
141  // | |
142  // l_lane r_lane
143  bool IsObjectInTheLaneGround(const std::shared_ptr<base::Object> &object,
144  const EgoLane &egolane_ground,
145  const Eigen::Affine3d world2camera,
146  const bool b_virtual, float *distance);
147 
148  // Check if the object is in the lane in ego-ground space
149  bool IsObjectInTheLane(const std::shared_ptr<base::Object> &object,
150  const EgoLane &egolane_image,
151  const EgoLane &egolane_ground,
152  const Eigen::Affine3d world2camera,
153  const bool b_virtual, float *distance);
154 
155  // Check if a point is left of a line segment
156  bool IsPointLeftOfLine(const Point2Df &point,
157  const Point2Df &line_seg_start_point,
158  const Point2Df &line_seg_end_point);
159 
160  // Make a virtual lane line using a reference lane line and its offset
161  // distance
162  bool MakeVirtualLane(const LaneLineSimple &ref_lane_line,
163  const float yaw_rate, const float offset_distance,
164  LaneLineSimple *virtual_lane_line);
165 
166  // transform point to another using motion
167  bool TranformPoint(const Eigen::VectorXf &in,
168  const Eigen::Matrix4f &motion_matrix,
169  Eigen::Vector3d *out);
170 
171  bool image2ground(const float image_x, const float image_y, float *ground_x,
172  float *ground_y);
173  bool ground2image(const float ground_x, const float ground_y, float *image_x,
174  float *image_y);
175 
176  // Member variables
177  bool b_image_based_cipv_ = false;
178  int32_t debug_level_ = 0;
179  float time_unit_ = kAverageFrameRate;
180 
181  float min_laneline_length_for_cipv_ = kMinLaneLineLengthForCIPV;
182  float average_lane_width_in_meter_ = kAverageLaneWidthInMeter;
183  float max_vehicle_width_in_meter_ = kMaxVehicleWidthInMeter;
184  float margin_vehicle_to_lane_ =
186  float single_virtual_egolane_width_in_meter_ =
188  float half_virtual_egolane_width_in_meter_ =
189  single_virtual_egolane_width_in_meter_ * 0.5f;
190  float half_vehicle_width_in_meter_ = kMaxVehicleWidthInMeter * 0.5f;
191  float max_dist_object_to_lane_in_meter_ = kMaxDistObjectToLaneInMeter;
192  float max_dist_object_to_virtual_lane_in_meter_ =
194  float max_dist_object_to_lane_in_pixel_ = kMaxDistObjectToLaneInPixel;
195  float MAX_VEHICLE_WIDTH_METER = 5.0f;
196  float EPSILON = 1.0e-6f;
197  std::size_t kDropsHistorySize = 100;
198  std::size_t kMaxObjectNum = 100;
199  std::size_t kMaxAllowedSkipObject = 10;
200 
201  std::map<int, size_t> object_id_skip_count_;
202  std::map<int, boost::circular_buffer<std::pair<float, float>>>
203  object_trackjectories_;
204  std::map<int, std::vector<double>> object_timestamps_;
205  Eigen::Matrix3d homography_im2car_ = Eigen::Matrix3d::Identity();
206  Eigen::Matrix3d homography_car2im_ = Eigen::Matrix3d::Identity();
207  int32_t old_cipv_track_id_ = -2;
208 };
209 
210 } // namespace camera
211 } // namespace perception
212 } // namespace apollo
static float VehicleDynamics(const uint32_t tick, const float yaw_rate, const float velocity, const float time_unit, float *x, float *y)
bool Init(const Eigen::Matrix3d &homography_im2car, const CipvInitOptions &options=CipvInitOptions()) override
constexpr float kMinVelocity
Definition: cipv_camera.h:40
Definition: camera_frame.h:33
Definition: lane_struct_for_calib.h:51
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: cipv_camera.h:52
Definition: base_cipv.h:50
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
constexpr float kMaxDistObjectToLaneInMeter
Definition: cipv_camera.h:41
constexpr uint32_t kMinLaneLineLengthForCIPV
Definition: lane_object.h:35
Definition: base_cipv.h:44
bool CollectDrops(const base::MotionBufferPtr &motion_buffer, const Eigen::Affine3d &world2camera, std::vector< std::shared_ptr< base::Object >> *objects)
Eigen::Matrix4f Matrix4f
Definition: base_map_fwd.h:26
Eigen::Vector2f Point2Df
Definition: lane_object.h:51
std::string Name() const override
bool Process(CameraFrame *frame, const CipvOptions &options, const Eigen::Affine3d &world2camera, const base::MotionBufferPtr &motion_buffer) override
constexpr float kMaxDistObjectToVirtualLaneInMeter
Definition: cipv_camera.h:42
constexpr float kAverageLaneWidthInMeter
Definition: lane_object.h:37
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:203
bool DetermineCipv(const std::vector< base::LaneLine > &lane_objects, const CipvOptions &options, const Eigen::Affine3d &world2camera, std::vector< std::shared_ptr< base::Object >> *objects)
constexpr float kMaxDistObjectToLaneInPixel
Definition: cipv_camera.h:43
Definition: lane_object.h:64
Definition: lane_object.h:55
const std::size_t kDropsHistorySize
Definition: cipv_camera.h:44
const std::size_t kMaxObjectNum
Definition: cipv_camera.h:45
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Eigen::Matrix3d Matrix3d
Definition: base_map_fwd.h:33
constexpr float kMaxVehicleWidthInMeter
Definition: lane_object.h:39
const std::size_t kMaxAllowedSkipObject
Definition: cipv_camera.h:46
constexpr float kMarginVehicleToLane
Definition: lane_object.h:41
static bool MakeVirtualEgoLaneFromYawRate(const float yaw_rate, const float velocity, const float offset_distance, LaneLineSimple *left_lane_line, LaneLineSimple *right_lane_line)