26 #include "Eigen/Dense" 27 #include "Eigen/Eigen" 28 #include "Eigen/Geometry" 37 namespace perception {
48 static constexpr uint32_t kMaxNumVirtualLanePoint = 25;
50 static constexpr
float kAverageFrameRate = 0.05f;
65 std::string
Name()
const override;
68 bool DetermineCipv(
const std::vector<base::LaneLine> &lane_objects,
71 std::vector<std::shared_ptr<base::Object>> *objects);
76 std::vector<std::shared_ptr<base::Object>> *objects);
79 const float velocity,
const float time_unit,
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);
89 const float offset_distance,
95 bool DistanceFromPointToLineSegment(
const Point2Df &point,
96 const Point2Df &line_seg_start_point,
101 bool GetEgoLane(
const std::vector<base::LaneLine> &lane_objects,
103 bool *b_left_valid,
bool *b_right_valid);
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,
110 bool CreateVirtualEgoLane(
const float yaw_rate,
const float velocity,
114 bool FindClosestObjectImage(
const std::shared_ptr<base::Object> &
object,
120 bool FindClosestObjectGround(
const std::shared_ptr<base::Object> &
object,
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);
133 bool IsObjectInTheLaneImage(
const std::shared_ptr<base::Object> &
object,
134 const EgoLane &egolane_image,
float *distance);
143 bool IsObjectInTheLaneGround(
const std::shared_ptr<base::Object> &
object,
146 const bool b_virtual,
float *distance);
149 bool IsObjectInTheLane(
const std::shared_ptr<base::Object> &
object,
153 const bool b_virtual,
float *distance);
156 bool IsPointLeftOfLine(
const Point2Df &point,
157 const Point2Df &line_seg_start_point,
158 const Point2Df &line_seg_end_point);
163 const float yaw_rate,
const float offset_distance,
167 bool TranformPoint(
const Eigen::VectorXf &in,
171 bool image2ground(
const float image_x,
const float image_y,
float *ground_x,
173 bool ground2image(
const float ground_x,
const float ground_y,
float *image_x,
177 bool b_image_based_cipv_ =
false;
178 int32_t debug_level_ = 0;
179 float time_unit_ = kAverageFrameRate;
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;
192 float max_dist_object_to_virtual_lane_in_meter_ =
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;
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_;
207 int32_t old_cipv_track_id_ = -2;
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
Definition: base_cipv.h:35
static bool MakeVirtualEgoLaneFromYawRate(const float yaw_rate, const float velocity, const float offset_distance, LaneLineSimple *left_lane_line, LaneLineSimple *right_lane_line)