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